visual_servo_nodelet.cpp
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * This file is part of the ViSP software.
4  * Copyright (C) 2019 by INRIA. All rights reserved.
5  *
6  * This software is free software; you can redistribute it and/or
7  * modify it under the terms of the GNU General Public License
8  * ("GPL") version 2 as published by the Free Software Foundation.
9  * See the file LICENSE.txt at the root directory of this source
10  * distribution for additional information about the GNU GPL.
11  *
12  * For using ViSP with software that can not be combined with the GNU
13  * GPL, please contact INRIA about acquiring a ViSP Professional
14  * Edition License.
15  *
16  * See http://visp.inria.fr/ for more information.
17  *
18  * This software was developed at:
19  * INRIA Rennes - Bretagne Atlantique
20  * Campus Universitaire de Beaulieu
21  * 35042 Rennes Cedex
22  * France
23  * https://team.inria.fr/rainbow/fr/
24  *
25  * If you have questions regarding the use of this file, please contact
26  * INRIA at visp@inria.fr
27  *
28  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
29  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
30  *
31  * Description:
32  * Visual servoing nodelet to control Parrot Bebop 2 drone.
33  *
34  * Authors:
35  * Gatien Gaumerais
36  * Fabien Spindler
37  *
38  *****************************************************************************/
39 
40 #include <ros/ros.h>
41 
42 #include <nodelet/nodelet.h>
44 
45 #include <geometry_msgs/Pose.h>
46 #include <geometry_msgs/PoseArray.h>
47 #include <geometry_msgs/Twist.h>
48 
49 #include <cv_bridge/cv_bridge.h>
52 
53 #include <visp3/core/vpConfig.h>
54 #include <visp3/core/vpExponentialMap.h>
55 #include <visp3/core/vpImageConvert.h>
56 #include <visp3/core/vpMomentAreaNormalized.h>
57 #include <visp3/core/vpMomentBasic.h>
58 #include <visp3/core/vpMomentCentered.h>
59 #include <visp3/core/vpMomentDatabase.h>
60 #include <visp3/core/vpMomentGravityCenter.h>
61 #include <visp3/core/vpMomentGravityCenterNormalized.h>
62 #include <visp3/core/vpMomentObject.h>
63 #include <visp3/core/vpPixelMeterConversion.h>
64 #include <visp3/core/vpPoint.h>
65 #include <visp3/core/vpTime.h>
66 #include <visp3/detection/vpDetectorAprilTag.h>
67 #include <visp3/gui/vpDisplayX.h>
68 #include <visp3/visual_features/vpFeatureBuilder.h>
69 #include <visp3/visual_features/vpFeatureMomentAreaNormalized.h>
70 #include <visp3/visual_features/vpFeatureMomentGravityCenterNormalized.h>
71 #include <visp3/visual_features/vpFeatureVanishingPoint.h>
72 #include <visp3/vs/vpServo.h>
73 #include <visp3/vs/vpServoDisplay.h>
74 
75 #include <iostream>
76 #include <string>
77 
78 #if VISP_VERSION_INT > VP_VERSION_INT( 3, 2, 0 ) // ViSP >= 3.0.0
79 
80 static double
81 getTagSize( ros::NodeHandle nh )
82 {
83  double res = 0;
84 
85  if ( nh.hasParam( "/vs/tagSize" ) )
86  {
87  nh.getParam( "/vs/tagSize", res );
88  return res;
89  }
90  else
91  {
92  ROS_WARN( "No tag size parameter has been found, using default value : 0.14 meters." );
93  return 0.14;
94  }
95 }
96 
97 static double
98 getDistanceToTag( ros::NodeHandle nh )
99 {
100  double res = 0;
101  if ( nh.hasParam( "/vs/distanceToTag" ) )
102  {
103  nh.getParam( "/vs/distanceToTag", res );
104  return res;
105  }
106  else
107  {
108  ROS_WARN( "No distance to tag parameter has been found, using default value : 1.5 meters." );
109  return 1.5;
110  }
111 }
112 
113 bool
114 compareImagePoint( std::pair< size_t, vpImagePoint > p1, std::pair< size_t, vpImagePoint > p2 )
115 {
116  return ( p1.second.get_v() < p2.second.get_v() );
117 }
118 
119 class bebopVSNodelet : public nodelet::Nodelet
120 {
121 public:
122  bebopVSNodelet();
123  virtual ~bebopVSNodelet();
124 
125  virtual void onInit();
126 
127  void imageCallback( const sensor_msgs::ImageConstPtr &msg );
128 
129 private:
130  ros::NodeHandle m_nh;
131  ros::Publisher m_pubTwist;
132  ros::Subscriber m_subImg;
133  ros::Publisher m_pubCam;
134 
135  bool bebop_has_been_setup;
136 
137  vpDisplayX m_display;
138  bool m_display_setup;
139  vpImage< unsigned char > I;
140 
141  double m_tagSize;
142  double m_Z_d;
143 
144  double m_cameraTilt;
145  double m_cameraPan;
146 
147  vpServo m_task;
148  vpDetectorAprilTag m_detector;
149  vpCameraParameters m_cam;
150 
151  bool m_vec_ip_has_been_sorted;
152  std::vector< std::pair< size_t, vpImagePoint > > m_vec_ip_sorted;
153 
154  vpVelocityTwistMatrix m_cVe;
155  vpMatrix m_eJe;
156 
157  double area;
158 
159  // Desired plane
160  double A;
161  double B;
162  double C;
163 
164  vpMomentObject m_obj, m_obj_d;
165  vpMomentDatabase mdb, mdb_d;
166  vpMomentBasic mb_d;
167  vpMomentGravityCenter mg, mg_d;
168  vpMomentCentered mc, mc_d;
169  vpMomentAreaNormalized man, man_d;
170  vpMomentGravityCenterNormalized mgn, mgn_d;
171 
172  vpFeatureMomentGravityCenterNormalized s_mgn, s_mgn_d;
173  vpFeatureMomentAreaNormalized s_man, s_man_d;
174  vpFeatureVanishingPoint s_vp, s_vp_d;
175 
176  void initVS();
177  vpColVector velocityToPosition( vpColVector &vel_cmd, double delta_t );
178 };
179 
180 PLUGINLIB_EXPORT_CLASS( bebopVSNodelet, nodelet::Nodelet )
181 
182 bebopVSNodelet::bebopVSNodelet()
183  : bebop_has_been_setup( false )
184  , m_display_setup( false )
185  , m_tagSize( getTagSize( m_nh ) ) // Fetching theses values
186  , m_Z_d( getDistanceToTag( m_nh ) ) // from the parameter server
187  , m_cameraTilt( 0.0 )
188  , m_cameraPan( 0.0 )
189  , m_detector( vpDetectorAprilTag::TAG_36h11 )
190  , m_vec_ip_has_been_sorted( false )
191  , m_eJe( vpMatrix( 6, 4, 0 ) )
192  , area( 0 )
193  , A( 0.0 )
194  , B( 0.0 )
195  , C( 1.0 / m_Z_d )
196  , m_obj( 3 )
197  , m_obj_d( 3 )
198  , man( 0, m_Z_d )
199  , man_d( 0, m_Z_d )
200  , s_mgn( mdb, A, B, C )
201  , s_mgn_d( mdb_d, A, B, C )
202  , s_man( mdb, A, B, C )
203  , s_man_d( mdb_d, A, B, C )
204 {
205 }
206 
207 bebopVSNodelet::~bebopVSNodelet() { m_task.kill(); }
208 
209 void
210 bebopVSNodelet::onInit()
211 {
212 
213  m_nh = getNodeHandle();
214  std::stringstream params_str;
215  params_str << "TAG PARAMETERS (meters) : tagSize : " << m_tagSize << " - distanceToTag : " << m_Z_d << std::endl;
216  NODELET_INFO( "%s", params_str.str().c_str() );
217 
218  initVS();
219 
220  NODELET_INFO( "Setting up publisher and subscriber..." );
221  m_pubTwist = m_nh.advertise< geometry_msgs::Twist >( "cmd_moveby", 1000 );
222  m_subImg = m_nh.subscribe( "image_raw", 1000, &bebopVSNodelet::imageCallback, this );
223  m_pubCam = m_nh.advertise< geometry_msgs::Twist >( "camera_control", 1000 );
224  NODELET_INFO( "Publisher and subscriber set up. Waiting for image callbacks..." );
225 }
226 
227 void
228 bebopVSNodelet::imageCallback( const sensor_msgs::ImageConstPtr &msg )
229 {
230  if ( !bebop_has_been_setup )
231  {
232  geometry_msgs::Twist out_cam_ctrl;
233  out_cam_ctrl.linear.x = 0;
234  out_cam_ctrl.linear.y = 0;
235  out_cam_ctrl.linear.z = 0;
236  out_cam_ctrl.angular.x = 0;
237  out_cam_ctrl.angular.y = m_cameraTilt;
238  out_cam_ctrl.angular.z = m_cameraPan;
239  m_pubCam.publish( out_cam_ctrl );
240 
241  bebop_has_been_setup = true;
242  NODELET_INFO( "Setting desired camera orientation..." );
243  }
244 
245  const cv::Mat frame = cv_bridge::toCvShare( msg, sensor_msgs::image_encodings::BGR8 )->image;
246  vpImageConvert::convert( frame, I );
247 
248  if ( !m_display_setup )
249  {
250  m_display.init( I, 100, 100, "DRONE VIEW" );
251  m_display_setup = true;
252  }
253  vpDisplay::display( I );
254 
255  std::vector< vpHomogeneousMatrix > cMo_vec;
256  m_detector.detect( I, m_tagSize, m_cam, cMo_vec ); // Detect AprilTags in current image
257 
258  geometry_msgs::Twist out_cmd_pos;
259 
260  if ( m_detector.getNbObjects() == 1 )
261  {
262  // Update current points used to compute the moments
263  std::vector< vpImagePoint > vec_ip = m_detector.getPolygon( 0 );
264  std::vector< vpPoint > vec_P;
265  for ( size_t i = 0; i < vec_ip.size(); i++ )
266  { // size = 4
267  double x = 0, y = 0;
268  vpPixelMeterConversion::convertPoint( m_cam, vec_ip[i], x, y );
269  vpPoint P;
270  P.set_x( x );
271  P.set_y( y );
272  vec_P.push_back( P );
273  }
274 
275  // Current moments
276  m_obj.setType( vpMomentObject::DENSE_POLYGON ); // Consider the AprilTag as a polygon
277  m_obj.fromVector( vec_P ); // Initialize the object with the points coordinates
278 
279  mg.linkTo( mdb ); // Add gravity center to database
280  mc.linkTo( mdb ); // Add centered moments to database
281  man.linkTo( mdb ); // Add area normalized to database
282  mgn.linkTo( mdb ); // Add gravity center normalized to database
283  mdb.updateAll( m_obj ); // All of the moments must be updated, not just an_d
284  mg.compute(); // Compute gravity center moment
285  mc.compute(); // Compute centered moments AFTER gravity center
286  man.setDesiredArea( area ); // Desired area was init at 0 (unknow at contruction), need to be updated here
287  man.compute(); // Compute area normalized moment AFTER centered moment
288  mgn.compute(); // Compute gravity center normalized moment AFTER area normalized moment
289 
290  s_mgn.update( A, B, C );
291  s_mgn.compute_interaction();
292  s_man.update( A, B, C );
293  s_man.compute_interaction();
294 
295  /* Sort points from their height in the image, and keep original indexes.
296  This is done once, in order to be independent from the orientation of the tag
297  when detecting vanishing points. */
298  if ( !m_vec_ip_has_been_sorted )
299  {
300  for ( size_t i = 0; i < vec_ip.size(); i++ )
301  {
302  // Add the points and their corresponding index
303  std::pair< size_t, vpImagePoint > index_pair = std::pair< size_t, vpImagePoint >( i, vec_ip[i] );
304  m_vec_ip_sorted.push_back( index_pair );
305  }
306 
307  // Sort the points and indexes from the v value of the points
308  std::sort( m_vec_ip_sorted.begin(), m_vec_ip_sorted.end(), compareImagePoint );
309 
310  m_vec_ip_has_been_sorted = true;
311  }
312 
313  // Use the two highest points for the first line, and the two others for the second line.
314  vpFeatureBuilder::create( s_vp, m_cam, vec_ip[m_vec_ip_sorted[0].first], vec_ip[m_vec_ip_sorted[1].first],
315  vec_ip[m_vec_ip_sorted[2].first], vec_ip[m_vec_ip_sorted[3].first],
316  vpFeatureVanishingPoint::selectAtanOneOverRho() );
317 
318  m_task.set_cVe( m_cVe );
319  m_task.set_eJe( m_eJe );
320 
321  // Compute the control law. Velocities are computed in the mobile robot reference frame
322  vpColVector ve = m_task.computeControlLaw();
323  std::stringstream ve_str;
324  ve_str << "ve: " << ve.t() << std::endl;
325  NODELET_INFO( "%s", ve_str.str().c_str() );
326 
327  // Computing the corresponding displacement
328  vpColVector cmd_pos = velocityToPosition( ve, 1.0 );
329 
330  // Sending the movement command to the drone
331 
332  out_cmd_pos.linear.x = cmd_pos[0];
333  out_cmd_pos.linear.y = cmd_pos[1];
334  out_cmd_pos.linear.z = cmd_pos[2];
335  out_cmd_pos.angular.x = 0;
336  out_cmd_pos.angular.y = 0;
337  out_cmd_pos.angular.z = cmd_pos[3];
338  m_pubTwist.publish( out_cmd_pos );
339 
340  for ( size_t i = 0; i < 4; i++ )
341  {
342  vpDisplay::displayCross( I, vec_ip[i], 15, vpColor::red, 1 );
343  std::stringstream ss;
344  ss << i;
345  vpDisplay::displayText( I, vec_ip[i] + vpImagePoint( 15, 15 ), ss.str(), vpColor::green );
346  }
347 
348  // Display visual features
349  vpDisplay::displayPolygon( I, vec_ip, vpColor::green,
350  3 ); // Current polygon used to compure an moment
351  vpDisplay::displayCross( I, m_detector.getCog( 0 ), 15, vpColor::green,
352  3 ); // Current polygon used to compute a moment
353  vpDisplay::displayLine( I, 0, static_cast< int >( m_cam.get_u0() ), static_cast< int >( I.getHeight() ) - 1,
354  static_cast< int >( m_cam.get_u0() ), vpColor::red,
355  3 ); // Vertical line as desired x position
356  vpDisplay::displayLine( I, static_cast< int >( m_cam.get_v0() ), 0, static_cast< int >( m_cam.get_v0() ),
357  static_cast< int >( I.getWidth() ) - 1, vpColor::red,
358  3 ); // Horizontal line as desired y position
359 
360  // Display lines corresponding to the vanishing point for the horizontal lines
361  vpDisplay::displayLine( I, vec_ip[m_vec_ip_sorted[0].first], vec_ip[m_vec_ip_sorted[1].first], vpColor::red, 1,
362  false );
363  vpDisplay::displayLine( I, vec_ip[m_vec_ip_sorted[2].first], vec_ip[m_vec_ip_sorted[3].first], vpColor::red, 1,
364  false );
365 
366  vpDisplay::displayText( I, 10, 10, "Click to exit", vpColor::red );
367  vpDisplay::flush( I );
368  }
369  else
370  {
371 
372  std::stringstream sserr;
373  sserr << "Failed to detect an Apriltag, or detected multiple ones";
374  vpDisplay::displayText( I, 120, 20, sserr.str(), vpColor::red );
375  vpDisplay::flush( I );
376 
377  // Stoping drone movement
378  out_cmd_pos.linear.x = 0;
379  out_cmd_pos.linear.y = 0;
380  out_cmd_pos.linear.z = 0;
381  out_cmd_pos.angular.x = 0;
382  out_cmd_pos.angular.y = 0;
383  out_cmd_pos.angular.z = 0;
384  m_pubTwist.publish( out_cmd_pos );
385  }
386 }
387 
388 void
389 bebopVSNodelet::initVS()
390 {
391  NODELET_INFO( "Setting up visual servoing..." );
392 
393  m_detector.setAprilTagQuadDecimate( 4.0 );
394  m_detector.setAprilTagNbThreads( 4 );
395  m_detector.setDisplayTag( true );
396 
397  m_cam.initPersProjWithoutDistortion( 531.9213063, 520.8495788, 429.133986, 240.9464457 );
398  m_cam.printParameters();
399 
400  // double lambda = 0.5;
401  vpAdaptiveGain lambda = vpAdaptiveGain( 1.5, 0.7, 30 );
402  m_task.setServo( vpServo::EYEINHAND_L_cVe_eJe );
403  m_task.setInteractionMatrixType( vpServo::CURRENT );
404  m_task.setLambda( lambda );
405 
406  if ( m_nh.hasParam( "/vs/cameraTilt" ) )
407  {
408  m_nh.getParam( "/vs/cameraTilt", m_cameraTilt );
409  }
410  else
411  {
412  ROS_WARN( "No camera tilt value found, using default value : -15 degrees." );
413  m_cameraTilt = -15.0;
414  }
415 
416  if ( m_nh.hasParam( "/vs/cameraPan" ) )
417  {
418  m_nh.getParam( "/vs/cameraPan", m_cameraPan );
419  }
420  else
421  {
422  ROS_WARN( "No camera pan value found, using default value : 0 degrees." );
423  m_cameraPan = 0.0;
424  }
425 
426  std::stringstream camparams_str;
427  camparams_str << "CAMERA PARAMETERS (degrees) : camera Tilt : " << m_cameraTilt << " - camera pan : " << m_cameraPan
428  << std::endl;
429  NODELET_INFO( "%s", camparams_str.str().c_str() );
430 
431  vpRxyzVector c1_rxyz_c2( vpMath::rad( m_cameraTilt ), vpMath::rad( m_cameraPan ), 0 );
432 
433  vpRotationMatrix c1Rc2( c1_rxyz_c2 ); // Rotation between camera 1 and 2
434  vpHomogeneousMatrix c1Mc2( vpTranslationVector(), c1Rc2 ); // Homogeneous matrix between c1 and c2
435 
436  vpRotationMatrix c1Re{ 0, 1, 0, 0, 0, 1, 1, 0, 0 }; // Rotation between camera 1 and E
437  vpTranslationVector c1te( 0, 0, -0.09 ); // Translation between camera 1 and E
438  vpHomogeneousMatrix c1Me( c1te, c1Re ); // Homogeneous matrix between c1 and E
439 
440  vpHomogeneousMatrix c2Me = c1Mc2.inverse() * c1Me; // Homogeneous matrix between c2 and E
441 
442  // vpVelocityTwistMatrix
443  m_cVe = vpVelocityTwistMatrix( c2Me );
444  m_task.set_cVe( m_cVe );
445 
446  m_eJe[0][0] = 1;
447  m_eJe[1][1] = 1;
448  m_eJe[2][2] = 1;
449  m_eJe[5][3] = 1;
450 
451  // Define the desired polygon corresponding the the AprilTag CLOCKWISE
452  double X[4] = { m_tagSize / 2., m_tagSize / 2., -m_tagSize / 2., -m_tagSize / 2. };
453  double Y[4] = { m_tagSize / 2., -m_tagSize / 2., -m_tagSize / 2., m_tagSize / 2. };
454 
455  std::vector< vpPoint > vec_P, vec_P_d;
456  for ( int i = 0; i < 4; i++ )
457  {
458  vpPoint P_d( X[i], Y[i], 0 );
459  vpHomogeneousMatrix cdMo( 0, 0, m_Z_d, 0, 0, 0 );
460  P_d.track( cdMo ); //
461  vec_P_d.push_back( P_d );
462  }
463 
464  // Desired moments
465  m_obj_d.setType( vpMomentObject::DENSE_POLYGON ); // Consider the AprilTag as a polygon
466  m_obj_d.fromVector( vec_P_d ); // Initialize the object with the points coordinates
467 
468  mb_d.linkTo( mdb_d ); // Add basic moments to database
469  mg_d.linkTo( mdb_d ); // Add gravity center to database
470  mc_d.linkTo( mdb_d ); // Add centered moments to database
471  man_d.linkTo( mdb_d ); // Add area normalized to database
472  mgn_d.linkTo( mdb_d ); // Add gravity center normalized to database
473  mdb_d.updateAll( m_obj_d ); // All of the moments must be updated, not just an_d
474  mg_d.compute(); // Compute gravity center moment
475  mc_d.compute(); // Compute centered moments AFTER gravity center
476 
477  if ( m_obj_d.getType() == vpMomentObject::DISCRETE )
478  area = mb_d.get( 2, 0 ) + mb_d.get( 0, 2 );
479  else
480  area = mb_d.get( 0, 0 );
481  // Update moment with the desired area
482  man_d.setDesiredArea( area );
483 
484  man_d.compute(); // Compute area normalized moment AFTER centered moments
485  mgn_d.compute(); // Compute gravity center normalized moment AFTER area normalized moment
486 
487  // Add the features
488  m_task.addFeature( s_mgn, s_mgn_d );
489  m_task.addFeature( s_man, s_man_d );
490  m_task.addFeature( s_vp, s_vp_d, vpFeatureVanishingPoint::selectAtanOneOverRho() );
491 
492  // Update desired gravity center normalized feature
493  s_mgn_d.update( A, B, C );
494  s_mgn_d.compute_interaction();
495  // Update desired area normalized feature
496  s_man_d.update( A, B, C );
497  s_man_d.compute_interaction();
498 
499  // Update desired vanishing point feature for the horizontal line
500  s_vp_d.setAtanOneOverRho( 0 );
501  s_vp_d.setAlpha( 0 );
502 
503  NODELET_INFO( "Visual servoing settup." );
504 }
505 
506 vpColVector
507 bebopVSNodelet::velocityToPosition( vpColVector &vel_cmd, double delta_t )
508 {
509  vpColVector res;
510  if ( vel_cmd.size() != 4 )
511  {
512  ROS_ERROR( "Can't compute velocity : dimension of the velocity vector should be equal to 4." );
513  res << 0., 0., 0., 0.;
514  return res;
515  }
516 
517  vpColVector ve( 6 );
518 
519  ve[0] = vel_cmd[0];
520  ve[1] = vel_cmd[1];
521  ve[2] = vel_cmd[2];
522  ve[5] = vel_cmd[3];
523 
524  vpHomogeneousMatrix M = vpExponentialMap::direct( ve, delta_t );
525 
526  double epsilon = ( std::numeric_limits< double >::epsilon() );
527  if ( std::abs( M.getRotationMatrix().getThetaUVector()[0] ) >= epsilon )
528  {
529  ROS_ERROR( "Can't compute velocity : rotation around X axis should be 0." );
530  res << 0., 0., 0., 0.;
531  return res;
532  }
533  if ( std::abs( M.getRotationMatrix().getThetaUVector()[1] ) >= epsilon )
534  {
535  ROS_ERROR( "Can't compute velocity : rotation around Y axis should be 0." );
536  res << 0., 0., 0., 0.;
537  return res;
538  }
539 
540  float dThetaZ = static_cast< float >( M.getRotationMatrix().getThetaUVector()[2] );
541  vpTranslationVector t = M.getTranslationVector();
542 
543  res << t[0], t[1], t[2], dThetaZ;
544  return res;
545 }
546 
547 #else
548 
549 #endif
ros::Publisher
image_encodings.h
epsilon
double epsilon
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ros.h
nodelet::Nodelet::onInit
virtual void onInit()=0
class_list_macros.h
A
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
ROS_ERROR
#define ROS_ERROR(...)
ros::NodeHandle::hasParam
bool hasParam(const std::string &key) const
ROS_WARN
#define ROS_WARN(...)
imageCallback
void imageCallback(const sensor_msgs::ImageConstPtr &msg)
image_transport.h
NODELET_INFO
#define NODELET_INFO(...)
nodelet::Nodelet
nodelet.h
cv_bridge.h
sensor_msgs::image_encodings::BGR8
const std::string BGR8
cv_bridge::toCvShare
CvImageConstPtr toCvShare(const sensor_msgs::Image &source, const boost::shared_ptr< void const > &tracked_object, const std::string &encoding=std::string())
ros::NodeHandle
ros::Subscriber


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