#include <robot_state.h>
Public Member Functions | |
| void | finishedReading () |
| double | getAnalogInput0 () |
| double | getAnalogInput1 () |
| char | getAnalogInputRange0 () |
| char | getAnalogInputRange1 () |
| double | getAnalogOutput0 () |
| double | getAnalogOutput1 () |
| char | getAnalogOutputDomain0 () |
| char | getAnalogOutputDomain1 () |
| int | getDigitalInputBits () |
| int | getDigitalOutputBits () |
| char | getEuromap67InterfaceInstalled () |
| float | getEuromapCurrent () |
| int | getEuromapInputBits () |
| int | getEuromapOutputBits () |
| float | getEuromapVoltage () |
| unsigned char | getInReducedMode () |
| float | getMasterBoardTemperature () |
| float | getMasterIOCurrent () |
| bool | getNewDataAvailable () |
| std::vector< double > | getQTarget () |
| float | getRobotCurrent () |
| unsigned char | getRobotMode () |
| float | getRobotVoltage48V () |
| unsigned char | getSafetyMode () |
| double | getTime () |
| std::vector< double > | getVActual () |
| double | getVersion () |
| bool | isEmergencyStopped () |
| bool | isPowerOnRobot () |
| bool | isProgramPaused () |
| bool | isProgramRunning () |
| bool | isProtectiveStopped () |
| bool | isReady () |
| bool | isRealRobotEnabled () |
| bool | isRobotConnected () |
| RobotState (std::condition_variable &msg_cond) | |
| void | setDisconnected () |
| void | unpack (uint8_t *buf, unsigned int buf_length) |
| void | unpackRobotMessage (uint8_t *buf, unsigned int offset, uint32_t len) |
| void | unpackRobotMessageVersion (uint8_t *buf, unsigned int offset, uint32_t len) |
| void | unpackRobotMode (uint8_t *buf, unsigned int offset) |
| void | unpackRobotState (uint8_t *buf, unsigned int offset, uint32_t len) |
| void | unpackRobotStateMasterboard (uint8_t *buf, unsigned int offset) |
| ~RobotState () | |
Private Member Functions | |
| double | ntohd (uint64_t nf) |
Private Attributes | |
| masterboard_data | mb_data_ |
| bool | new_data_available_ |
| std::condition_variable * | pMsg_cond_ |
| robot_mode_data | robot_mode_ |
| unsigned char | robot_mode_running_ |
| std::recursive_mutex | val_lock_ |
| version_message | version_msg_ |
Definition at line 151 of file robot_state.h.
| RobotState::RobotState | ( | std::condition_variable & | msg_cond | ) |
Definition at line 21 of file robot_state.cpp.
| void RobotState::finishedReading | ( | ) |
Definition at line 325 of file robot_state.cpp.
| double RobotState::getAnalogInput0 | ( | ) |
Definition at line 339 of file robot_state.cpp.
| double RobotState::getAnalogInput1 | ( | ) |
Definition at line 342 of file robot_state.cpp.
| char RobotState::getAnalogInputRange0 | ( | ) |
| char RobotState::getAnalogInputRange1 | ( | ) |
| double RobotState::getAnalogOutput0 | ( | ) |
Definition at line 345 of file robot_state.cpp.
| double RobotState::getAnalogOutput1 | ( | ) |
Definition at line 349 of file robot_state.cpp.
| char RobotState::getAnalogOutputDomain0 | ( | ) |
| char RobotState::getAnalogOutputDomain1 | ( | ) |
| int RobotState::getDigitalInputBits | ( | ) |
Definition at line 333 of file robot_state.cpp.
| int RobotState::getDigitalOutputBits | ( | ) |
Definition at line 336 of file robot_state.cpp.
| float RobotState::getEuromapCurrent | ( | ) |
| int RobotState::getEuromapInputBits | ( | ) |
| int RobotState::getEuromapOutputBits | ( | ) |
| float RobotState::getEuromapVoltage | ( | ) |
| unsigned char RobotState::getInReducedMode | ( | ) |
| float RobotState::getMasterBoardTemperature | ( | ) |
| float RobotState::getMasterIOCurrent | ( | ) |
| bool RobotState::getNewDataAvailable | ( | ) |
Definition at line 329 of file robot_state.cpp.
| std::vector<double> RobotState::getQTarget | ( | ) |
| float RobotState::getRobotCurrent | ( | ) |
| unsigned char RobotState::getRobotMode | ( | ) |
Definition at line 373 of file robot_state.cpp.
| float RobotState::getRobotVoltage48V | ( | ) |
| unsigned char RobotState::getSafetyMode | ( | ) |
| double RobotState::getTime | ( | ) |
| std::vector<double> RobotState::getVActual | ( | ) |
| double RobotState::getVersion | ( | ) |
Definition at line 315 of file robot_state.cpp.
| bool RobotState::isEmergencyStopped | ( | ) |
Definition at line 361 of file robot_state.cpp.
| bool RobotState::isPowerOnRobot | ( | ) |
Definition at line 358 of file robot_state.cpp.
| bool RobotState::isProgramPaused | ( | ) |
Definition at line 370 of file robot_state.cpp.
| bool RobotState::isProgramRunning | ( | ) |
Definition at line 367 of file robot_state.cpp.
| bool RobotState::isProtectiveStopped | ( | ) |
Definition at line 364 of file robot_state.cpp.
| bool RobotState::isReady | ( | ) |
Definition at line 376 of file robot_state.cpp.
| bool RobotState::isRealRobotEnabled | ( | ) |
Definition at line 355 of file robot_state.cpp.
| bool RobotState::isRobotConnected | ( | ) |
Definition at line 352 of file robot_state.cpp.
| double RobotState::ntohd | ( | uint64_t | nf | ) | [private] |
Definition at line 29 of file robot_state.cpp.
| void RobotState::setDisconnected | ( | ) |
Definition at line 383 of file robot_state.cpp.
| void RobotState::unpack | ( | uint8_t * | buf, |
| unsigned int | buf_length | ||
| ) |
Definition at line 35 of file robot_state.cpp.
| void RobotState::unpackRobotMessage | ( | uint8_t * | buf, |
| unsigned int | offset, | ||
| uint32_t | len | ||
| ) |
Definition at line 65 of file robot_state.cpp.
| void RobotState::unpackRobotMessageVersion | ( | uint8_t * | buf, |
| unsigned int | offset, | ||
| uint32_t | len | ||
| ) |
Definition at line 123 of file robot_state.cpp.
| void RobotState::unpackRobotMode | ( | uint8_t * | buf, |
| unsigned int | offset | ||
| ) |
Definition at line 149 of file robot_state.cpp.
| void RobotState::unpackRobotState | ( | uint8_t * | buf, |
| unsigned int | offset, | ||
| uint32_t | len | ||
| ) |
Definition at line 91 of file robot_state.cpp.
| void RobotState::unpackRobotStateMasterboard | ( | uint8_t * | buf, |
| unsigned int | offset | ||
| ) |
Definition at line 212 of file robot_state.cpp.
masterboard_data RobotState::mb_data_ [private] |
Definition at line 154 of file robot_state.h.
bool RobotState::new_data_available_ [private] |
Definition at line 160 of file robot_state.h.
std::condition_variable* RobotState::pMsg_cond_ [private] |
Definition at line 159 of file robot_state.h.
robot_mode_data RobotState::robot_mode_ [private] |
Definition at line 155 of file robot_state.h.
unsigned char RobotState::robot_mode_running_ [private] |
Definition at line 161 of file robot_state.h.
std::recursive_mutex RobotState::val_lock_ [private] |
Definition at line 157 of file robot_state.h.
version_message RobotState::version_msg_ [private] |
Definition at line 153 of file robot_state.h.