Visual Servoing Platform  version 3.6.1 under development (2024-05-09)
servoAfma6AprilTagIBVS.cpp
1 /****************************************************************************
2  *
3  * ViSP, open source Visual Servoing Platform software.
4  * Copyright (C) 2005 - 2023 by Inria. All rights reserved.
5  *
6  * This software is free software; you can redistribute it and/or modify
7  * it under the terms of the GNU General Public License as published by
8  * the Free Software Foundation; either version 2 of the License, or
9  * (at your option) any later version.
10  * See the file LICENSE.txt at the root directory of this source
11  * distribution for additional information about the GNU GPL.
12  *
13  * For using ViSP with software that can not be combined with the GNU
14  * GPL, please contact Inria about acquiring a ViSP Professional
15  * Edition License.
16  *
17  * See https://visp.inria.fr for more information.
18  *
19  * This software was developed at:
20  * Inria Rennes - Bretagne Atlantique
21  * Campus Universitaire de Beaulieu
22  * 35042 Rennes Cedex
23  * France
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  * tests the control law
33  * eye-in-hand control
34  * velocity computed in the camera frame
35  *
36 *****************************************************************************/
54 #include <iostream>
55 
56 #include <visp3/core/vpCameraParameters.h>
57 #include <visp3/detection/vpDetectorAprilTag.h>
58 #include <visp3/gui/vpDisplayGDI.h>
59 #include <visp3/gui/vpDisplayX.h>
60 #include <visp3/gui/vpPlot.h>
61 #include <visp3/io/vpImageIo.h>
62 #include <visp3/robot/vpRobotAfma6.h>
63 #include <visp3/sensor/vpRealSense2.h>
64 #include <visp3/visual_features/vpFeatureBuilder.h>
65 #include <visp3/visual_features/vpFeaturePoint.h>
66 #include <visp3/vs/vpServo.h>
67 #include <visp3/vs/vpServoDisplay.h>
68 
69 #if defined(VISP_HAVE_REALSENSE2) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && defined(VISP_HAVE_AFMA6)
70 
71 void display_point_trajectory(const vpImage<unsigned char> &I, const std::vector<vpImagePoint> &vip,
72  std::vector<vpImagePoint> *traj_vip)
73 {
74  for (size_t i = 0; i < vip.size(); i++) {
75  if (traj_vip[i].size()) {
76  // Add the point only if distance with the previous > 1 pixel
77  if (vpImagePoint::distance(vip[i], traj_vip[i].back()) > 1.) {
78  traj_vip[i].push_back(vip[i]);
79  }
80  }
81  else {
82  traj_vip[i].push_back(vip[i]);
83  }
84  }
85  for (size_t i = 0; i < vip.size(); i++) {
86  for (size_t j = 1; j < traj_vip[i].size(); j++) {
87  vpDisplay::displayLine(I, traj_vip[i][j - 1], traj_vip[i][j], vpColor::green, 2);
88  }
89  }
90 }
91 
92 int main(int argc, char **argv)
93 {
94  double opt_tagSize = 0.120;
95  bool display_tag = true;
96  int opt_quad_decimate = 2;
97  bool opt_verbose = false;
98  bool opt_plot = false;
99  bool opt_adaptive_gain = false;
100  bool opt_task_sequencing = false;
101  double convergence_threshold = 0.00005;
102 
103  for (int i = 1; i < argc; i++) {
104  if (std::string(argv[i]) == "--tag_size" && i + 1 < argc) {
105  opt_tagSize = std::stod(argv[i + 1]);
106  }
107  else if (std::string(argv[i]) == "--verbose") {
108  opt_verbose = true;
109  }
110  else if (std::string(argv[i]) == "--plot") {
111  opt_plot = true;
112  }
113  else if (std::string(argv[i]) == "--adaptive_gain") {
114  opt_adaptive_gain = true;
115  }
116  else if (std::string(argv[i]) == "--task_sequencing") {
117  opt_task_sequencing = true;
118  }
119  else if (std::string(argv[i]) == "--quad_decimate" && i + 1 < argc) {
120  opt_quad_decimate = std::stoi(argv[i + 1]);
121  }
122  else if (std::string(argv[i]) == "--no-convergence-threshold") {
123  convergence_threshold = 0.;
124  }
125  else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") {
126  std::cout
127  << argv[0] << " --tag_size <marker size in meter; default " << opt_tagSize << ">] "
128  << "[--quad_decimate <decimation; default " << opt_quad_decimate
129  << ">] [--adaptive_gain] [--plot] [--task_sequencing] [--no-convergence-threshold] [--verbose] [--help] [-h]"
130  << "\n";
131  return EXIT_SUCCESS;
132  }
133  }
134 
135  vpRobotAfma6 robot;
136 
137  try {
138  std::cout << "WARNING: This example will move the robot! "
139  << "Please make sure to have the user stop button at hand!" << std::endl
140  << "Press Enter to continue..." << std::endl;
141  std::cin.ignore();
142 
143  /*
144  * Move to a safe position
145  */
146  vpColVector q(6, 0);
147  q[0] = 0.;
148  q[1] = 0.;
149  q[2] = 0.;
150  q[3] = vpMath::rad(0.);
151  q[4] = vpMath::rad(0.);
152  q[5] = vpMath::rad(0.);
153 
154  std::cout << "Move to joint position: " << q.t() << std::endl;
156  robot.setPosition(vpRobot::JOINT_STATE, q);
157 
158  vpRealSense2 rs;
159  rs2::config config;
160  unsigned int width = 640, height = 480;
161  config.enable_stream(RS2_STREAM_COLOR, 640, 480, RS2_FORMAT_RGBA8, 30);
162  config.enable_stream(RS2_STREAM_DEPTH, 640, 480, RS2_FORMAT_Z16, 30);
163  config.enable_stream(RS2_STREAM_INFRARED, 640, 480, RS2_FORMAT_Y8, 30);
164  rs.open(config);
165 
166  // Get camera intrinsics
167  vpCameraParameters cam =
169  std::cout << "cam:\n" << cam << "\n";
170 
171  vpImage<unsigned char> I(height, width);
172 
173 #if defined(VISP_HAVE_X11)
174  vpDisplayX dc(I, 10, 10, "Color image");
175 #elif defined(VISP_HAVE_GDI)
176  vpDisplayGDI dc(I, 10, 10, "Color image");
177 #endif
178 
181  // vpDetectorAprilTag::vpPoseEstimationMethod poseEstimationMethod = vpDetectorAprilTag::BEST_RESIDUAL_VIRTUAL_VS;
182  vpDetectorAprilTag detector(tagFamily);
183  detector.setAprilTagPoseEstimationMethod(poseEstimationMethod);
184  detector.setDisplayTag(display_tag);
185  detector.setAprilTagQuadDecimate(opt_quad_decimate);
186 
187  // Servo
188  vpHomogeneousMatrix cdMc, cMo, oMo;
189 
190  // Desired pose used to compute the desired features
191  vpHomogeneousMatrix cdMo(vpTranslationVector(0, 0, opt_tagSize * 3), // 3 times tag with along camera z axis
192  vpRotationMatrix({ 1, 0, 0, 0, -1, 0, 0, 0, -1 }));
193 
194  // Create visual features
195  std::vector<vpFeaturePoint> p(4), pd(4); // We use 4 points
196 
197  // Define 4 3D points corresponding to the CAD model of the Apriltag
198  std::vector<vpPoint> point(4);
199  point[0].setWorldCoordinates(-opt_tagSize / 2., -opt_tagSize / 2., 0);
200  point[1].setWorldCoordinates(opt_tagSize / 2., -opt_tagSize / 2., 0);
201  point[2].setWorldCoordinates(opt_tagSize / 2., opt_tagSize / 2., 0);
202  point[3].setWorldCoordinates(-opt_tagSize / 2., opt_tagSize / 2., 0);
203 
204  vpServo task;
205  // Add the 4 visual feature points
206  for (size_t i = 0; i < p.size(); i++) {
207  task.addFeature(p[i], pd[i]);
208  }
211 
212  if (opt_adaptive_gain) {
213  vpAdaptiveGain lambda(1.5, 0.4, 30); // lambda(0)=4, lambda(oo)=0.4 and lambda'(0)=30
214  task.setLambda(lambda);
215  }
216  else {
217  task.setLambda(0.5);
218  }
219 
220  vpPlot *plotter = nullptr;
221  int iter_plot = 0;
222 
223  if (opt_plot) {
224  plotter = new vpPlot(2, static_cast<int>(250 * 2), 500, static_cast<int>(I.getWidth()) + 80, 10,
225  "Real time curves plotter");
226  plotter->setTitle(0, "Visual features error");
227  plotter->setTitle(1, "Camera velocities");
228  plotter->initGraph(0, 8);
229  plotter->initGraph(1, 6);
230  plotter->setLegend(0, 0, "error_feat_p1_x");
231  plotter->setLegend(0, 1, "error_feat_p1_y");
232  plotter->setLegend(0, 2, "error_feat_p2_x");
233  plotter->setLegend(0, 3, "error_feat_p2_y");
234  plotter->setLegend(0, 4, "error_feat_p3_x");
235  plotter->setLegend(0, 5, "error_feat_p3_y");
236  plotter->setLegend(0, 6, "error_feat_p4_x");
237  plotter->setLegend(0, 7, "error_feat_p4_y");
238  plotter->setLegend(1, 0, "vc_x");
239  plotter->setLegend(1, 1, "vc_y");
240  plotter->setLegend(1, 2, "vc_z");
241  plotter->setLegend(1, 3, "wc_x");
242  plotter->setLegend(1, 4, "wc_y");
243  plotter->setLegend(1, 5, "wc_z");
244  }
245 
246  bool final_quit = false;
247  bool has_converged = false;
248  bool send_velocities = false;
249  bool servo_started = false;
250  std::vector<vpImagePoint> *traj_corners = nullptr; // To memorize point trajectory
251 
252  static double t_init_servo = vpTime::measureTimeMs();
253 
255 
256  while (!has_converged && !final_quit) {
257  double t_start = vpTime::measureTimeMs();
258 
259  rs.acquire(I);
260 
262 
263  std::vector<vpHomogeneousMatrix> cMo_vec;
264  detector.detect(I, opt_tagSize, cam, cMo_vec);
265 
266  {
267  std::stringstream ss;
268  ss << "Left click to " << (send_velocities ? "stop the robot" : "servo the robot") << ", right click to quit.";
269  vpDisplay::displayText(I, 20, 20, ss.str(), vpColor::red);
270  }
271 
272  vpColVector v_c(6);
273 
274  // Only one tag is detected
275  if (cMo_vec.size() == 1) {
276  cMo = cMo_vec[0];
277 
278  static bool first_time = true;
279  if (first_time) {
280  // Introduce security wrt tag positioning in order to avoid PI rotation
281  std::vector<vpHomogeneousMatrix> v_oMo(2), v_cdMc(2);
282  v_oMo[1].buildFrom(0, 0, 0, 0, 0, M_PI);
283  for (size_t i = 0; i < 2; i++) {
284  v_cdMc[i] = cdMo * v_oMo[i] * cMo.inverse();
285  }
286  if (std::fabs(v_cdMc[0].getThetaUVector().getTheta()) < std::fabs(v_cdMc[1].getThetaUVector().getTheta())) {
287  oMo = v_oMo[0];
288  }
289  else {
290  std::cout << "Desired frame modified to avoid PI rotation of the camera" << std::endl;
291  oMo = v_oMo[1]; // Introduce PI rotation
292  }
293 
294  // Compute the desired position of the features from the desired pose
295  for (size_t i = 0; i < point.size(); i++) {
296  vpColVector cP, p_;
297  point[i].changeFrame(cdMo * oMo, cP);
298  point[i].projection(cP, p_);
299 
300  pd[i].set_x(p_[0]);
301  pd[i].set_y(p_[1]);
302  pd[i].set_Z(cP[2]);
303  }
304  }
305 
306  // Get tag corners
307  std::vector<vpImagePoint> corners = detector.getPolygon(0);
308 
309  // Update visual features
310  for (size_t i = 0; i < corners.size(); i++) {
311  // Update the point feature from the tag corners location
312  vpFeatureBuilder::create(p[i], cam, corners[i]);
313  // Set the feature Z coordinate from the pose
314  vpColVector cP;
315  point[i].changeFrame(cMo, cP);
316 
317  p[i].set_Z(cP[2]);
318  }
319 
320  if (opt_task_sequencing) {
321  if (!servo_started) {
322  if (send_velocities) {
323  servo_started = true;
324  }
325  t_init_servo = vpTime::measureTimeMs();
326  }
327  v_c = task.computeControlLaw((vpTime::measureTimeMs() - t_init_servo) / 1000.);
328  }
329  else {
330  v_c = task.computeControlLaw();
331  }
332 
333  // Display the current and desired feature points in the image display
334  vpServoDisplay::display(task, cam, I);
335  for (size_t i = 0; i < corners.size(); i++) {
336  std::stringstream ss;
337  ss << i;
338  // Display current point indexes
339  vpDisplay::displayText(I, corners[i] + vpImagePoint(15, 15), ss.str(), vpColor::red);
340  // Display desired point indexes
341  vpImagePoint ip;
342  vpMeterPixelConversion::convertPoint(cam, pd[i].get_x(), pd[i].get_y(), ip);
343  vpDisplay::displayText(I, ip + vpImagePoint(15, 15), ss.str(), vpColor::red);
344  }
345  if (first_time) {
346  traj_corners = new std::vector<vpImagePoint>[corners.size()];
347  }
348  // Display the trajectory of the points used as features
349  display_point_trajectory(I, corners, traj_corners);
350 
351  if (opt_plot) {
352  plotter->plot(0, iter_plot, task.getError());
353  plotter->plot(1, iter_plot, v_c);
354  iter_plot++;
355  }
356 
357  if (opt_verbose) {
358  std::cout << "v_c: " << v_c.t() << std::endl;
359  }
360 
361  double error = task.getError().sumSquare();
362  std::stringstream ss;
363  ss << "error: " << error;
364  vpDisplay::displayText(I, 20, static_cast<int>(I.getWidth()) - 150, ss.str(), vpColor::red);
365 
366  if (opt_verbose)
367  std::cout << "error: " << error << std::endl;
368 
369  if (error < convergence_threshold) {
370  has_converged = true;
371  std::cout << "Servo task has converged"
372  << "\n";
373  vpDisplay::displayText(I, 100, 20, "Servo task has converged", vpColor::red);
374  }
375  if (first_time) {
376  first_time = false;
377  }
378  } // end if (cMo_vec.size() == 1)
379  else {
380  v_c = 0;
381  }
382 
383  if (!send_velocities) {
384  v_c = 0;
385  }
386 
387  // Send to the robot
389 
390  {
391  std::stringstream ss;
392  ss << "Loop time: " << vpTime::measureTimeMs() - t_start << " ms";
393  vpDisplay::displayText(I, 40, 20, ss.str(), vpColor::red);
394  }
395  vpDisplay::flush(I);
396 
398  if (vpDisplay::getClick(I, button, false)) {
399  switch (button) {
401  send_velocities = !send_velocities;
402  break;
403 
405  final_quit = true;
406  v_c = 0;
407  break;
408 
409  default:
410  break;
411  }
412  }
413  }
414  std::cout << "Stop the robot " << std::endl;
416 
417  if (opt_plot && plotter != nullptr) {
418  delete plotter;
419  plotter = nullptr;
420  }
421 
422  if (!final_quit) {
423  while (!final_quit) {
424  rs.acquire(I);
426 
427  vpDisplay::displayText(I, 20, 20, "Click to quit the program.", vpColor::red);
428  vpDisplay::displayText(I, 40, 20, "Visual servo converged.", vpColor::red);
429 
430  if (vpDisplay::getClick(I, false)) {
431  final_quit = true;
432  }
433 
434  vpDisplay::flush(I);
435  }
436  }
437  if (traj_corners) {
438  delete[] traj_corners;
439  }
440  }
441  catch (const vpException &e) {
442  std::cout << "ViSP exception: " << e.what() << std::endl;
443  std::cout << "Stop the robot " << std::endl;
445  return EXIT_FAILURE;
446  }
447  catch (const std::exception &e) {
448  std::cout << "ur_rtde exception: " << e.what() << std::endl;
449  return EXIT_FAILURE;
450  }
451 
452  return EXIT_SUCCESS;
453 }
454 #else
455 int main()
456 {
457 #if !defined(VISP_HAVE_REALSENSE2)
458  std::cout << "Install librealsense-2.x" << std::endl;
459 #endif
460 #if !defined(VISP_HAVE_AFMA6)
461  std::cout << "ViSP is not build with Afma6 robot support..." << std::endl;
462 #endif
463  return EXIT_SUCCESS;
464 }
465 #endif
Adaptive gain computation.
Generic class defining intrinsic camera parameters.
@ perspectiveProjWithDistortion
Perspective projection with distortion model.
Implementation of column vector and the associated operations.
Definition: vpColVector.h:163
double sumSquare() const
static const vpColor red
Definition: vpColor.h:211
static const vpColor green
Definition: vpColor.h:214
@ TAG_36h11
AprilTag 36h11 pattern (recommended)
Display for windows using GDI (available on any windows 32 platform).
Definition: vpDisplayGDI.h:128
Use the X11 console to display images on unix-like OS. Thus to enable this class X11 should be instal...
Definition: vpDisplayX.h:128
static bool getClick(const vpImage< unsigned char > &I, bool blocking=true)
static void display(const vpImage< unsigned char > &I)
static void displayLine(const vpImage< unsigned char > &I, const vpImagePoint &ip1, const vpImagePoint &ip2, const vpColor &color, unsigned int thickness=1, bool segment=true)
static void flush(const vpImage< unsigned char > &I)
static void displayText(const vpImage< unsigned char > &I, const vpImagePoint &ip, const std::string &s, const vpColor &color)
error that can be emitted by ViSP classes.
Definition: vpException.h:59
const char * what() const
Definition: vpException.cpp:70
static void create(vpFeaturePoint &s, const vpCameraParameters &cam, const vpDot &d)
Implementation of an homogeneous matrix and operations on such kind of matrices.
vpHomogeneousMatrix inverse() const
Class that defines a 2D point in an image. This class is useful for image processing and stores only ...
Definition: vpImagePoint.h:82
static double distance(const vpImagePoint &iP1, const vpImagePoint &iP2)
unsigned int getWidth() const
Definition: vpImage.h:245
static double rad(double deg)
Definition: vpMath.h:127
static void convertPoint(const vpCameraParameters &cam, const double &x, const double &y, double &u, double &v)
This class enables real time drawing of 2D or 3D graphics. An instance of the class open a window whi...
Definition: vpPlot.h:109
void initGraph(unsigned int graphNum, unsigned int curveNbr)
Definition: vpPlot.cpp:202
void setLegend(unsigned int graphNum, unsigned int curveNum, const std::string &legend)
Definition: vpPlot.cpp:545
void plot(unsigned int graphNum, unsigned int curveNum, double x, double y)
Definition: vpPlot.cpp:269
void setTitle(unsigned int graphNum, const std::string &title)
Definition: vpPlot.cpp:503
vpCameraParameters getCameraParameters(const rs2_stream &stream, vpCameraParameters::vpCameraParametersProjType type=vpCameraParameters::perspectiveProjWithDistortion, int index=-1) const
void acquire(vpImage< unsigned char > &grey, double *ts=nullptr)
bool open(const rs2::config &cfg=rs2::config())
Control of Irisa's gantry robot named Afma6.
Definition: vpRobotAfma6.h:209
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel) vp_override
@ JOINT_STATE
Definition: vpRobot.h:80
@ CAMERA_FRAME
Definition: vpRobot.h:82
@ STATE_POSITION_CONTROL
Initialize the position controller.
Definition: vpRobot.h:66
@ STATE_VELOCITY_CONTROL
Initialize the velocity controller.
Definition: vpRobot.h:65
@ STATE_STOP
Stops robot motion especially in velocity and acceleration control.
Definition: vpRobot.h:64
virtual vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
Definition: vpRobot.cpp:198
Implementation of a rotation matrix and operations on such kind of matrices.
static void display(const vpServo &s, const vpCameraParameters &cam, const vpImage< unsigned char > &I, vpColor currentColor=vpColor::green, vpColor desiredColor=vpColor::red, unsigned int thickness=1)
void setInteractionMatrixType(const vpServoIteractionMatrixType &interactionMatrixType, const vpServoInversionType &interactionMatrixInversion=PSEUDO_INVERSE)
Definition: vpServo.cpp:378
@ EYEINHAND_CAMERA
Definition: vpServo.h:155
void addFeature(vpBasicFeature &s_cur, vpBasicFeature &s_star, unsigned int select=vpBasicFeature::FEATURE_ALL)
Definition: vpServo.cpp:329
void setLambda(double c)
Definition: vpServo.h:976
void setServo(const vpServoType &servo_type)
Definition: vpServo.cpp:132
vpColVector getError() const
Definition: vpServo.h:504
vpColVector computeControlLaw()
Definition: vpServo.cpp:703
@ CURRENT
Definition: vpServo.h:196
Class that consider the case of a translation vector.
VISP_EXPORT double measureTimeMs()