#include <JointControlCommandWrist.h>
Public Member Functions | |
void | actuator (void) |
void | bootLoader (void) |
Transition command to JointControlMode::BOOTLOADER for the joint. | |
void | disableCalibrationMode (void) |
Transition command to JointControlCalibrationMode::DISABLE for the joint. | |
void | disableClearFaultMode (void) |
Transition command to JointControlClearFaultMode::DISABLE for the joint. | |
void | drive (void) |
Transition command to JointControlMode::DRIVE for the joint. | |
void | enableCalibrationMode (void) |
Transition command to JointControlCalibrationMode::ENABLE for the joint. | |
void | enableClearFaultMode (void) |
Transition command to JointControlClearFaultMode::ENABLE for the joint. | |
void | getStates (r2_msgs::JointControlData &commandStates) |
Retrieve state information. | |
JointControlCommandWrist (const std::string &, IoFunctions) | |
Constructor for JointControlCommandFsmWrist. | |
void | motCom (void) |
Transition command to JointControlMode::MOTCOM for the joint. | |
void | multiLoopSmooth (void) |
Transition command to JointControlMo//enableCalibrationMode();de::MULTILOOPSMOOTH for the joint. | |
void | multiLoopStep (void) |
Transition command to JointControlMode::MULTILOOPSTEP for the joint. | |
void | neutral (void) |
Transition command to JointControlMode::NEUTRAL for the joint. | |
void | off (void) |
Transition command to JointControlMode::OFF for the joint. | |
void | park (void) |
Transition command to JointControlMode::PARK for the joint. | |
void | resetCalibrationMode (void) |
Transition command to JointControlCalibrationMode::UNCALIBRATED for the joint. | |
void | stallMode (void) |
Transition command to JointControlCommandMode::STALLMODE for the joint. | |
virtual | ~JointControlCommandWrist () |
Protected Member Functions | |
void | setParameters () |
Protected Attributes | |
const std::string | logCategory |
Private Attributes | |
std::string | CalibrationModeLiveCoeffName |
std::string | ClearFaultStateLiveCoeffName |
std::string | CommandModeLiveCoeffName |
std::string | ControlModeLiveCoeffName |
Definition at line 13 of file JointControlCommandWrist.h.
JointControlCommandWrist::JointControlCommandWrist | ( | const std::string & | mechanism, |
IoFunctions | ioFunctions | ||
) |
Constructor for JointControlCommandFsmWrist.
Definition at line 11 of file JointControlCommandWrist.cpp.
JointControlCommandWrist::~JointControlCommandWrist | ( | ) | [virtual] |
Definition at line 30 of file JointControlCommandWrist.cpp.
void JointControlCommandWrist::actuator | ( | void | ) | [virtual] |
Implements JointControlCommandInterface.
Definition at line 195 of file JointControlCommandWrist.cpp.
void JointControlCommandWrist::bootLoader | ( | void | ) | [virtual] |
Transition command to JointControlMode::BOOTLOADER for the joint.
if we return to bootloader, reset calibration mode
Implements JointControlCommandInterface.
Definition at line 96 of file JointControlCommandWrist.cpp.
void JointControlCommandWrist::disableCalibrationMode | ( | void | ) | [virtual] |
Transition command to JointControlCalibrationMode::DISABLE for the joint.
Implements JointControlCommandInterface.
Definition at line 208 of file JointControlCommandWrist.cpp.
void JointControlCommandWrist::disableClearFaultMode | ( | void | ) | [virtual] |
Transition command to JointControlClearFaultMode::DISABLE for the joint.
Implements JointControlCommandInterface.
Definition at line 243 of file JointControlCommandWrist.cpp.
void JointControlCommandWrist::drive | ( | void | ) | [virtual] |
Transition command to JointControlMode::DRIVE for the joint.
Implements JointControlCommandInterface.
Definition at line 143 of file JointControlCommandWrist.cpp.
void JointControlCommandWrist::enableCalibrationMode | ( | void | ) | [virtual] |
Transition command to JointControlCalibrationMode::ENABLE for the joint.
Implements JointControlCommandInterface.
Definition at line 218 of file JointControlCommandWrist.cpp.
void JointControlCommandWrist::enableClearFaultMode | ( | void | ) | [virtual] |
Transition command to JointControlClearFaultMode::ENABLE for the joint.
Implements JointControlCommandInterface.
Definition at line 254 of file JointControlCommandWrist.cpp.
void JointControlCommandWrist::getStates | ( | r2_msgs::JointControlData & | commandStates | ) | [virtual] |
Retrieve state information.
Implements JointControlCommandInterface.
Definition at line 85 of file JointControlCommandWrist.cpp.
void JointControlCommandWrist::motCom | ( | void | ) | [virtual] |
Transition command to JointControlMode::MOTCOM for the joint.
Implements JointControlCommandInterface.
Definition at line 156 of file JointControlCommandWrist.cpp.
void JointControlCommandWrist::multiLoopSmooth | ( | void | ) | [virtual] |
Transition command to JointControlMo//enableCalibrationMode();de::MULTILOOPSMOOTH for the joint.
Implements JointControlCommandInterface.
Definition at line 188 of file JointControlCommandWrist.cpp.
void JointControlCommandWrist::multiLoopStep | ( | void | ) | [virtual] |
Transition command to JointControlMode::MULTILOOPSTEP for the joint.
Implements JointControlCommandInterface.
Definition at line 177 of file JointControlCommandWrist.cpp.
void JointControlCommandWrist::neutral | ( | void | ) | [virtual] |
Transition command to JointControlMode::NEUTRAL for the joint.
Implements JointControlCommandInterface.
Definition at line 132 of file JointControlCommandWrist.cpp.
void JointControlCommandWrist::off | ( | void | ) | [virtual] |
Transition command to JointControlMode::OFF for the joint.
Implements JointControlCommandInterface.
Definition at line 109 of file JointControlCommandWrist.cpp.
void JointControlCommandWrist::park | ( | void | ) | [virtual] |
Transition command to JointControlMode::PARK for the joint.
Implements JointControlCommandInterface.
Definition at line 120 of file JointControlCommandWrist.cpp.
void JointControlCommandWrist::resetCalibrationMode | ( | void | ) | [virtual] |
Transition command to JointControlCalibrationMode::UNCALIBRATED for the joint.
Implements JointControlCommandInterface.
Definition at line 230 of file JointControlCommandWrist.cpp.
void JointControlCommandWrist::setParameters | ( | ) | [protected, virtual] |
Parse parameter file
Implements JointControlCommandInterface.
Definition at line 34 of file JointControlCommandWrist.cpp.
void JointControlCommandWrist::stallMode | ( | void | ) | [virtual] |
Transition command to JointControlCommandMode::STALLMODE for the joint.
Implements JointControlCommandInterface.
Definition at line 167 of file JointControlCommandWrist.cpp.
std::string JointControlCommandWrist::CalibrationModeLiveCoeffName [private] |
Definition at line 52 of file JointControlCommandWrist.h.
std::string JointControlCommandWrist::ClearFaultStateLiveCoeffName [private] |
Definition at line 53 of file JointControlCommandWrist.h.
std::string JointControlCommandWrist::CommandModeLiveCoeffName [private] |
Definition at line 51 of file JointControlCommandWrist.h.
std::string JointControlCommandWrist::ControlModeLiveCoeffName [private] |
Definition at line 50 of file JointControlCommandWrist.h.
const std::string JointControlCommandWrist::logCategory [protected] |
Definition at line 46 of file JointControlCommandWrist.h.