51 #include <visp3/robot/vpRobot.h>
53 #include <geometry_msgs/Twist.h>
54 #include <nav_msgs/Odometry.h>
73 vpTranslationVector
p;
99 void getVelocity(
const vpRobot::vpControlFrameType frame, vpColVector &velocity );
100 vpColVector getVelocity(
const vpRobot::vpControlFrameType frame );
106 void setPosition(
const vpRobot::vpControlFrameType ,
const vpColVector & ){};
107 void odomCallback(
const nav_msgs::Odometry::ConstPtr &msg );
108 void getCameraDisplacement( vpColVector & );
116 void getDisplacement(
const vpRobot::vpControlFrameType , vpColVector & );
117 void getDisplacement(
const vpRobot::vpControlFrameType , vpColVector & ,
struct timespec ×tamp );
118 void getPosition(
const vpRobot::vpControlFrameType , vpColVector & );
122 void init(
int argc,
char **argv );
124 void setVelocity(
const vpRobot::vpControlFrameType frame,
const vpColVector &vel );
126 void setCmdVelTopic( std::string topic_name );
127 void setOdomTopic( std::string topic_name );
128 void setMasterURI( std::string master_uri );
129 void setNodespace( std::string nodespace );