#include <JointCommandRigid.h>
Public Member Functions | |
r2_msgs::JointCapability | getCapability () |
r2_msgs::JointCommand | getCommandedState () |
sensor_msgs::JointState | getCompleteMeasuredState () |
sensor_msgs::JointState | getSimpleMeasuredState () |
JointCommandRigid (const std::string &mechanism, IoFunctions ioFunctions) | |
void | loadCoeffs () |
void | setCommand (r2_msgs::JointCommand msg, r2_msgs::JointControlData) |
void | setFaultState () |
void | updateMeasuredState (r2_msgs::JointControlData msg) |
virtual | ~JointCommandRigid () |
Protected Attributes | |
std::string | brakePwmCommandElement |
unsigned int | completeMessageSize |
std::string | desiredPositionCommandElement |
std::string | desiredPositionVelocityLimitCommandElement |
std::vector< double > | effortVals |
std::string | encoderName |
std::string | encoderPositionStatusElement |
std::string | encoderRoboDynJointName |
std::string | encoderVelocityStatusElement |
double | jointGearRatio |
double | jointKinematicOffset |
std::string | jointPositionStatusElement |
std::string | jointRoboDynJointName |
std::string | jointVelocityStatusElement |
std::string | motComLimitCommandElement |
std::vector< double > | positionVals |
std::vector< double > | velocityVals |
Definition at line 12 of file JointCommandRigid.h.
JointCommandRigid::JointCommandRigid | ( | const std::string & | mechanism, |
IoFunctions | ioFunctions | ||
) |
Definition at line 7 of file JointCommandRigid.cpp.
JointCommandRigid::~JointCommandRigid | ( | ) | [virtual] |
Definition at line 39 of file JointCommandRigid.cpp.
r2_msgs::JointCapability JointCommandRigid::getCapability | ( | ) | [virtual] |
Implements JointCommandInterface.
Definition at line 269 of file JointCommandRigid.cpp.
r2_msgs::JointCommand JointCommandRigid::getCommandedState | ( | ) | [virtual] |
Implements JointCommandInterface.
Definition at line 214 of file JointCommandRigid.cpp.
sensor_msgs::JointState JointCommandRigid::getCompleteMeasuredState | ( | ) | [virtual] |
Implements JointCommandInterface.
Definition at line 199 of file JointCommandRigid.cpp.
sensor_msgs::JointState JointCommandRigid::getSimpleMeasuredState | ( | ) | [virtual] |
Implements JointCommandInterface.
Definition at line 188 of file JointCommandRigid.cpp.
void JointCommandRigid::loadCoeffs | ( | ) | [virtual] |
Initialize messages
Parse parameter file
Status Elements
Command Elements
Capability Elements
Set robot limits
Implements JointCommandInterface.
Definition at line 42 of file JointCommandRigid.cpp.
void JointCommandRigid::setCommand | ( | r2_msgs::JointCommand | msg, |
r2_msgs::JointControlData | |||
) | [virtual] |
Implements JointCommandInterface.
Definition at line 224 of file JointCommandRigid.cpp.
void JointCommandRigid::setFaultState | ( | ) |
Definition at line 210 of file JointCommandRigid.cpp.
void JointCommandRigid::updateMeasuredState | ( | r2_msgs::JointControlData | msg | ) | [virtual] |
joint
encoder
Implements JointCommandInterface.
Definition at line 165 of file JointCommandRigid.cpp.
std::string JointCommandRigid::brakePwmCommandElement [protected] |
Definition at line 41 of file JointCommandRigid.h.
unsigned int JointCommandRigid::completeMessageSize [protected] |
Definition at line 53 of file JointCommandRigid.h.
std::string JointCommandRigid::desiredPositionCommandElement [protected] |
Definition at line 39 of file JointCommandRigid.h.
std::string JointCommandRigid::desiredPositionVelocityLimitCommandElement [protected] |
Definition at line 40 of file JointCommandRigid.h.
std::vector<double> JointCommandRigid::effortVals [protected] |
Definition at line 51 of file JointCommandRigid.h.
std::string JointCommandRigid::encoderName [protected] |
Definition at line 47 of file JointCommandRigid.h.
std::string JointCommandRigid::encoderPositionStatusElement [protected] |
Definition at line 34 of file JointCommandRigid.h.
std::string JointCommandRigid::encoderRoboDynJointName [protected] |
Definition at line 31 of file JointCommandRigid.h.
std::string JointCommandRigid::encoderVelocityStatusElement [protected] |
Definition at line 37 of file JointCommandRigid.h.
double JointCommandRigid::jointGearRatio [protected] |
Definition at line 45 of file JointCommandRigid.h.
double JointCommandRigid::jointKinematicOffset [protected] |
Definition at line 44 of file JointCommandRigid.h.
std::string JointCommandRigid::jointPositionStatusElement [protected] |
Definition at line 33 of file JointCommandRigid.h.
std::string JointCommandRigid::jointRoboDynJointName [protected] |
Definition at line 30 of file JointCommandRigid.h.
std::string JointCommandRigid::jointVelocityStatusElement [protected] |
Definition at line 36 of file JointCommandRigid.h.
std::string JointCommandRigid::motComLimitCommandElement [protected] |
Definition at line 42 of file JointCommandRigid.h.
std::vector<double> JointCommandRigid::positionVals [protected] |
Definition at line 49 of file JointCommandRigid.h.
std::vector<double> JointCommandRigid::velocityVals [protected] |
Definition at line 50 of file JointCommandRigid.h.