#include <robot_state.h>
Public Member Functions | |
bool | getControllerUpdated () |
bool | getDataPublished () |
double | getEndSpeed () |
std::vector< double > | getJointCurrent () |
std::vector< double > | getJointTemperatures () |
std::vector< double > | getJointVoltage () |
std::vector< double > | getJonitPosition () |
std::vector< double > | getJonitVelocity () |
std::vector< double > | getTcpForce () |
std::vector< double > | getToolOrientation () |
std::vector< double > | getToolPosition () |
RobotState (std::condition_variable &msg_cond) | |
void | setControllerUpdated () |
void | setDataPublished () |
void | unpack (uint8_t *buf) |
~RobotState () | |
Private Attributes | |
bool | controller_updated_ |
bool | data_published_ |
double | end_speed_actual_ |
std::vector< double > | joint_current_actual_ |
std::vector< double > | joint_position_actual_ |
std::vector< double > | joint_temperatures_actual_ |
std::vector< double > | joint_velocity_actual_ |
std::vector< double > | joint_voltage_actual_ |
std::condition_variable * | pMsg_cond_ |
std::vector< double > | tcp_force_actual_ |
std::vector< double > | tool_orientation_actual_ |
std::vector< double > | tool_position_actual_ |
std::mutex | val_lock_ |
Definition at line 12 of file robot_state.h.
RobotState::RobotState | ( | std::condition_variable & | msg_cond | ) |
Definition at line 5 of file robot_state.cpp.
Definition at line 20 of file robot_state.cpp.
bool RobotState::getControllerUpdated | ( | ) |
Definition at line 37 of file robot_state.cpp.
bool RobotState::getDataPublished | ( | ) |
Definition at line 30 of file robot_state.cpp.
double RobotState::getEndSpeed | ( | ) |
Definition at line 104 of file robot_state.cpp.
std::vector< double > RobotState::getJointCurrent | ( | ) |
Definition at line 80 of file robot_state.cpp.
std::vector< double > RobotState::getJointTemperatures | ( | ) |
Definition at line 73 of file robot_state.cpp.
std::vector< double > RobotState::getJointVoltage | ( | ) |
Definition at line 87 of file robot_state.cpp.
std::vector< double > RobotState::getJonitPosition | ( | ) |
Definition at line 41 of file robot_state.cpp.
std::vector< double > RobotState::getJonitVelocity | ( | ) |
Definition at line 50 of file robot_state.cpp.
std::vector< double > RobotState::getTcpForce | ( | ) |
Definition at line 96 of file robot_state.cpp.
std::vector< double > RobotState::getToolOrientation | ( | ) |
Definition at line 66 of file robot_state.cpp.
std::vector< double > RobotState::getToolPosition | ( | ) |
Definition at line 58 of file robot_state.cpp.
void RobotState::setControllerUpdated | ( | ) |
Definition at line 34 of file robot_state.cpp.
void RobotState::setDataPublished | ( | ) |
Definition at line 27 of file robot_state.cpp.
void RobotState::unpack | ( | uint8_t * | buf | ) |
Definition at line 112 of file robot_state.cpp.
bool RobotState::controller_updated_ [private] |
Definition at line 30 of file robot_state.h.
bool RobotState::data_published_ [private] |
Definition at line 29 of file robot_state.h.
double RobotState::end_speed_actual_ [private] |
Definition at line 23 of file robot_state.h.
std::vector<double> RobotState::joint_current_actual_ [private] |
Definition at line 19 of file robot_state.h.
std::vector<double> RobotState::joint_position_actual_ [private] |
Definition at line 14 of file robot_state.h.
std::vector<double> RobotState::joint_temperatures_actual_ [private] |
Definition at line 18 of file robot_state.h.
std::vector<double> RobotState::joint_velocity_actual_ [private] |
Definition at line 15 of file robot_state.h.
std::vector<double> RobotState::joint_voltage_actual_ [private] |
Definition at line 20 of file robot_state.h.
std::condition_variable* RobotState::pMsg_cond_ [private] |
Definition at line 28 of file robot_state.h.
std::vector<double> RobotState::tcp_force_actual_ [private] |
Definition at line 21 of file robot_state.h.
std::vector<double> RobotState::tool_orientation_actual_ [private] |
Definition at line 17 of file robot_state.h.
std::vector<double> RobotState::tool_position_actual_ [private] |
Definition at line 16 of file robot_state.h.
std::mutex RobotState::val_lock_ [private] |
Definition at line 26 of file robot_state.h.