viper650.cpp
Go to the documentation of this file.
1 #include <math.h>
2 #include <sstream>
3 #include <stdio.h>
4 
5 #include <geometry_msgs/Pose.h>
6 #include <geometry_msgs/PoseStamped.h>
7 #include <geometry_msgs/TwistStamped.h>
8 #include <nav_msgs/Odometry.h>
9 #include <ros/ros.h>
10 #include <sensor_msgs/JointState.h>
11 #include <std_msgs/Float64MultiArray.h>
12 #include <tf/tf.h>
14 #include <tf/transform_datatypes.h>
15 #include <tf/transform_listener.h>
16 
17 #include <visp3/core/vpHomogeneousMatrix.h>
18 #include <visp3/core/vpIoTools.h>
19 #include <visp3/core/vpMath.h>
20 #include <visp3/robot/vpRobotViper650.h>
21 
22 #include <visp_bridge/3dpose.h> // visp_bridge
23 
24 #ifdef VISP_HAVE_VIPER650
25 
27 {
28 public:
30  virtual ~RosViper650Node();
31 
32 public:
33  int setup();
34  void setCameraVel( const geometry_msgs::TwistStampedConstPtr & );
35  void setJointVel( const sensor_msgs::JointStateConstPtr & );
36  void setRefVel( const geometry_msgs::TwistStampedConstPtr & );
37  void spin();
38  void publish();
39 
40 protected:
49  std::string setControlMode; // "joint_space", "camera_frame" (default), "reference_frame"
50  std::string getStateSpace; // "joint_space", "camera_frame" (default), "reference_frame"
51  std::string cmdVelTopicName; // default to /cmd_vel
52  std::string endEffectorType; // "TOOL_PTGREY_FLEA2_CAMERA" (default), "TOOL_GENERIC_CAMERA", "TOOL_CUSTOM"
54 
56 
57  std::string serial_port;
58 
59  vpRobotViper650 *robot;
60  geometry_msgs::PoseStamped position;
61  sensor_msgs::JointState jointState;
62  std_msgs::Float64MultiArray jacobian;
63 
64  // for odom->base_link transform
66  geometry_msgs::TransformStamped odom_trans;
67  // for resolving tf names.
68  std::string tf_prefix;
69  std::string frame_id_odom;
70  std::string frame_id_base_link;
71 
72  vpHomogeneousMatrix wMc; // world to camera transformation
73  vpColVector q; // measured joint position
74 };
75 
77 {
78  // read in config options
79  n = nh;
80 
81  ROS_INFO( "Launch Viper650 robot ros node" );
82 
83  robot = NULL;
84  n.param< std::string >( "set_control_mode", setControlMode, "tool_frame" );
85  n.param< std::string >( "get_state_space", getStateSpace, "tool_frame" );
86  n.param< std::string >( "cmd_vel_topic_name", cmdVelTopicName, "cmd_vel" );
87  n.param< std::string >( "end_effector", endEffectorType, "TOOL_PTGREY_FLEA2_CAMERA" );
88  n.param< std::string >( "custom_tool_transformation_filename", customToolTransformationFileName, "" );
89 
90  /*
91  * Figure out what frame_id's to use. if a tf_prefix param is specified,
92  * it will be added to the beginning of the frame_ids.
93  *
94  * e.g. rosrun ... _tf_prefix:=MyRobot (or equivalently using <param>s in
95  * roslaunch files)
96  * will result in the frame_ids being set to /MyRobot/odom etc,
97  * rather than /odom. This is useful for Multi Robot Systems.
98  * See ROS Wiki for further details.
99  */
101  // frame_id_odom = tf::resolve(tf_prefix, "odom");
102  // frame_id_base_link = tf::resolve(tf_prefix, "base_link");
103 
104  // advertise services
105  // pose_pub = n.advertise<geometry_msgs::PoseStamped>("pose", 1000);
106  // vel_pub = n.advertise<geometry_msgs::TwistStamped>("velocity", 1000);
107  // jointState_pub = n.advertise<sensor_msgs::JointState>("joint_state", 1000);
108 
109  // subscribe to services
110  if ( setControlMode == "joint_space" )
111  {
112  ROS_INFO( "Viper650 robot controlled in joint space" );
113  jointState_pub = n.advertise< sensor_msgs::JointState >( "joint_state", 10 );
114  jacobian_pub = n.advertise< std_msgs::Float64MultiArray >( "jacobian", 10 );
116  (boost::function< void( const sensor_msgs::JointStateConstPtr & ) >)boost::bind(
117  &RosViper650Node::setJointVel, this, _1 ) );
118  }
119  else if ( setControlMode == "camera_frame" )
120  {
121  ROS_INFO( "Viper650 robot controlled in camera frame" );
122  pose_pub = n.advertise< geometry_msgs::PoseStamped >( "pose", 10 );
123  vel_pub = n.advertise< geometry_msgs::TwistStamped >( "velocity", 10 );
125  (boost::function< void( const geometry_msgs::TwistStampedConstPtr & ) >)boost::bind(
126  &RosViper650Node::setCameraVel, this, _1 ) );
127  }
128  else if ( setControlMode == "reference_frame" )
129  {
130  ROS_INFO( "Viper650 robot controlled in reference frame" );
131  pose_pub = n.advertise< geometry_msgs::PoseStamped >( "pose", 10 );
132  vel_pub = n.advertise< geometry_msgs::TwistStamped >( "velocity", 10 );
134  (boost::function< void( const geometry_msgs::TwistStampedConstPtr & ) >)boost::bind(
135  &RosViper650Node::setRefVel, this, _1 ) );
136  }
137 }
138 
140 {
141  if ( robot )
142  {
143  robot->stopMotion();
144  delete robot;
145  robot = NULL;
146  }
147 }
148 
149 int
151 {
152  robot = new vpRobotViper650;
153 
154  if ( endEffectorType == "TOOL_PTGREY_FLEA2_CAMERA" )
155  {
156  robot->init( vpViper650::TOOL_PTGREY_FLEA2_CAMERA, vpCameraParameters::perspectiveProjWithDistortion );
157  }
158  else if ( endEffectorType == "TOOL_GENERIC_CAMERA" )
159  {
160  robot->init( vpViper650::TOOL_GENERIC_CAMERA, vpCameraParameters::perspectiveProjWithDistortion );
161  }
162  else if ( endEffectorType == "TOOL_CUSTOM" )
163  {
164  if ( vpIoTools::checkFilename( customToolTransformationFileName ) == false )
165  {
166  ROS_ERROR( "Viper650: Missing or bad filename for eMt custom tool transformation" );
167  return -1;
168  }
169 
170  vpHomogeneousMatrix eMt;
171  std::ifstream f( customToolTransformationFileName.c_str() );
172  try
173  {
174  eMt.load( f );
175  f.close();
176  }
177  catch ( vpException &e )
178  {
179  ROS_ERROR_STREAM( "Viper650: Cannot load eMt custom tool transformation from \""
180  << customToolTransformationFileName << "\": " << e.getStringMessage() );
181  f.close();
182  return -1;
183  }
184 
185  robot->init( vpViper650::TOOL_CUSTOM, eMt );
186  }
187 
188  robot->setRobotState( vpRobot::STATE_VELOCITY_CONTROL );
189 
190  return 0;
191 }
192 
193 void
195 {
196  ros::Rate loop_rate( 100 );
197  while ( ros::ok() )
198  {
199  this->publish();
200  ros::spinOnce();
201  loop_rate.sleep();
202  }
203 }
204 
205 void
207 {
208  double timestamp;
209  robot->getPosition( vpRobot::ARTICULAR_FRAME, q, timestamp );
210 
211  if ( getStateSpace == "joint_space" )
212  {
213  vpColVector qdot;
214  robot->getVelocity( vpRobot::ARTICULAR_FRAME, qdot, timestamp );
215  jointState.position.clear();
216  jointState.velocity.clear();
217  jointState.header.stamp = ros::Time( timestamp );
218  for ( unsigned int i = 0; i < qdot.size(); i++ )
219  {
220  jointState.position.push_back( q[i] );
221  jointState.velocity.push_back( qdot[i] );
222  }
224 
225  vpMatrix eJe;
226  robot->get_eJe( eJe );
227  vpHomogeneousMatrix eMc;
228  robot->get_eMc( eMc );
229  vpMatrix cJc = vpVelocityTwistMatrix( eMc.inverse() ) * eJe;
230 
231  jacobian.data.clear();
232  jacobian.layout.dim.resize( 2 );
233 
234  jacobian.layout.dim[0].label = "height";
235  jacobian.layout.dim[0].size = cJc.getRows();
236  jacobian.layout.dim[0].stride = cJc.size();
237  jacobian.layout.dim[1].label = "width";
238  jacobian.layout.dim[1].size = cJc.getCols();
239  jacobian.layout.dim[1].stride = cJc.getCols();
240  for ( unsigned int i = 0; i < cJc.size(); i++ )
241  jacobian.data.push_back( cJc.data[i] );
243  }
244  else if ( getStateSpace == "camera_frame" )
245  {
246  wMc = robot->get_fMc( q );
248  position.header.stamp = ros::Time( timestamp ); // to improve: should be the timestamp returned by getPosition()
249 
250  // ROS_INFO( "Viper650 publish pose at %f s: [%0.2f %0.2f %0.2f] - [%0.2f %0.2f %0.2f %0.2f]",
251  // position.header.stamp.toSec(),
252  // position.pose.position.x, position.pose.position.y, position.pose.position.z,
253  // position.pose.orientation.w, position.pose.orientation.x, position.pose.orientation.y,
254  // position.pose.orientation.z);
256 
257  vpColVector vel( 6 );
258  robot->getVelocity( vpRobot::CAMERA_FRAME, vel, timestamp );
259  geometry_msgs::TwistStamped vel_msg;
260  vel_msg.header.stamp = ros::Time( timestamp );
261  vel_msg.twist.linear.x = vel[0];
262  vel_msg.twist.linear.y = vel[1];
263  vel_msg.twist.linear.z = vel[2];
264  vel_msg.twist.angular.x = vel[3];
265  vel_msg.twist.angular.y = vel[4];
266  vel_msg.twist.angular.z = vel[5];
267  vel_pub.publish( vel_msg );
268  }
269  else if ( getStateSpace == "reference_frame" )
270  {
271  wMc = robot->get_fMc( q );
273  position.header.stamp = ros::Time( timestamp ); // to improve: should be the timestamp returned by getPosition()
274 
275  // ROS_INFO( "Viper650 publish pose at %f s: [%0.2f %0.2f %0.2f] - [%0.2f %0.2f %0.2f %0.2f]",
276  // position.header.stamp.toSec(),
277  // position.pose.position.x, position.pose.position.y, position.pose.position.z,
278  // position.pose.orientation.w, position.pose.orientation.x, position.pose.orientation.y,
279  // position.pose.orientation.z);
281 
282  vpColVector vel( 6 );
283  robot->getVelocity( vpRobot::REFERENCE_FRAME, vel, timestamp );
284  geometry_msgs::TwistStamped vel_msg;
285  vel_msg.header.stamp = ros::Time( timestamp );
286  vel_msg.twist.linear.x = vel[0];
287  vel_msg.twist.linear.y = vel[1];
288  vel_msg.twist.linear.z = vel[2];
289  vel_msg.twist.angular.x = vel[3];
290  vel_msg.twist.angular.y = vel[4];
291  vel_msg.twist.angular.z = vel[5];
292  vel_pub.publish( vel_msg );
293  }
294 }
295 
296 void
297 RosViper650Node::setCameraVel( const geometry_msgs::TwistStampedConstPtr &msg )
298 {
300 
301  vpColVector vc( 6 ); // Vel in m/s and rad/s
302 
303  vc[0] = msg->twist.linear.x;
304  vc[1] = msg->twist.linear.y;
305  vc[2] = msg->twist.linear.z;
306 
307  vc[3] = msg->twist.angular.x;
308  vc[4] = msg->twist.angular.y;
309  vc[5] = msg->twist.angular.z;
310 
311  ROS_INFO( "Viper650 new camera vel at %f s: [%0.2f %0.2f %0.2f] m/s [%0.2f %0.2f %0.2f] rad/s", veltime.toSec(),
312  vc[0], vc[1], vc[2], vc[3], vc[4], vc[5] );
313  robot->setVelocity( vpRobot::CAMERA_FRAME, vc );
314 }
315 
316 void
317 RosViper650Node::setJointVel( const sensor_msgs::JointStateConstPtr &msg )
318 {
320 
321  if ( msg->velocity.size() != 6 )
322  {
323  ROS_ERROR( "Viper650: Cannot apply a joint velocity vector that is not 6 dimensional" );
324  return;
325  }
326  vpColVector qdot( 6 ); // Vel in rad/s for each joint
327 
328  for ( unsigned int i = 0; i < msg->velocity.size(); i++ )
329  qdot[i] = msg->velocity[i];
330 
331  ROS_INFO( "Viper650 new joint vel at %f s: [%0.2f %0.2f %0.2f %0.2f %0.2f %0.2f] rad/s", veltime.toSec(), qdot[0],
332  qdot[1], qdot[2], qdot[3], qdot[4], qdot[5] );
333 
334  robot->setVelocity( vpRobot::ARTICULAR_FRAME, qdot );
335 }
336 
337 void
338 RosViper650Node::setRefVel( const geometry_msgs::TwistStampedConstPtr &msg )
339 {
341 
342  vpColVector vref( 6 ); // Vel in m/s and rad/s
343 
344  vref[0] = msg->twist.linear.x;
345  vref[1] = msg->twist.linear.y;
346  vref[2] = msg->twist.linear.z;
347 
348  vref[3] = msg->twist.angular.x;
349  vref[4] = msg->twist.angular.y;
350  vref[5] = msg->twist.angular.z;
351 
352  ROS_INFO( "Viper650 new reference vel at %f s: [%0.2f %0.2f %0.2f] m/s [%0.2f %0.2f %0.2f] rad/s", veltime.toSec(),
353  vref[0], vref[1], vref[2], vref[3], vref[4], vref[5] );
354  robot->setVelocity( vpRobot::REFERENCE_FRAME, vref );
355 }
356 
357 #endif // #ifdef VISP_HAVE_Viper650
358 
359 int
360 main( int argc, char **argv )
361 {
362 #ifdef VISP_HAVE_VIPER650
363  ros::init( argc, argv, "RosViper650" );
364  ros::NodeHandle n( std::string( "~" ) );
365 
366  RosViper650Node *node = new RosViper650Node( n );
367 
368  if ( node->setup() != 0 )
369  {
370  printf( "Viper650 setup failed... \n" );
371  return -1;
372  }
373 
374  node->spin();
375 
376  delete node;
377 
378  printf( "\nQuitting... \n" );
379 #else
380  printf( "The Viper650 robot is not supported by ViSP...\n" );
381 #endif
382  return 0;
383 }
RosViper650Node
Definition: viper650.cpp:26
ros::Publisher
RosViper650Node::veltime
ros::Time veltime
Definition: viper650.cpp:55
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
RosViper650Node::robot
vpRobotViper650 * robot
Definition: viper650.cpp:59
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
RosViper650Node::endEffectorType
std::string endEffectorType
Definition: viper650.cpp:52
ros.h
ros::spinOnce
ROSCPP_DECL void spinOnce()
RosViper650Node::serial_port
std::string serial_port
Definition: viper650.cpp:57
TimeBase< Time, Duration >::toSec
double toSec() const
RosViper650Node::wMc
vpHomogeneousMatrix wMc
Definition: viper650.cpp:72
RosViper650Node::getStateSpace
std::string getStateSpace
Definition: viper650.cpp:50
main
int main(int argc, char **argv)
Definition: viper650.cpp:360
RosViper650Node::setControlMode
std::string setControlMode
Definition: viper650.cpp:49
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
ros::ok
ROSCPP_DECL bool ok()
RosViper650Node::publish
void publish()
Definition: viper650.cpp:206
transform_broadcaster.h
f
f
RosViper650Node::odom_broadcaster
tf::TransformBroadcaster odom_broadcaster
Definition: viper650.cpp:65
RosViper650Node::vel_pub
ros::Publisher vel_pub
Definition: viper650.cpp:43
RosViper650Node::n
ros::NodeHandle n
Definition: viper650.cpp:41
RosViper650Node::setCameraVel
void setCameraVel(const geometry_msgs::TwistStampedConstPtr &)
Definition: viper650.cpp:297
tf::TransformBroadcaster
tf::getPrefixParam
std::string getPrefixParam(ros::NodeHandle &nh)
RosViper650Node::frame_id_odom
std::string frame_id_odom
Definition: viper650.cpp:69
RosViper650Node::q
vpColVector q
Definition: viper650.cpp:73
3dpose.h
RosViper650Node::setup
int setup()
Definition: viper650.cpp:150
ROS_ERROR
#define ROS_ERROR(...)
RosViper650Node::tf_prefix
std::string tf_prefix
Definition: viper650.cpp:68
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
ros::Rate::sleep
bool sleep()
RosViper650Node::frame_id_base_link
std::string frame_id_base_link
Definition: viper650.cpp:70
RosViper650Node::cmd_jointvel_sub
ros::Subscriber cmd_jointvel_sub
Definition: viper650.cpp:47
RosViper650Node::~RosViper650Node
virtual ~RosViper650Node()
Definition: viper650.cpp:139
visp_bridge::toGeometryMsgsPose
geometry_msgs::Pose toGeometryMsgsPose(const vpHomogeneousMatrix &mat)
transform_listener.h
tf.h
transform_datatypes.h
ros::Time
RosViper650Node::odom_trans
geometry_msgs::TransformStamped odom_trans
Definition: viper650.cpp:66
RosViper650Node::position
geometry_msgs::PoseStamped position
Definition: viper650.cpp:60
RosViper650Node::customToolTransformationFileName
std::string customToolTransformationFileName
Definition: viper650.cpp:53
RosViper650Node::setJointVel
void setJointVel(const sensor_msgs::JointStateConstPtr &)
Definition: viper650.cpp:317
RosViper650Node::cmdVelTopicName
std::string cmdVelTopicName
Definition: viper650.cpp:51
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
ros::Rate
RosViper650Node::jacobian_pub
ros::Publisher jacobian_pub
Definition: viper650.cpp:45
RosViper650Node::RosViper650Node
RosViper650Node(ros::NodeHandle n)
Definition: viper650.cpp:76
RosViper650Node::cmd_refvel_sub
ros::Subscriber cmd_refvel_sub
Definition: viper650.cpp:48
RosViper650Node::jacobian
std_msgs::Float64MultiArray jacobian
Definition: viper650.cpp:62
ROS_INFO
#define ROS_INFO(...)
RosViper650Node::setRefVel
void setRefVel(const geometry_msgs::TwistStampedConstPtr &)
Definition: viper650.cpp:338
RosViper650Node::jointState_pub
ros::Publisher jointState_pub
Definition: viper650.cpp:44
RosViper650Node::spin
void spin()
Definition: viper650.cpp:194
ros::NodeHandle
ros::Subscriber
RosViper650Node::cmd_camvel_sub
ros::Subscriber cmd_camvel_sub
Definition: viper650.cpp:46
RosViper650Node::pose_pub
ros::Publisher pose_pub
Definition: viper650.cpp:42
RosViper650Node::jointState
sensor_msgs::JointState jointState
Definition: viper650.cpp:61
ros::Time::now
static Time now()


visp_ros
Author(s): Francois Pasteau, Fabien Spindler, Gatien Gaumerais, Alexander Oliva
autogenerated on Wed Mar 2 2022 01:13:33