52 #include <visp/vpRobot.h> 54 #include <nav_msgs/Odometry.h> 55 #include <geometry_msgs/Twist.h> 73 vpTranslationVector
p;
100 void getVelocity (
const vpRobot::vpControlFrameType frame, vpColVector & velocity);
101 vpColVector getVelocity (
const vpRobot::vpControlFrameType frame);
107 void setPosition(
const vpRobot::vpControlFrameType ,
const vpColVector &) {};
108 void odomCallback(
const nav_msgs::Odometry::ConstPtr& msg);
109 void getCameraDisplacement(vpColVector & );
117 void getDisplacement(
const vpRobot::vpControlFrameType , vpColVector &);
118 void getDisplacement(
const vpRobot::vpControlFrameType , vpColVector &,
struct timespec ×tamp);
119 void getPosition(
const vpRobot::vpControlFrameType , vpColVector &);
123 void init(
int argc,
char **argv) ;
125 void setVelocity(
const vpRobot::vpControlFrameType frame,
const vpColVector &vel);
127 void setCmdVelTopic(std::string topic_name);
128 void setOdomTopic(std::string topic_name);
129 void setMasterURI(std::string master_uri);
130 void setNodespace(std::string nodespace);
ros::AsyncSpinner * spinner
Interface for robots based on ROS.
void setPosition(const vpRobot::vpControlFrameType, const vpColVector &)
void get_eJe(vpMatrix &eJe)
void getArticularDisplacement(vpColVector &)