Go to the documentation of this file.00001
00008 #ifndef JOINTCONTROLCOMMONINTERFACE_H_
00009 #define JOINTCONTROLCOMMONINTERFACE_H_
00010
00011 #include <boost/shared_ptr.hpp>
00012 #include <boost/make_shared.hpp>
00013 #include <boost/function.hpp>
00014 #include <string>
00015 #include "nasa_common_logging/Logger.h"
00016 #include "robot_instance/ApiMap.h"
00017 #include "robot_instance/StringUtilities.h"
00018 #include "r2_msgs/RosMsgPrinter.h"
00019
00020 class JointControlCommonInterface
00021 {
00022 public:
00023 class IoFunctions
00024 {
00025 public:
00026 boost::function<std::string(const std::string&)> getRegisterFile;
00027 boost::function<std::string(const std::string&)> getControlFile;
00028 boost::function<bool(const std::string&)> hasLiveCoeff;
00029 boost::function<float(const std::string&)> getLiveCoeff;
00030 boost::function<void(const std::string&, float)> setLiveCoeff;
00031 boost::function<bool(const std::string&)> hasParam;
00032 boost::function<void(const std::string&, double)> setDoubleParam;
00033 boost::function<void(const std::string&, int)> setIntParam;
00034 boost::function<void(const std::string&, bool)> setBoolParam;
00035 boost::function<void(const std::string&, std::string)> setStringParam;
00036 boost::function<bool(const std::string&, double&)> getDoubleParam;
00037 boost::function<bool(const std::string&, int&)> getIntParam;
00038 boost::function<bool(const std::string&, bool&)> getBoolParam;
00039 boost::function<bool(const std::string&, std::string&)> getStringParam;
00040 };
00041
00042 std::string mechanism;
00043
00044 protected:
00045 JointControlCommonInterface(const std::string& mechanism, IoFunctions io)
00046 : mechanism(mechanism), io(io)
00047 {};
00048 virtual ~JointControlCommonInterface() {};
00049
00050 IoFunctions io;
00051 };
00052
00053 #endif