ManipulatorHandler.h
Go to the documentation of this file.
00001 
00002 
00003 #ifndef MANIPULATOR_HANDLER_H
00004 #define MANIPULATOR_HANDLER_H
00005 
00006 #include <vrep_ros_plugin/GenericObjectHandler.h>
00007 #include <vrep_ros_plugin/access.h>
00008 #include <sensor_msgs/JointState.h>
00009 #include <geometry_msgs/Twist.h>
00010 
00011 class ManipulatorHandler : public GenericObjectHandler
00012 {
00013 public:
00014         ManipulatorHandler();
00015         ~ManipulatorHandler();
00016 
00020         void synchronize();
00021 
00025         void handleSimulation();
00026 
00030         unsigned int getObjectType() const;
00031 
00032 protected:
00033 
00037         void _initialize();
00038 
00040         std::vector<int> _handleOfJoints;
00041 
00043     std::vector<std::string> _jointNames;
00044 
00046         ros::Publisher _pub;
00047 
00049     ros::Subscriber _sub;
00050 
00052     ros::Subscriber _subVelMob;
00053 
00055         double _acquisitionFrequency;
00056 
00058         simFloat _lastPublishedStatus;
00059 
00061         simFloat _lastReceivedCmdTime;
00062 
00064     ros::Time _lastPrintedMsg;
00065 
00067     sensor_msgs::JointState _lastReceivedCmd;
00068 
00070     std::vector<CustomDataHeaders::ManipulatorCtrlMode> _jointCtrlMode;
00071 
00073         void jointCommandCallback(const sensor_msgs::JointStateConstPtr& msg);
00074 
00076         void VelMobCommandCallback(const geometry_msgs::TwistConstPtr& msg);
00077 
00079         unsigned int _numJoints;
00081         //float _tempjoint;
00082 
00084         double _axle_lenght;
00085 
00086         // Wheel radius
00087         double _mb_radius;
00088 
00090         CustomDataHeaders::ManipulatorCtrlMode _defaultModeCtrl;
00091 
00092 };
00093 
00094 
00095 #endif // ndef MANIPULATOR_HANDLER_H


manipulator_handler
Author(s): Giovanni Claudio
autogenerated on Sat Jun 8 2019 20:22:51