Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041
00042
00043
00044 #ifndef vpROSRobot_H
00045 #define vpROSRobot_H
00046
00052 #include <visp/vpRobot.h>
00053 #include <ros/ros.h>
00054 #include <nav_msgs/Odometry.h>
00055 #include <geometry_msgs/Twist.h>
00056
00062 class VISP_EXPORT vpROSRobot : public vpRobot
00063 {
00064 protected:
00065 ros::NodeHandle *n;
00066 ros::Publisher cmdvel;
00067 ros::Subscriber odom;
00068 ros::AsyncSpinner *spinner;
00069
00070 bool isInitialized;
00071
00072 vpQuaternionVector q;
00073 vpTranslationVector p;
00074 vpColVector pose_prev;
00075 vpColVector displacement;
00076 uint32_t _sec, _nsec;
00077 volatile bool odom_mutex;
00078 std::string _master_uri;
00079 std::string _topic_cmd;
00080 std::string _topic_odom;
00081 std::string _nodespace;
00082
00083 private:
00084 void get_eJe(vpMatrix & eJe){}
00085
00086 vpROSRobot(const vpROSRobot &robot);
00091 void get_fJe(vpMatrix & ) {}
00092
00097 void getArticularDisplacement(vpColVector & ) {};
00098
00099
00100 void getVelocity (const vpRobot::vpControlFrameType frame, vpColVector & velocity);
00101 vpColVector getVelocity (const vpRobot::vpControlFrameType frame);
00102
00107 void setPosition(const vpRobot::vpControlFrameType , const vpColVector &) {};
00108 void odomCallback(const nav_msgs::Odometry::ConstPtr& msg);
00109 void getCameraDisplacement(vpColVector & );
00110
00111 public:
00113 vpROSRobot() ;
00115 virtual ~vpROSRobot() ;
00116
00117 void getDisplacement(const vpRobot::vpControlFrameType , vpColVector &);
00118 void getDisplacement(const vpRobot::vpControlFrameType , vpColVector &, struct timespec ×tamp);
00119 void getPosition(const vpRobot::vpControlFrameType , vpColVector &);
00120
00122 void init() ;
00123 void init(int argc, char **argv) ;
00124
00125 void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel);
00126 void stopMotion();
00127 void setCmdVelTopic(std::string topic_name);
00128 void setOdomTopic(std::string topic_name);
00129 void setMasterURI(std::string master_uri);
00130 void setNodespace(std::string nodespace);
00131 } ;
00132
00133 #endif
00134
00135
00136