#include <RosMsgTreeId.h>
Public Member Functions | |
| bool | GetCompletionMessage (RateLimiter &yl, r2_msgs::StringArray &completionMsg) |
| void | getJointCommand (const JointDynamicsData &jd, sensor_msgs::JointState &tauFF) |
| void | getJointInertias (const JointDynamicsData &jd, sensor_msgs::JointState &Hv) |
| void | getSegmentForces (const JointDynamicsData &jd, r2_msgs::WrenchState &segForceMsg) |
| RosMsgTreeId () | |
| int | setBaseFrame (const r2_msgs::StringArray &baseMsg, std::string &baseFrame) |
| void | setEmptyTorqueMsg (const JointDynamicsData &jd, sensor_msgs::JointState &tauFF) |
| void | setJointData (const sensor_msgs::JointState &actualState, const sensor_msgs::JointState &desiredStates, const r2_msgs::WrenchState &wrenchState, JointDynamicsData &jd) |
| ~RosMsgTreeId () | |
Definition at line 12 of file RosMsgTreeId.h.
Definition at line 3 of file RosMsgTreeId.cpp.
Definition at line 7 of file RosMsgTreeId.cpp.
| bool RosMsgTreeId::GetCompletionMessage | ( | RateLimiter & | yl, |
| r2_msgs::StringArray & | completionMsg | ||
| ) |
Definition at line 211 of file RosMsgTreeId.cpp.
| void RosMsgTreeId::getJointCommand | ( | const JointDynamicsData & | jd, |
| sensor_msgs::JointState & | tauFF | ||
| ) |
Definition at line 103 of file RosMsgTreeId.cpp.
| void RosMsgTreeId::getJointInertias | ( | const JointDynamicsData & | jd, |
| sensor_msgs::JointState & | Hv | ||
| ) |
Definition at line 186 of file RosMsgTreeId.cpp.
| void RosMsgTreeId::getSegmentForces | ( | const JointDynamicsData & | jd, |
| r2_msgs::WrenchState & | segForceMsg | ||
| ) |
Definition at line 129 of file RosMsgTreeId.cpp.
| int RosMsgTreeId::setBaseFrame | ( | const r2_msgs::StringArray & | baseMsg, |
| std::string & | baseFrame | ||
| ) |
Definition at line 11 of file RosMsgTreeId.cpp.
| void RosMsgTreeId::setEmptyTorqueMsg | ( | const JointDynamicsData & | jd, |
| sensor_msgs::JointState & | tauFF | ||
| ) |
Definition at line 160 of file RosMsgTreeId.cpp.
| void RosMsgTreeId::setJointData | ( | const sensor_msgs::JointState & | actualState, |
| const sensor_msgs::JointState & | desiredStates, | ||
| const r2_msgs::WrenchState & | wrenchState, | ||
| JointDynamicsData & | jd | ||
| ) |
Definition at line 31 of file RosMsgTreeId.cpp.