#include <arm_state.h>
Public Member Functions | |
const std::string & | getArmName () const |
const sensor_msgs::JointState & | getJointStates () const |
void | replaceJointPositions (sensor_msgs::JointState &state) const |
Static Public Member Functions | |
static const ArmState & | get (const std::string &armStateParameter, const std::string &armName) |
static void | replaceJointPositions (sensor_msgs::JointState &state, const sensor_msgs::JointState &joints) |
Private Member Functions | |
ArmState (const std::string &armStateParameter, const std::string &armName) | |
Private Attributes | |
std::string | armName |
sensor_msgs::JointState | armState |
Static Private Attributes | |
static std::map< std::string, ArmState > | states |
Definition at line 16 of file arm_state.h.
ArmState::ArmState | ( | const std::string & | armStateParameter, |
const std::string & | armName | ||
) | [private] |
Definition at line 29 of file arm_state.cpp.
const ArmState & ArmState::get | ( | const std::string & | armStateParameter, |
const std::string & | armName | ||
) | [static] |
Definition at line 16 of file arm_state.cpp.
const std::string& ArmState::getArmName | ( | ) | const [inline] |
Definition at line 22 of file arm_state.h.
const sensor_msgs::JointState& ArmState::getJointStates | ( | ) | const [inline] |
Definition at line 23 of file arm_state.h.
void ArmState::replaceJointPositions | ( | sensor_msgs::JointState & | state, |
const sensor_msgs::JointState & | joints | ||
) | [static] |
Definition at line 75 of file arm_state.cpp.
void ArmState::replaceJointPositions | ( | sensor_msgs::JointState & | state | ) | const |
Definition at line 70 of file arm_state.cpp.
std::string ArmState::armName [private] |
Definition at line 29 of file arm_state.h.
sensor_msgs::JointState ArmState::armState [private] |
Definition at line 30 of file arm_state.h.
map< string, ArmState > ArmState::states [static, private] |
Definition at line 27 of file arm_state.h.