JointControlManagerInterface.h
Go to the documentation of this file.
00001 /***************************************************************************/
00014 #ifndef JOINTCONTROLMANAGERINTERFACE_H_
00015 #define JOINTCONTROLMANAGERINTERFACE_H_
00016 
00017 #include <boost/shared_ptr.hpp>
00018 #include <string>
00019 #include <map>
00020 #include "robodyn_mechanisms/JointControlActualInterface.h"
00021 #include "robodyn_mechanisms/JointControlCommandInterface.h"
00022 
00023 class JointControlManagerInterface : public JointControlCommonInterface
00024 {
00025 public:
00026     virtual bool                                  verifyStates(void)                                             = 0;
00027     virtual bool                                  verifyControlModeState(void)                                   = 0;
00028     virtual bool                                  verifyCommandModeState(void)                                   = 0;
00029     virtual bool                                  verifyCalibrationModeState(void)                               = 0;
00030     virtual bool                                  verifyClearFaultModeState(void)                                = 0;
00031     virtual r2_msgs::JointControlData getActualStates(void)                                          = 0;
00032     virtual r2_msgs::JointControlData getCommandStates(void)                                         = 0;
00033     virtual void                                  setCommandStates(const r2_msgs::JointControlData&) = 0;
00034     virtual diagnostic_msgs::DiagnosticStatus     getFaults()                                                    = 0;
00035 
00036     double getTimeLimit(void)
00037     {
00038         return timeLimit;
00039     }
00040 
00041     void setTimeLimit(double newTimeLimit)
00042     {
00043         timeLimit = newTimeLimit;
00044     }
00045 
00046     std::string getType(void)
00047     {
00048         return type;
00049     }
00050 
00051     void setPowerState(r2_msgs::PowerState newPowerState)
00052     {
00053         powerState = newPowerState;
00054     }
00055 
00056 protected:
00057     r2_msgs::JointControlData              actualStates;
00058     r2_msgs::JointControlData              commandStates;
00059     r2_msgs::JointControlData              prevActualStates;
00060     r2_msgs::JointControlData              defaultStates;
00061     boost::shared_ptr<JointControlActualInterface>     jointControlActual;
00062     boost::shared_ptr<JointControlCommandInterface>    jointControlCommand;
00063     ros::Time                                          lastControlModeMatchTime;
00064     ros::Time                                          lastCommandModeMatchTime;
00065     ros::Time                                          lastCalibrationModeMatchTime;
00066     ros::Time                                          lastClearFaultModeMatchTime;
00067     std::string                                        type;
00068     double                                             timeLimit;
00069     r2_msgs::PowerState                    powerState;
00070 
00071     JointControlManagerInterface(const std::string& mechanism, IoFunctions io, double timeLimit, const std::string& type)
00072         : JointControlCommonInterface(mechanism, io), type(type), timeLimit(timeLimit)
00073     {};
00074     virtual ~JointControlManagerInterface() {};
00075 };
00076 
00077 typedef boost::shared_ptr<JointControlManagerInterface> JointControlManagerPtr;
00078 typedef std::map<std::string, JointControlManagerPtr>   JointControlManagerMap;
00079 
00080 #endif


robodyn_mechanisms
Author(s):
autogenerated on Thu Jun 6 2019 21:22:49