tutorial-ros-pioneer-visual-servo.cpp
Go to the documentation of this file.
1 
21 #include <iostream>
22 
23 #include <visp/vpCameraParameters.h>
24 #include <visp/vpDisplayX.h>
25 #include <visp/vpDot2.h>
26 #include <visp/vpFeatureBuilder.h>
27 #include <visp/vpFeatureDepth.h>
28 #include <visp/vpFeaturePoint.h>
29 #include <visp/vpHomogeneousMatrix.h>
30 #include <visp/vpImage.h>
31 #include <visp/vpImageConvert.h>
32 #include <visp/vpServo.h>
33 #include <visp/vpVelocityTwistMatrix.h>
34 
35 #include <visp_ros/vpROSGrabber.h>
37 
38 #if defined( VISP_HAVE_DC1394_2 ) && defined( VISP_HAVE_X11 )
39 #define TEST_COULD_BE_ACHIEVED
40 #endif
41 
42 #ifdef TEST_COULD_BE_ACHIEVED
43 int
44 main( int argc, char **argv )
45 {
46  try
47  {
48  vpImage< unsigned char > I; // Create a gray level image container
49  double depth = 1.;
50  double lambda = 0.6;
51  double coef = 1. / 6.77; // Scale parameter used to estimate the depth Z of the blob from its surface
52 
53  vpROSRobotPioneer robot;
54  robot.setCmdVelTopic( "/RosAria/cmd_vel" );
55  robot.init();
56 
57  // Wait 3 sec to be sure that the low level Aria thread used to control
58  // the robot is started. Without this delay we experienced a delay (arround 2.2 sec)
59  // between the velocity send to the robot and the velocity that is really applied
60  // to the wheels.
61  vpTime::sleepMs( 3000 );
62 
63  std::cout << "Robot connected" << std::endl;
64 
65  // Camera parameters. In this experiment we don't need a precise calibration of the camera
66  vpCameraParameters cam;
67 
68  // Create a grabber based on libdc1394-2.x third party lib (for firewire cameras under Linux)
69  vpROSGrabber g;
70  g.setCameraInfoTopic( "/camera/camera_info" );
71  g.setImageTopic( "/camera/image_raw" );
72  g.setRectify( true );
73 
74  // Get camera parameters from /camera/camera_info topic
75  if ( g.getCameraInfo( cam ) == false )
76  cam.initPersProjWithoutDistortion( 600, 600, I.getWidth() / 2, I.getHeight() / 2 );
77 
78  g.acquire( I );
79 
80  // Create an image viewer
81  vpDisplayX d( I, 10, 10, "Current frame" );
82  vpDisplay::display( I );
83  vpDisplay::flush( I );
84 
85  // Create a blob tracker
86  vpDot2 dot;
87  dot.setGraphics( true );
88  dot.setComputeMoments( true );
89  dot.setEllipsoidShapePrecision( 0. ); // to track a blob without any constraint on the shape
90  dot.setGrayLevelPrecision( 0.9 ); // to set the blob gray level bounds for binarisation
91  dot.setEllipsoidBadPointsPercentage( 0.5 ); // to be accept 50% of bad inner and outside points with bad gray level
92  dot.initTracking( I );
93  vpDisplay::flush( I );
94 
95  vpServo task;
96  task.setServo( vpServo::EYEINHAND_L_cVe_eJe );
97  task.setInteractionMatrixType( vpServo::DESIRED, vpServo::PSEUDO_INVERSE );
98  task.setLambda( lambda );
99  vpVelocityTwistMatrix cVe;
100  cVe = robot.get_cVe();
101  task.set_cVe( cVe );
102 
103  std::cout << "cVe: \n" << cVe << std::endl;
104 
105  vpMatrix eJe;
106  robot.get_eJe( eJe );
107  task.set_eJe( eJe );
108  std::cout << "eJe: \n" << eJe << std::endl;
109 
110  // Current and desired visual feature associated to the x coordinate of the point
111  vpFeaturePoint s_x, s_xd;
112 
113  // Create the current x visual feature
114  vpFeatureBuilder::create( s_x, cam, dot );
115 
116  // Create the desired x* visual feature
117  s_xd.buildFrom( 0, 0, depth );
118 
119  // Add the feature
120  task.addFeature( s_x, s_xd );
121 
122  // Create the current log(Z/Z*) visual feature
123  vpFeatureDepth s_Z, s_Zd;
124  // Surface of the blob estimated from the image moment m00 and converted in meters
125  double surface = 1. / sqrt( dot.m00 / ( cam.get_px() * cam.get_py() ) );
126  double Z, Zd;
127  // Initial depth of the blob in from of the camera
128  Z = coef * surface;
129  // Desired depth Z* of the blob. This depth is learned and equal to the initial depth
130  Zd = Z;
131 
132  std::cout << "Z " << Z << std::endl;
133  s_Z.buildFrom( s_x.get_x(), s_x.get_y(), Z, 0 ); // log(Z/Z*) = 0 that's why the last parameter is 0
134  s_Zd.buildFrom( s_x.get_x(), s_x.get_y(), Zd, 0 ); // log(Z/Z*) = 0 that's why the last parameter is 0
135 
136  // Add the feature
137  task.addFeature( s_Z, s_Zd );
138 
139  vpColVector v; // vz, wx
140 
141  while ( 1 )
142  {
143  // Acquire a new image
144  g.acquire( I );
145 
146  // Set the image as background of the viewer
147  vpDisplay::display( I );
148 
149  // Does the blob tracking
150  dot.track( I );
151  // Update the current x feature
152  vpFeatureBuilder::create( s_x, cam, dot );
153 
154  // Update log(Z/Z*) feature. Since the depth Z change, we need to update the intection matrix
155  surface = 1. / sqrt( dot.m00 / ( cam.get_px() * cam.get_py() ) );
156  Z = coef * surface;
157  s_Z.buildFrom( s_x.get_x(), s_x.get_y(), Z, log( Z / Zd ) );
158 
159  robot.get_cVe( cVe );
160  task.set_cVe( cVe );
161 
162  robot.get_eJe( eJe );
163  task.set_eJe( eJe );
164 
165  // Compute the control law. Velocities are computed in the mobile robot reference frame
166  v = task.computeControlLaw();
167 
168  std::cout << "Send velocity to the pionner: " << v[0] << " m/s " << vpMath::deg( v[1] ) << " deg/s" << std::endl;
169 
170  // Send the velocity to the robot
171  robot.setVelocity( vpRobot::REFERENCE_FRAME, v );
172 
173  // Draw a vertical line which corresponds to the desired x coordinate of the dot cog
174  vpDisplay::displayLine( I, 0, 320, 479, 320, vpColor::red );
175  vpDisplay::flush( I );
176 
177  // A click in the viewer to exit
178  if ( vpDisplay::getClick( I, false ) )
179  break;
180  }
181 
182  std::cout << "Ending robot thread..." << std::endl;
183 
184  // Kill the servo task
185  task.print();
186  task.kill();
187  }
188  catch ( vpException e )
189  {
190  std::cout << "Catch an exception: " << e << std::endl;
191  return 1;
192  }
193 }
194 #else
195 int
196 main()
197 {
198  std::cout << "You don't have the right 3rd party libraries to run this example..." << std::endl;
199 }
200 #endif
main
int main(int argc, char **argv)
Definition: tutorial-ros-pioneer-visual-servo.cpp:44
vpROSRobotPioneer.h
vpROSGrabber::getCameraInfo
bool getCameraInfo(vpCameraParameters &cam)
Definition: vpROSGrabber.cpp:649
vpROSGrabber
Class for cameras video capture for ROS cameras.
Definition: vpROSGrabber.h:104
vpROSRobotPioneer::init
void init()
basic initialization
Definition: vpROSRobotPioneer.cpp:65
dot
TFSIMD_FORCE_INLINE tfScalar dot(const Quaternion &q1, const Quaternion &q2)
d
d
vpROSGrabber::setImageTopic
void setImageTopic(const std::string &topic_name)
Definition: vpROSGrabber.cpp:592
vpROSRobotPioneer
Interface for Pioneer mobile robots based on ROS.
Definition: vpROSRobotPioneer.h:64
vpROSGrabber::setCameraInfoTopic
void setCameraInfoTopic(const std::string &topic_name)
Definition: vpROSGrabber.cpp:579
vpROSRobot::setCmdVelTopic
void setCmdVelTopic(std::string topic_name)
Definition: vpROSRobot.cpp:305
vpROSGrabber::acquire
void acquire(vpImage< unsigned char > &I)
Definition: vpROSGrabber.cpp:412
vpROSRobotPioneer::get_eJe
void get_eJe(vpMatrix &eJe)
Definition: vpROSRobotPioneer.h:84
vpROSGrabber::setRectify
void setRectify(bool rectify)
Definition: vpROSGrabber.cpp:517
vpROSGrabber.h
class for Camera video capture for ROS middleware.
vpROSRobotPioneer::setVelocity
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel)
Definition: vpROSRobotPioneer.cpp:96


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