00001 /***************************************************************************/ 00008 #ifndef JOINTCONTROLACTUALFSMINTERFACE_H_ 00009 #define JOINTCONTROLACTUALFSMINTERFACE_H_ 00010 00011 #include <boost/shared_ptr.hpp> 00012 #include <string> 00013 #include "robodyn_mechanisms/JointControlCommonInterface.h" 00014 #include <r2_msgs/JointControlData.h> 00015 #include "diagnostic_msgs/DiagnosticStatus.h" 00016 00017 class JointControlActualInterface : public JointControlCommonInterface 00018 { 00019 public: 00020 virtual void getStates(r2_msgs::JointControlData&) = 0; 00021 virtual void updateControlModeState(void) = 0; 00022 virtual void updateCommandModeState(void) = 0; 00023 virtual void updateCalibrationModeState(void) = 0; 00024 virtual void updateClearFaultModeState(void) = 0; 00025 virtual void updateCoeffState(void) = 0; 00026 virtual void getFaults(diagnostic_msgs::DiagnosticStatus&) = 0; 00027 00028 protected: 00029 JointControlActualInterface(const std::string& mechanism, IoFunctions io) 00030 : JointControlCommonInterface(mechanism, io) 00031 {}; 00032 virtual ~JointControlActualInterface() {}; 00033 virtual void setParameters() = 0; 00034 00035 r2_msgs::JointControlData states; 00036 }; 00037 00038 #endif