Visual Servoing Platform  version 3.6.1 under development (2024-05-09)
servoAfma6AprilTagPBVS.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  * Data acquisition with RealSense RGB-D sensor and Franka robot.
33  *
34 *****************************************************************************/
35 
51 #include <iostream>
52 
53 #include <visp3/core/vpCameraParameters.h>
54 #include <visp3/detection/vpDetectorAprilTag.h>
55 #include <visp3/gui/vpDisplayGDI.h>
56 #include <visp3/gui/vpDisplayX.h>
57 #include <visp3/gui/vpPlot.h>
58 #include <visp3/io/vpImageIo.h>
59 #include <visp3/robot/vpRobotAfma6.h>
60 #include <visp3/sensor/vpRealSense2.h>
61 #include <visp3/visual_features/vpFeatureThetaU.h>
62 #include <visp3/visual_features/vpFeatureTranslation.h>
63 #include <visp3/vs/vpServo.h>
64 #include <visp3/vs/vpServoDisplay.h>
65 
66 #if defined(VISP_HAVE_REALSENSE2) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && defined(VISP_HAVE_AFMA6)
67 
68 void display_point_trajectory(const vpImage<unsigned char> &I, const std::vector<vpImagePoint> &vip,
69  std::vector<vpImagePoint> *traj_vip)
70 {
71  for (size_t i = 0; i < vip.size(); i++) {
72  if (traj_vip[i].size()) {
73  // Add the point only if distance with the previous > 1 pixel
74  if (vpImagePoint::distance(vip[i], traj_vip[i].back()) > 1.) {
75  traj_vip[i].push_back(vip[i]);
76  }
77  }
78  else {
79  traj_vip[i].push_back(vip[i]);
80  }
81  }
82  for (size_t i = 0; i < vip.size(); i++) {
83  for (size_t j = 1; j < traj_vip[i].size(); j++) {
84  vpDisplay::displayLine(I, traj_vip[i][j - 1], traj_vip[i][j], vpColor::green, 2);
85  }
86  }
87 }
88 
89 int main(int argc, char **argv)
90 {
91  double opt_tagSize = 0.120;
92  bool display_tag = true;
93  int opt_quad_decimate = 2;
94  bool opt_verbose = false;
95  bool opt_plot = false;
96  bool opt_adaptive_gain = false;
97  bool opt_task_sequencing = false;
98  double convergence_threshold_t = 0.0005; // Value in [m]
99  double convergence_threshold_tu = 0.5; // Value in [deg]
100 
101  for (int i = 1; i < argc; i++) {
102  if (std::string(argv[i]) == "--tag_size" && i + 1 < argc) {
103  opt_tagSize = std::stod(argv[i + 1]);
104  }
105  else if (std::string(argv[i]) == "--verbose") {
106  opt_verbose = true;
107  }
108  else if (std::string(argv[i]) == "--plot") {
109  opt_plot = true;
110  }
111  else if (std::string(argv[i]) == "--adaptive_gain") {
112  opt_adaptive_gain = true;
113  }
114  else if (std::string(argv[i]) == "--task_sequencing") {
115  opt_task_sequencing = true;
116  }
117  else if (std::string(argv[i]) == "--quad_decimate" && i + 1 < argc) {
118  opt_quad_decimate = std::stoi(argv[i + 1]);
119  }
120  else if (std::string(argv[i]) == "--no-convergence-threshold") {
121  convergence_threshold_t = 0.;
122  convergence_threshold_tu = 0.;
123  }
124  else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") {
125  std::cout
126  << argv[0] << " [--tag_size <marker size in meter; default " << opt_tagSize << ">] "
127  << "[--quad_decimate <decimation; default " << opt_quad_decimate
128  << ">] [--adaptive_gain] [--plot] [--task_sequencing] [--no-convergence-threshold] [--verbose] [--help] [-h]"
129  << "\n";
130  return EXIT_SUCCESS;
131  }
132  }
133 
134  vpRobotAfma6 robot;
135 
136  try {
137  std::cout << "WARNING: This example will move the robot! "
138  << "Please make sure to have the user stop button at hand!" << std::endl
139  << "Press Enter to continue..." << std::endl;
140  std::cin.ignore();
141 
142  /*
143  * Move to a safe position
144  */
145  vpColVector q(6, 0);
146  q[0] = 0.;
147  q[1] = 0.;
148  q[2] = 0.;
149  q[3] = vpMath::rad(0.);
150  q[4] = vpMath::rad(0.);
151  q[5] = vpMath::rad(0.);
152  std::cout << "Move to joint position: " << q.t() << std::endl;
154  robot.setPosition(vpRobot::JOINT_STATE, q);
155 
156  vpRealSense2 rs;
157  rs2::config config;
158  unsigned int width = 640, height = 480;
159  config.enable_stream(RS2_STREAM_COLOR, 640, 480, RS2_FORMAT_RGBA8, 30);
160  config.enable_stream(RS2_STREAM_DEPTH, 640, 480, RS2_FORMAT_Z16, 30);
161  config.enable_stream(RS2_STREAM_INFRARED, 640, 480, RS2_FORMAT_Y8, 30);
162  rs.open(config);
163 
164  // Get camera intrinsics
165  vpCameraParameters cam =
167  std::cout << "cam:\n" << cam << "\n";
168 
169  vpImage<unsigned char> I(height, width);
170 
171 #if defined(VISP_HAVE_X11)
172  vpDisplayX dc(I, 10, 10, "Color image");
173 #elif defined(VISP_HAVE_GDI)
174  vpDisplayGDI dc(I, 10, 10, "Color image");
175 #endif
176 
179  // vpDetectorAprilTag::vpPoseEstimationMethod poseEstimationMethod = vpDetectorAprilTag::BEST_RESIDUAL_VIRTUAL_VS;
180  vpDetectorAprilTag detector(tagFamily);
181  detector.setAprilTagPoseEstimationMethod(poseEstimationMethod);
182  detector.setDisplayTag(display_tag);
183  detector.setAprilTagQuadDecimate(opt_quad_decimate);
184 
185  // Servo
186  vpHomogeneousMatrix cdMc, cMo, oMo;
187 
188  // Desired pose to reach
189  vpHomogeneousMatrix cdMo(vpTranslationVector(0, 0, opt_tagSize * 3), // 3 times tag with along camera z axis
190  vpRotationMatrix({ 1, 0, 0, 0, -1, 0, 0, 0, -1 }));
191 
192  cdMc = cdMo * cMo.inverse();
195  t.buildFrom(cdMc);
196  tu.buildFrom(cdMc);
197 
200 
201  vpServo task;
202  task.addFeature(t, td);
203  task.addFeature(tu, tud);
206 
207  if (opt_adaptive_gain) {
208  vpAdaptiveGain lambda(1.5, 0.4, 30); // lambda(0)=4, lambda(oo)=0.4 and lambda'(0)=30
209  task.setLambda(lambda);
210  }
211  else {
212  task.setLambda(0.5);
213  }
214 
215  vpPlot *plotter = nullptr;
216  int iter_plot = 0;
217 
218  if (opt_plot) {
219  plotter = new vpPlot(2, static_cast<int>(250 * 2), 500, static_cast<int>(I.getWidth()) + 80, 10,
220  "Real time curves plotter");
221  plotter->setTitle(0, "Visual features error");
222  plotter->setTitle(1, "Camera velocities");
223  plotter->initGraph(0, 6);
224  plotter->initGraph(1, 6);
225  plotter->setLegend(0, 0, "error_feat_tx");
226  plotter->setLegend(0, 1, "error_feat_ty");
227  plotter->setLegend(0, 2, "error_feat_tz");
228  plotter->setLegend(0, 3, "error_feat_theta_ux");
229  plotter->setLegend(0, 4, "error_feat_theta_uy");
230  plotter->setLegend(0, 5, "error_feat_theta_uz");
231  plotter->setLegend(1, 0, "vc_x");
232  plotter->setLegend(1, 1, "vc_y");
233  plotter->setLegend(1, 2, "vc_z");
234  plotter->setLegend(1, 3, "wc_x");
235  plotter->setLegend(1, 4, "wc_y");
236  plotter->setLegend(1, 5, "wc_z");
237  }
238 
239  bool final_quit = false;
240  bool has_converged = false;
241  bool send_velocities = false;
242  bool servo_started = false;
243  std::vector<vpImagePoint> *traj_vip = nullptr; // To memorize point trajectory
244 
245  static double t_init_servo = vpTime::measureTimeMs();
246 
248 
249  while (!has_converged && !final_quit) {
250  double t_start = vpTime::measureTimeMs();
251 
252  rs.acquire(I);
253 
255 
256  std::vector<vpHomogeneousMatrix> cMo_vec;
257  detector.detect(I, opt_tagSize, cam, cMo_vec);
258 
259  std::stringstream ss;
260  ss << "Left click to " << (send_velocities ? "stop the robot" : "servo the robot") << ", right click to quit.";
261  vpDisplay::displayText(I, 20, 20, ss.str(), vpColor::red);
262 
263  vpColVector v_c(6);
264 
265  // Only one tag is detected
266  if (cMo_vec.size() == 1) {
267  cMo = cMo_vec[0];
268 
269  static bool first_time = true;
270  if (first_time) {
271  // Introduce security wrt tag positioning in order to avoid PI rotation
272  std::vector<vpHomogeneousMatrix> v_oMo(2), v_cdMc(2);
273  v_oMo[1].buildFrom(0, 0, 0, 0, 0, M_PI);
274  for (size_t i = 0; i < 2; i++) {
275  v_cdMc[i] = cdMo * v_oMo[i] * cMo.inverse();
276  }
277  if (std::fabs(v_cdMc[0].getThetaUVector().getTheta()) < std::fabs(v_cdMc[1].getThetaUVector().getTheta())) {
278  oMo = v_oMo[0];
279  }
280  else {
281  std::cout << "Desired frame modified to avoid PI rotation of the camera" << std::endl;
282  oMo = v_oMo[1]; // Introduce PI rotation
283  }
284  }
285 
286  // Update visual features
287  cdMc = cdMo * oMo * cMo.inverse();
288  t.buildFrom(cdMc);
289  tu.buildFrom(cdMc);
290 
291  if (opt_task_sequencing) {
292  if (!servo_started) {
293  if (send_velocities) {
294  servo_started = true;
295  }
296  t_init_servo = vpTime::measureTimeMs();
297  }
298  v_c = task.computeControlLaw((vpTime::measureTimeMs() - t_init_servo) / 1000.);
299  }
300  else {
301  v_c = task.computeControlLaw();
302  }
303 
304  // Display desired and current pose features
305  vpDisplay::displayFrame(I, cdMo * oMo, cam, opt_tagSize / 1.5, vpColor::yellow, 2);
306  vpDisplay::displayFrame(I, cMo, cam, opt_tagSize / 2, vpColor::none, 3);
307  // Get tag corners
308  std::vector<vpImagePoint> vip = detector.getPolygon(0);
309  // Get the tag cog corresponding to the projection of the tag frame in the image
310  vip.push_back(detector.getCog(0));
311  // Display the trajectory of the points
312  if (first_time) {
313  traj_vip = new std::vector<vpImagePoint>[vip.size()];
314  }
315  display_point_trajectory(I, vip, traj_vip);
316 
317  if (opt_plot) {
318  plotter->plot(0, iter_plot, task.getError());
319  plotter->plot(1, iter_plot, v_c);
320  iter_plot++;
321  }
322 
323  if (opt_verbose) {
324  std::cout << "v_c: " << v_c.t() << std::endl;
325  }
326 
328  vpThetaUVector cd_tu_c = cdMc.getThetaUVector();
329  double error_tr = sqrt(cd_t_c.sumSquare());
330  double error_tu = vpMath::deg(sqrt(cd_tu_c.sumSquare()));
331 
332  ss.str("");
333  ss << "error_t: " << error_tr;
334  vpDisplay::displayText(I, 20, static_cast<int>(I.getWidth()) - 150, ss.str(), vpColor::red);
335  ss.str("");
336  ss << "error_tu: " << error_tu;
337  vpDisplay::displayText(I, 40, static_cast<int>(I.getWidth()) - 150, ss.str(), vpColor::red);
338 
339  if (opt_verbose)
340  std::cout << "error translation: " << error_tr << " ; error rotation: " << error_tu << std::endl;
341 
342  if (error_tr < convergence_threshold_t && error_tu < convergence_threshold_tu) {
343  has_converged = true;
344  std::cout << "Servo task has converged" << std::endl;
345  ;
346  vpDisplay::displayText(I, 100, 20, "Servo task has converged", vpColor::red);
347  }
348 
349  if (first_time) {
350  first_time = false;
351  }
352  } // end if (cMo_vec.size() == 1)
353  else {
354  v_c = 0;
355  }
356 
357  if (!send_velocities) {
358  v_c = 0;
359  }
360 
361  // Send to the robot
363 
364  ss.str("");
365  ss << "Loop time: " << vpTime::measureTimeMs() - t_start << " ms";
366  vpDisplay::displayText(I, 40, 20, ss.str(), vpColor::red);
367  vpDisplay::flush(I);
368 
370  if (vpDisplay::getClick(I, button, false)) {
371  switch (button) {
373  send_velocities = !send_velocities;
374  break;
375 
377  final_quit = true;
378  v_c = 0;
379  break;
380 
381  default:
382  break;
383  }
384  }
385  }
386  std::cout << "Stop the robot " << std::endl;
388 
389  if (opt_plot && plotter != nullptr) {
390  delete plotter;
391  plotter = nullptr;
392  }
393 
394  if (!final_quit) {
395  while (!final_quit) {
396  rs.acquire(I);
398 
399  vpDisplay::displayText(I, 20, 20, "Click to quit the program.", vpColor::red);
400  vpDisplay::displayText(I, 40, 20, "Visual servo converged.", vpColor::red);
401 
402  if (vpDisplay::getClick(I, false)) {
403  final_quit = true;
404  }
405 
406  vpDisplay::flush(I);
407  }
408  }
409 
410  if (traj_vip) {
411  delete[] traj_vip;
412  }
413  }
414  catch (const vpException &e) {
415  std::cout << "ViSP exception: " << e.what() << std::endl;
416  std::cout << "Stop the robot " << std::endl;
418  return EXIT_FAILURE;
419  }
420  catch (const std::exception &e) {
421  std::cout << "ur_rtde exception: " << e.what() << std::endl;
422  return EXIT_FAILURE;
423  }
424 
425  return EXIT_SUCCESS;
426 }
427 #else
428 int main()
429 {
430 #if !defined(VISP_HAVE_REALSENSE2)
431  std::cout << "Install librealsense-2.x" << std::endl;
432 #endif
433 #if !defined(VISP_HAVE_AFMA6)
434  std::cout << "ViSP is not build with Afma-6 robot support..." << std::endl;
435 #endif
436  return EXIT_SUCCESS;
437 }
438 #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
static const vpColor red
Definition: vpColor.h:211
static const vpColor none
Definition: vpColor.h:223
static const vpColor yellow
Definition: vpColor.h:219
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 displayFrame(const vpImage< unsigned char > &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, double size, const vpColor &color=vpColor::none, unsigned int thickness=1, const vpImagePoint &offset=vpImagePoint(0, 0), const std::string &frameName="", const vpColor &textColor=vpColor::black, const vpImagePoint &textOffset=vpImagePoint(15, 15))
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
Class that defines a 3D visual feature from a axis/angle parametrization that represent the rotatio...
Class that defines the translation visual feature .
Implementation of an homogeneous matrix and operations on such kind of matrices.
vpThetaUVector getThetaUVector() const
vpHomogeneousMatrix inverse() const
vpTranslationVector getTranslationVector() const
void buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
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 double deg(double rad)
Definition: vpMath.h:117
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.
double sumSquare() const
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
Implementation of a rotation vector as axis-angle minimal representation.
Class that consider the case of a translation vector.
VISP_EXPORT double measureTimeMs()