6 #include <geometry_msgs/TwistStamped.h> 7 #include <geometry_msgs/Pose.h> 8 #include <geometry_msgs/PoseStamped.h> 9 #include <nav_msgs/Odometry.h> 15 #include <visp/vpRobotAfma6.h> 20 #ifdef VISP_HAVE_AFMA6 30 void setCameraVel(
const geometry_msgs::TwistStampedConstPtr &);
55 vpHomogeneousMatrix
wMc;
101 robot =
new vpRobotAfma6;
103 robot->init(vpAfma6::TOOL_CCMOP, vpCameraParameters::perspectiveProjWithDistortion);
104 vpCameraParameters cam;
105 robot->getCameraParameters(cam, 640, 480);
106 std::cout <<
"Camera parameters (640 x 480):\n" << cam << std::endl;
108 robot->setRobotState(vpRobot::STATE_VELOCITY_CONTROL);
127 robot->getPosition(vpRobot::ARTICULAR_FRAME,
q, timestamp);
139 robot->getVelocity(vpRobot::CAMERA_FRAME, vel, timestamp);
140 geometry_msgs::TwistStamped vel_msg;
141 vel_msg.header.stamp =
ros::Time(timestamp);
142 vel_msg.twist.linear.x = vel[0];
143 vel_msg.twist.linear.y = vel[1];
144 vel_msg.twist.linear.z = vel[2];
145 vel_msg.twist.angular.x = vel[3];
146 vel_msg.twist.angular.y = vel[4];
147 vel_msg.twist.angular.z = vel[5];
160 vc[0] = msg->twist.linear.x;
161 vc[1] = msg->twist.linear.y;
162 vc[2] = msg->twist.linear.z;
164 vc[3] = msg->twist.angular.x;
165 vc[4] = msg->twist.angular.y;
166 vc[5] = msg->twist.angular.z;
171 robot->setVelocity(vpRobot::CAMERA_FRAME, vc);
176 #endif // #ifdef VISP_HAVE_AFMA6 178 int main(
int argc,
char** argv )
180 #ifdef VISP_HAVE_AFMA6 186 if( node->
setup() != 0 )
188 printf(
"Afma6 setup failed... \n" );
196 printf(
"\nQuitting... \n" );
198 printf(
"This node is node available since ViSP was \nnot build with Afma6 robot support...\n");
RosAfma6Node(ros::NodeHandle n)
std::string frame_id_odom
void publish(const boost::shared_ptr< M > &message) const
std::string getPrefixParam(ros::NodeHandle &nh)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
std::string frame_id_base_link
geometry_msgs::PoseStamped position
void setCameraVel(const geometry_msgs::TwistStampedConstPtr &)
int main(int argc, char **argv)
geometry_msgs::Pose toGeometryMsgsPose(const vpHomogeneousMatrix &mat)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::Subscriber cmd_camvel_sub
geometry_msgs::TransformStamped odom_trans
ROSCPP_DECL void spinOnce()
tf::TransformBroadcaster odom_broadcaster