00001 /***************************************************************************/ 00008 #ifndef JOINTCONTROLCOMMANDFSMINTERFACE_H_ 00009 #define JOINTCONTROLCOMMANDFSMINTERFACE_H_ 00010 00011 #include <boost/shared_ptr.hpp> 00012 #include <string> 00013 #include "robodyn_mechanisms/JointControlCommonInterface.h" 00014 #include <r2_msgs/JointControlData.h> 00015 00016 class JointControlCommandInterface : public JointControlCommonInterface 00017 { 00018 public: 00019 virtual void getStates(r2_msgs::JointControlData&) = 0; 00020 00021 // controlMode functions 00022 virtual void bootLoader(void) = 0; 00023 virtual void off(void) = 0; 00024 virtual void park(void) = 0; 00025 virtual void neutral(void) = 0; 00026 virtual void drive(void) = 0; 00027 00028 // commandMode functions 00029 virtual void motCom(void) = 0; 00030 virtual void stallMode(void) = 0; 00031 virtual void multiLoopStep(void) = 0; 00032 virtual void multiLoopSmooth(void) = 0; 00033 virtual void actuator(void) = 0; 00034 00035 // calibrationMode functions 00036 virtual void disableCalibrationMode(void) = 0; 00037 virtual void enableCalibrationMode(void) = 0; 00038 virtual void resetCalibrationMode(void) = 0; 00039 00040 // clearFaultMode functions 00041 virtual void enableClearFaultMode(void) = 0; 00042 virtual void disableClearFaultMode(void) = 0; 00043 00044 protected: 00045 r2_msgs::JointControlData states; 00046 00047 JointControlCommandInterface(const std::string& mechanism, IoFunctions io) 00048 : JointControlCommonInterface(mechanism, io) 00049 {}; 00050 virtual ~JointControlCommandInterface() {}; 00051 virtual void setParameters() = 0; 00052 }; 00053 00054 #endif