afma6.cpp
Go to the documentation of this file.
1 #include <stdio.h>
2 #include <math.h>
3 #include <sstream>
4 
5 #include <ros/ros.h>
6 #include <geometry_msgs/TwistStamped.h>
7 #include <geometry_msgs/Pose.h>
8 #include <geometry_msgs/PoseStamped.h>
9 #include <nav_msgs/Odometry.h>
10 #include <tf/tf.h>
11 #include <tf/transform_listener.h>
12 #include <tf/transform_broadcaster.h>
13 #include <tf/transform_datatypes.h>
14 
15 #include <visp/vpRobotAfma6.h> // visp
16 #include <visp/vpRingLight.h>
17 
18 #include <visp_bridge/3dpose.h> // visp_bridge
19 
20 
21 #ifdef VISP_HAVE_AFMA6
22 
24 {
25  public:
26  RosAfma6Node(ros::NodeHandle n);
27  virtual ~RosAfma6Node();
28 
29  public:
30  int setup();
31  void setCameraVel( const geometry_msgs::TwistStampedConstPtr &);
32  void spin();
33  void publish();
34 
35  protected:
36  ros::NodeHandle n;
37  ros::Publisher pose_pub;
38  ros::Publisher vel_pub;
39  ros::Subscriber cmd_camvel_sub;
40 
41  ros::Time veltime;
42 
43  std::string serial_port;
44 
45  vpRobotAfma6 *robot;
46  geometry_msgs::PoseStamped position;
47 
48  //for odom->base_link transform
49  tf::TransformBroadcaster odom_broadcaster;
50  geometry_msgs::TransformStamped odom_trans;
51  //for resolving tf names.
52  std::string tf_prefix;
53  std::string frame_id_odom;
54  std::string frame_id_base_link;
55 
56  vpHomogeneousMatrix wMc; // world to camera transformation
57  vpColVector q; // measured joint position
58  };
59 
60 
61 RosAfma6Node::RosAfma6Node(ros::NodeHandle nh)
62 {
63  // read in config options
64  n = nh;
65 
66  ROS_INFO( "using Afma6 robot" );
67 
68  robot = NULL;
69  /*
70  * Figure out what frame_id's to use. if a tf_prefix param is specified,
71  * it will be added to the beginning of the frame_ids.
72  *
73  * e.g. rosrun ... _tf_prefix:=MyRobot (or equivalently using <param>s in
74  * roslaunch files)
75  * will result in the frame_ids being set to /MyRobot/odom etc,
76  * rather than /odom. This is useful for Multi Robot Systems.
77  * See ROS Wiki for further details.
78  */
79  tf_prefix = tf::getPrefixParam(n);
80 // frame_id_odom = tf::resolve(tf_prefix, "odom");
81 // frame_id_base_link = tf::resolve(tf_prefix, "base_link");
82 
83  // advertise services
84  pose_pub = n.advertise<geometry_msgs::PoseStamped>("pose", 1000);
85  vel_pub = n.advertise<geometry_msgs::TwistStamped>("velocity", 1000);
86 
87  // subscribe to services
88  cmd_camvel_sub = n.subscribe( "cmd_camvel", 1, (boost::function < void(const geometry_msgs::TwistStampedConstPtr&)>) boost::bind( &RosAfma6Node::setCameraVel, this, _1 ));
89 }
90 
92 {
93  if (robot) {
94  robot->stopMotion();
95  delete robot;
96  robot = NULL;
97  }
98 }
99 
101 {
102  robot = new vpRobotAfma6;
103 
104  robot->init(vpAfma6::TOOL_CCMOP, vpCameraParameters::perspectiveProjWithDistortion);
105 
106  robot->setRobotState(vpRobot::STATE_VELOCITY_CONTROL);
107 
108  return 0;
109 }
110 
112 {
113  ros::Rate loop_rate(100);
114  while(ros::ok()){
115  this->publish();
116  ros::spinOnce();
117  loop_rate.sleep();
118  }
119 // ros::spin();
120 }
121 
123 {
124  double timestamp;
125  robot->getPosition(vpRobot::ARTICULAR_FRAME, q, timestamp);
126  wMc = robot->get_fMc(q);
127  position.pose = visp_bridge::toGeometryMsgsPose(wMc);
128  position.header.stamp = ros::Time(timestamp); // to improve: should be the timestamp returned by getPosition()
129 
130  // ROS_INFO( "Afma6 publish pose at %f s: [%0.2f %0.2f %0.2f] - [%0.2f %0.2f %0.2f %0.2f]",
131  // position.header.stamp.toSec(),
132  // position.pose.position.x, position.pose.position.y, position.pose.position.z,
133  // position.pose.orientation.w, position.pose.orientation.x, position.pose.orientation.y, position.pose.orientation.z);
134  pose_pub.publish(position);
135 
136  vpColVector vel(6);
137  robot->getVelocity(vpRobot::CAMERA_FRAME, vel, timestamp);
138  geometry_msgs::TwistStamped vel_msg;
139  vel_msg.header.stamp = ros::Time(timestamp);
140  vel_msg.twist.linear.x = vel[0];
141  vel_msg.twist.linear.y = vel[1];
142  vel_msg.twist.linear.z = vel[2];
143  vel_msg.twist.angular.x = vel[3];
144  vel_msg.twist.angular.y = vel[4];
145  vel_msg.twist.angular.z = vel[5];
146  vel_pub.publish(vel_msg);
147 
148 // ros::Duration(1e-3).sleep();
149 }
150 
151 void
152 RosAfma6Node::setCameraVel( const geometry_msgs::TwistStampedConstPtr &msg)
153 {
154  veltime = ros::Time::now();
155 
156  vpColVector vc(6); // Vel in m/s and rad/s
157 
158  vc[0] = msg->twist.linear.x;
159  vc[1] = msg->twist.linear.y;
160  vc[2] = msg->twist.linear.z;
161 
162  vc[3] = msg->twist.angular.x;
163  vc[4] = msg->twist.angular.y;
164  vc[5] = msg->twist.angular.z;
165 
166 // ROS_INFO( "Afma6 new camera vel at %f s: [%0.2f %0.2f %0.2f] m/s [%0.2f %0.2f %0.2f] rad/s",
167 // veltime.toSec(),
168 // vc[0], vc[1], vc[2], vc[3], vc[4], vc[5]);
169  robot->setVelocity(vpRobot::CAMERA_FRAME, vc);
170 
171 // this->publish();
172 }
173 
174 #endif // #ifdef VISP_HAVE_AFMA6
175 
176 int main( int argc, char** argv )
177 {
178 #ifdef VISP_HAVE_AFMA6
179  ros::init(argc,argv, "RosAfma6");
180  ros::NodeHandle n(std::string("~"));
181 
182  vpRingLight light;
183  light.on();
184 
185  RosAfma6Node *node = new RosAfma6Node(n);
186 
187  if( node->setup() != 0 )
188  {
189  printf( "Afma6 setup failed... \n" );
190  return -1;
191  }
192 
193  node->spin();
194 
195  delete node;
196 
197  light.off();
198 
199  printf( "\nQuitting... \n" );
200 #else
201  printf("This node is node available since ViSP was \nnot build with Afma6 robot support...\n");
202 #endif
203  return 0;
204 }
205 
RosAfma6Node(ros::NodeHandle n)
Definition: afma6.cpp:61
void spin()
Definition: afma6.cpp:111
void publish()
Definition: afma6.cpp:122
vpColVector q
Definition: afma6.cpp:57
std::string frame_id_odom
Definition: afma6.cpp:53
std::string frame_id_base_link
Definition: afma6.cpp:54
vpRobotAfma6 * robot
Definition: afma6.cpp:45
geometry_msgs::PoseStamped position
Definition: afma6.cpp:46
void setCameraVel(const geometry_msgs::TwistStampedConstPtr &)
Definition: afma6.cpp:152
int main(int argc, char **argv)
Definition: afma6.cpp:176
ros::Time veltime
Definition: afma6.cpp:41
ros::NodeHandle n
Definition: afma6.cpp:36
int setup()
Definition: afma6.cpp:100
ros::Publisher vel_pub
Definition: afma6.cpp:38
std::string tf_prefix
Definition: afma6.cpp:52
virtual ~RosAfma6Node()
Definition: afma6.cpp:91
vpHomogeneousMatrix wMc
Definition: afma6.cpp:56
ros::Subscriber cmd_camvel_sub
Definition: afma6.cpp:39
geometry_msgs::TransformStamped odom_trans
Definition: afma6.cpp:50
ros::Publisher pose_pub
Definition: afma6.cpp:37
tf::TransformBroadcaster odom_broadcaster
Definition: afma6.cpp:49
std::string serial_port
Definition: afma6.cpp:43


visp_ros
Author(s): Francois Pasteau, Fabien Spindler
autogenerated on Mon Mar 2 2015 01:32:56