TubeTareInterface.h
Go to the documentation of this file.
00001 #ifndef TUBETAREINTERFACE_H
00002 #define TUBETAREINTERFACE_H
00003 
00004 #include <vector>
00005 #include <cstring>
00006 #include <boost/function.hpp>
00007 #include "tinyxml.h"
00008 #include "nasa_common_logging/Logger.h"
00009 #include <cstring>
00010 #include <boost/shared_ptr.hpp>
00011 #include <ros/builtin_message_traits.h>
00012 #include "robot_instance/ApiMap.h"
00013 
00014 class TubeTareInterface
00015 {
00016 public:
00017     class IoFunctions
00018     {
00019     public:
00020         boost::function<uint16_t(const std::string&)>                 getUInt16;
00021         boost::function<void(const std::string&, uint16_t)>           setUInt16;
00022         boost::function<uint32_t(const std::string&)>                 getUInt32;
00023         boost::function<void(const std::string&, uint32_t)>           setUInt32;
00024         boost::function<int16_t(const std::string&)>                  getInt16;
00025         boost::function<void(const std::string&, int16_t)>            setInt16;
00026         boost::function<int32_t(const std::string&)>                  getInt32;
00027         boost::function<void(const std::string&, int32_t)>            setInt32;
00028         boost::function<float(const std::string&)>                    getFloat;
00029         boost::function<void(const std::string&, float)>              setFloat;
00030         boost::function<float(const std::string&)>                    getMotorCoeff;
00031         boost::function<std::vector<std::string>(const std::string&)> getJointNames;
00032         boost::function<std::vector<std::string>(const std::string&)> getActuatorNames;
00033         boost::function<std::string(const std::string&)>              getCommandFile;
00034         boost::function<bool(const std::string&)>                     hasLiveCoeff;
00035         boost::function<float(const std::string&)>                    getLiveCoeff;
00036         boost::function<void(const std::string&, float)>              setLiveCoeff;
00037     };
00038 
00039     virtual void setStop(const std::vector<std::string>& actuators = std::vector<std::string>()) = 0; //the motcom command for stop (0)
00040     virtual bool isMoving() = 0; //checks if the velocity is 0
00041     virtual void setRelease(const std::vector<std::string>& actuators = std::vector<std::string>()) = 0; //the motcom command for release (limited)
00042     virtual void getEncoderTarePos() = 0; //perform the tare (TareEncoderAbsolute)
00043     virtual void setTighten(const std::vector<std::string>& actuators = std::vector<std::string>()) = 0; //set motcom to tighten position (limited)
00044     virtual int  goodPosition() = 0; //checks if near end of travel
00045     virtual void getSliderTarePos() = 0;//SliderVectorType &encoderOffsets, SliderVectorType &sliderOffsets);
00046     virtual void getTensionTareValue() = 0;
00047     virtual void resetTensionCounter() = 0;
00048 
00049     std::string mechanism;
00050     std::vector<std::string> roboDynJoints;
00051     std::vector<std::string> roboDynActuators;
00052 protected:
00053     TubeTareInterface(const std::string& mechanism, IoFunctions io)
00054         : mechanism(mechanism), io(io)
00055     {}
00056     virtual ~TubeTareInterface() {}
00057 
00058     IoFunctions io;
00059 };
00060 
00061 typedef boost::shared_ptr<TubeTareInterface> TubeTareInterfacePtr;
00062 
00063 
00064 #endif // TUBETAREINTERFACE_H


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