#include <JointControlActualWrist.h>
Public Member Functions | |
void | getFaults (diagnostic_msgs::DiagnosticStatus &faultStatus) |
void | getStates (r2_msgs::JointControlData &actualStates) |
get the Command, Control, and Calibration Mode states, as well as the Coeff State | |
JointControlActualWrist (const std::string &, IoFunctions) | |
Constructor for JointControlActualFsmWrist. | |
void | updateCalibrationModeState (void) |
Update the calibration mode state. | |
void | updateClearFaultModeState (void) |
Update the clearFault mode state. | |
void | updateCoeffState (void) |
Update the coefficient state. | |
void | updateCommandModeState (void) |
Update the command mode state. | |
void | updateControlModeState (void) |
Update the control mode state. | |
virtual | ~JointControlActualWrist () |
Protected Member Functions | |
void | setParameters () |
Protected Attributes | |
const std::string | logCategory |
Private Attributes | |
std::string | CalibrationModeLiveCoeffName |
std::string | ClearFaultStateLiveCoeffName |
std::string | CoeffStateLiveCoeffName |
std::string | CommandModeLiveCoeffName |
std::string | ControlModeLiveCoeffName |
std::string | LittlesideSliderLimitLiveCoeffName |
std::string | PitchLimitLiveCoeffName |
std::string | SensorErrorLiveCoeffName |
std::string | SliderDiffErrorLiveCoeffName |
std::string | ThumbsideSliderLimitLiveCoeffName |
std::string | YawLimitLiveCoeffName |
Definition at line 13 of file JointControlActualWrist.h.
JointControlActualWrist::JointControlActualWrist | ( | const std::string & | mechanism, |
IoFunctions | ioFunctions | ||
) |
Constructor for JointControlActualFsmWrist.
mechanism | |
ioFunctions |
invalid_argument | if any of the io file is empty |
Definition at line 15 of file JointControlActualWrist.cpp.
JointControlActualWrist::~JointControlActualWrist | ( | ) | [virtual] |
Definition at line 31 of file JointControlActualWrist.cpp.
void JointControlActualWrist::getFaults | ( | diagnostic_msgs::DiagnosticStatus & | faultStatus | ) | [virtual] |
Implements JointControlActualInterface.
Definition at line 258 of file JointControlActualWrist.cpp.
void JointControlActualWrist::getStates | ( | r2_msgs::JointControlData & | actualStates | ) | [virtual] |
get the Command, Control, and Calibration Mode states, as well as the Coeff State
Implements JointControlActualInterface.
Definition at line 103 of file JointControlActualWrist.cpp.
void JointControlActualWrist::setParameters | ( | ) | [protected, virtual] |
Parse parameter file
Implements JointControlActualInterface.
Definition at line 36 of file JointControlActualWrist.cpp.
void JointControlActualWrist::updateCalibrationModeState | ( | void | ) | [virtual] |
Update the calibration mode state.
Implements JointControlActualInterface.
Definition at line 214 of file JointControlActualWrist.cpp.
void JointControlActualWrist::updateClearFaultModeState | ( | void | ) | [virtual] |
Update the clearFault mode state.
Implements JointControlActualInterface.
Definition at line 230 of file JointControlActualWrist.cpp.
void JointControlActualWrist::updateCoeffState | ( | void | ) | [virtual] |
Update the coefficient state.
Implements JointControlActualInterface.
Definition at line 246 of file JointControlActualWrist.cpp.
void JointControlActualWrist::updateCommandModeState | ( | void | ) | [virtual] |
Update the command mode state.
Implements JointControlActualInterface.
Definition at line 198 of file JointControlActualWrist.cpp.
void JointControlActualWrist::updateControlModeState | ( | void | ) | [virtual] |
Update the control mode state.
Implements JointControlActualInterface.
Definition at line 117 of file JointControlActualWrist.cpp.
std::string JointControlActualWrist::CalibrationModeLiveCoeffName [private] |
Definition at line 41 of file JointControlActualWrist.h.
std::string JointControlActualWrist::ClearFaultStateLiveCoeffName [private] |
Definition at line 43 of file JointControlActualWrist.h.
std::string JointControlActualWrist::CoeffStateLiveCoeffName [private] |
Definition at line 42 of file JointControlActualWrist.h.
std::string JointControlActualWrist::CommandModeLiveCoeffName [private] |
Definition at line 40 of file JointControlActualWrist.h.
std::string JointControlActualWrist::ControlModeLiveCoeffName [private] |
Definition at line 39 of file JointControlActualWrist.h.
std::string JointControlActualWrist::LittlesideSliderLimitLiveCoeffName [private] |
Definition at line 35 of file JointControlActualWrist.h.
const std::string JointControlActualWrist::logCategory [protected] |
Definition at line 29 of file JointControlActualWrist.h.
std::string JointControlActualWrist::PitchLimitLiveCoeffName [private] |
Definition at line 33 of file JointControlActualWrist.h.
std::string JointControlActualWrist::SensorErrorLiveCoeffName [private] |
Definition at line 37 of file JointControlActualWrist.h.
std::string JointControlActualWrist::SliderDiffErrorLiveCoeffName [private] |
Definition at line 38 of file JointControlActualWrist.h.
std::string JointControlActualWrist::ThumbsideSliderLimitLiveCoeffName [private] |
Definition at line 36 of file JointControlActualWrist.h.
std::string JointControlActualWrist::YawLimitLiveCoeffName [private] |
Definition at line 34 of file JointControlActualWrist.h.