JointCommandInterface.h
Go to the documentation of this file.
00001 
00006 #ifndef JOINTCOMMANDINTERFACE_H_
00007 #define JOINTCOMMANDINTERFACE_H_
00008 
00009 #include <vector>
00010 #include <boost/function.hpp>
00011 #include <sensor_msgs/JointState.h>
00012 #include <r2_msgs/JointCommand.h>
00013 #include <r2_msgs/JointCapability.h>
00014 #include <r2_msgs/JointControlDataArray.h>
00015 #include <diagnostic_msgs/DiagnosticArray.h>
00016 #include "nasa_common_logging/Logger.h"
00017 #include <cstring>
00018 #include <boost/shared_ptr.hpp>
00019 #include "robot_instance/ApiMap.h"
00020 
00021 class JointCommandInterface
00022 {
00023 public:
00024     class IoFunctions
00025     {
00026     public:
00027         boost::function<uint16_t(const std::string&)>                 getUInt16;
00028         boost::function<void(const std::string&, uint16_t)>           setUInt16;
00029         boost::function<uint32_t(const std::string&)>                 getUInt32;
00030         boost::function<void(const std::string&, uint32_t)>           setUInt32;
00031         boost::function<int16_t(const std::string&)>                  getInt16;
00032         boost::function<void(const std::string&, int16_t)>            setInt16;
00033         boost::function<int32_t(const std::string&)>                  getInt32;
00034         boost::function<void(const std::string&, int32_t)>            setInt32;
00035         boost::function<float(const std::string&)>                    getFloat;
00036         boost::function<void(const std::string&, float)>              setFloat;
00037         boost::function<float(const std::string&)>                    getMotorCoeff;
00038         boost::function<bool(const std::string&)>                     hasBrainstemCoeff;
00039         boost::function<float(const std::string&)>                    getBrainstemCoeff;
00040         boost::function<std::vector<std::string>(const std::string&)> getJointNames;
00041         boost::function<std::vector<std::string>(const std::string&)> getAllJointNames;
00042         boost::function<std::vector<std::string>(const std::string&)> getActuatorNames;
00043         boost::function<std::string(const std::string&)>              getCommandFile;
00044         boost::function<bool(const std::string&)>                     hasLiveCoeff;
00045         boost::function<float(const std::string&)>                    getLiveCoeff;
00046         boost::function<void(const std::string&, float)>              setLiveCoeff;
00047         boost::function<bool(const std::string&)>                     hasParam;
00048         boost::function<void(const std::string&, double)>             setDoubleParam;
00049         boost::function<void(const std::string&, int)>                setIntParam;
00050         boost::function<void(const std::string&, bool)>               setBoolParam;
00051         boost::function<void(const std::string&, std::string)>        setStringParam;
00052         boost::function<bool(const std::string&, double&)>            getDoubleParam;
00053         boost::function<bool(const std::string&, int&)>               getIntParam;
00054         boost::function<bool(const std::string&, bool&)>              getBoolParam;
00055         boost::function<bool(const std::string&, std::string&)>       getStringParam;
00056     };
00057 
00058     virtual sensor_msgs::JointState           getSimpleMeasuredState() = 0;
00059     virtual sensor_msgs::JointState           getCompleteMeasuredState() = 0;
00060     virtual r2_msgs::JointCommand getCommandedState() = 0;
00061     virtual void setCommand(r2_msgs::JointCommand msg, r2_msgs::JointControlData control) = 0;
00062     virtual void updateMeasuredState(r2_msgs::JointControlData msg) = 0;
00063 
00064     virtual r2_msgs::JointCapability getCapability() = 0;
00065     virtual void loadCoeffs() = 0;
00066 
00067     std::string mechanism;
00068     std::vector<std::string> roboDynJoints, roboDynAllJoints;
00069     std::vector<std::string> roboDynActuators;
00070 
00071 protected:
00072     JointCommandInterface(const std::string& mechanism, IoFunctions io)
00073         : mechanism(mechanism), io(io)
00074     {};
00075     virtual ~JointCommandInterface() {};
00076 
00077     IoFunctions io;
00078 
00079     sensor_msgs::JointState              simpleMeasuredStateMsg;
00080     sensor_msgs::JointState              completeMeasuredStateMsg;
00081     r2_msgs::JointCommand    commandedStateMsg;
00082     r2_msgs::JointCapability jointCapabilityMsg;
00083 
00084 };
00085 
00086 typedef boost::shared_ptr<JointCommandInterface> JointCommandInterfacePtr;
00087 
00088 #endif /* JOINTCOMMANDINTERFACE_H_ */


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