Visual Servoing Platform  version 3.6.1 under development (2024-12-17)
servoUniversalRobotsIBVS.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 *****************************************************************************/
59 #include <iostream>
60 
61 #include <visp3/core/vpCameraParameters.h>
62 #include <visp3/core/vpConfig.h>
63 #include <visp3/detection/vpDetectorAprilTag.h>
64 #include <visp3/gui/vpDisplayGDI.h>
65 #include <visp3/gui/vpDisplayX.h>
66 #include <visp3/gui/vpPlot.h>
67 #include <visp3/io/vpImageIo.h>
68 #include <visp3/robot/vpRobotUniversalRobots.h>
69 #include <visp3/sensor/vpRealSense2.h>
70 #include <visp3/visual_features/vpFeatureBuilder.h>
71 #include <visp3/visual_features/vpFeaturePoint.h>
72 #include <visp3/vs/vpServo.h>
73 #include <visp3/vs/vpServoDisplay.h>
74 
75 #if defined(VISP_HAVE_REALSENSE2) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && defined(VISP_HAVE_UR_RTDE)
76 
77 #ifdef ENABLE_VISP_NAMESPACE
78 using namespace VISP_NAMESPACE_NAME;
79 #endif
80 
81 void display_point_trajectory(const vpImage<unsigned char> &I, const std::vector<vpImagePoint> &vip,
82  std::vector<vpImagePoint> *traj_vip)
83 {
84  for (size_t i = 0; i < vip.size(); i++) {
85  if (traj_vip[i].size()) {
86  // Add the point only if distance with the previous > 1 pixel
87  if (vpImagePoint::distance(vip[i], traj_vip[i].back()) > 1.) {
88  traj_vip[i].push_back(vip[i]);
89  }
90  }
91  else {
92  traj_vip[i].push_back(vip[i]);
93  }
94  }
95  for (size_t i = 0; i < vip.size(); i++) {
96  for (size_t j = 1; j < traj_vip[i].size(); j++) {
97  vpDisplay::displayLine(I, traj_vip[i][j - 1], traj_vip[i][j], vpColor::green, 2);
98  }
99  }
100 }
101 
102 int main(int argc, char **argv)
103 {
104  double opt_tagSize = 0.120;
105  std::string opt_robot_ip = "192.168.0.100";
106  std::string opt_eMc_filename = "";
107  bool display_tag = true;
108  int opt_quad_decimate = 2;
109  bool opt_verbose = false;
110  bool opt_plot = false;
111  bool opt_adaptive_gain = false;
112  bool opt_task_sequencing = false;
113  double convergence_threshold = 0.00005;
114 
115  for (int i = 1; i < argc; i++) {
116  if (std::string(argv[i]) == "--tag_size" && i + 1 < argc) {
117  opt_tagSize = std::stod(argv[i + 1]);
118  }
119  else if (std::string(argv[i]) == "--ip" && i + 1 < argc) {
120  opt_robot_ip = std::string(argv[i + 1]);
121  }
122  else if (std::string(argv[i]) == "--eMc" && i + 1 < argc) {
123  opt_eMc_filename = std::string(argv[i + 1]);
124  }
125  else if (std::string(argv[i]) == "--verbose") {
126  opt_verbose = true;
127  }
128  else if (std::string(argv[i]) == "--plot") {
129  opt_plot = true;
130  }
131  else if (std::string(argv[i]) == "--adaptive_gain") {
132  opt_adaptive_gain = true;
133  }
134  else if (std::string(argv[i]) == "--task_sequencing") {
135  opt_task_sequencing = true;
136  }
137  else if (std::string(argv[i]) == "--quad_decimate" && i + 1 < argc) {
138  opt_quad_decimate = std::stoi(argv[i + 1]);
139  }
140  else if (std::string(argv[i]) == "--no-convergence-threshold") {
141  convergence_threshold = 0.;
142  }
143  else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") {
144  std::cout
145  << argv[0] << " [--ip <default " << opt_robot_ip << ">] [--tag_size <marker size in meter; default "
146  << opt_tagSize << ">] [--eMc <eMc extrinsic file>] "
147  << "[--quad_decimate <decimation; default " << opt_quad_decimate
148  << ">] [--adaptive_gain] [--plot] [--task_sequencing] [--no-convergence-threshold] [--verbose] [--help] [-h]"
149  << "\n";
150  return EXIT_SUCCESS;
151  }
152  }
153 
155 
156  try {
157  robot.connect(opt_robot_ip);
158 
159  std::cout << "WARNING: This example will move the robot! "
160  << "Please make sure to have the user stop button at hand!" << std::endl
161  << "Press Enter to continue..." << std::endl;
162  std::cin.ignore();
163 
164  /*
165  * Move to a safe position
166  */
167  vpColVector q(6, 0);
168  q[0] = -vpMath::rad(16);
169  q[1] = -vpMath::rad(120);
170  q[2] = vpMath::rad(120);
171  q[3] = -vpMath::rad(90);
172  q[4] = -vpMath::rad(90);
173  q[5] = 0;
174  std::cout << "Move to joint position: " << q.t() << std::endl;
176  robot.setPosition(vpRobot::JOINT_STATE, q);
177 
178  vpRealSense2 rs;
179  rs2::config config;
180  unsigned int width = 640, height = 480;
181  config.enable_stream(RS2_STREAM_COLOR, 640, 480, RS2_FORMAT_RGBA8, 30);
182  config.enable_stream(RS2_STREAM_DEPTH, 640, 480, RS2_FORMAT_Z16, 30);
183  config.enable_stream(RS2_STREAM_INFRARED, 640, 480, RS2_FORMAT_Y8, 30);
184  rs.open(config);
185 
186  // Get camera extrinsics
187  vpPoseVector ePc;
188  // Set camera extrinsics default values
189  ePc[0] = -0.0312543;
190  ePc[1] = -0.0584638;
191  ePc[2] = 0.0309834;
192  ePc[3] = -0.00506562;
193  ePc[4] = -0.00293325;
194  ePc[5] = 0.0117901;
195 
196  // If provided, read camera extrinsics from --eMc <file>
197  if (!opt_eMc_filename.empty()) {
198  ePc.loadYAML(opt_eMc_filename, ePc);
199  }
200  else {
201  std::cout << "Warning, opt_eMc_filename is empty! Use hard coded values."
202  << "\n";
203  }
204  vpHomogeneousMatrix eMc(ePc);
205  std::cout << "eMc:\n" << eMc << "\n";
206 
207  // Get camera intrinsics
208  vpCameraParameters cam =
210  std::cout << "cam:\n" << cam << "\n";
211 
212  vpImage<unsigned char> I(height, width);
213 
214 #if defined(VISP_HAVE_X11)
215  vpDisplayX dc(I, 10, 10, "Color image");
216 #elif defined(VISP_HAVE_GDI)
217  vpDisplayGDI dc(I, 10, 10, "Color image");
218 #endif
219 
222  // vpDetectorAprilTag::vpPoseEstimationMethod poseEstimationMethod = vpDetectorAprilTag::BEST_RESIDUAL_VIRTUAL_VS;
223  vpDetectorAprilTag detector(tagFamily);
224  detector.setAprilTagPoseEstimationMethod(poseEstimationMethod);
225  detector.setDisplayTag(display_tag);
226  detector.setAprilTagQuadDecimate(opt_quad_decimate);
227 
228  // Servo
229  vpHomogeneousMatrix cdMc, cMo, oMo;
230 
231  // Desired pose used to compute the desired features
232  vpHomogeneousMatrix cdMo(vpTranslationVector(0, 0, opt_tagSize * 3), // 3 times tag with along camera z axis
233  vpRotationMatrix({ 1, 0, 0, 0, -1, 0, 0, 0, -1 }));
234 
235  // Create visual features
236  std::vector<vpFeaturePoint> p(4), pd(4); // We use 4 points
237 
238  // Define 4 3D points corresponding to the CAD model of the Apriltag
239  std::vector<vpPoint> point(4);
240  point[0].setWorldCoordinates(-opt_tagSize / 2., -opt_tagSize / 2., 0);
241  point[1].setWorldCoordinates(opt_tagSize / 2., -opt_tagSize / 2., 0);
242  point[2].setWorldCoordinates(opt_tagSize / 2., opt_tagSize / 2., 0);
243  point[3].setWorldCoordinates(-opt_tagSize / 2., opt_tagSize / 2., 0);
244 
245  vpServo task;
246  // Add the 4 visual feature points
247  for (size_t i = 0; i < p.size(); i++) {
248  task.addFeature(p[i], pd[i]);
249  }
252 
253  if (opt_adaptive_gain) {
254  vpAdaptiveGain lambda(1.5, 0.4, 30); // lambda(0)=4, lambda(oo)=0.4 and lambda'(0)=30
255  task.setLambda(lambda);
256  }
257  else {
258  task.setLambda(0.5);
259  }
260 
261  vpPlot *plotter = nullptr;
262  int iter_plot = 0;
263 
264  if (opt_plot) {
265  plotter = new vpPlot(2, static_cast<int>(250 * 2), 500, static_cast<int>(I.getWidth()) + 80, 10,
266  "Real time curves plotter");
267  plotter->setTitle(0, "Visual features error");
268  plotter->setTitle(1, "Camera velocities");
269  plotter->initGraph(0, 8);
270  plotter->initGraph(1, 6);
271  plotter->setLegend(0, 0, "error_feat_p1_x");
272  plotter->setLegend(0, 1, "error_feat_p1_y");
273  plotter->setLegend(0, 2, "error_feat_p2_x");
274  plotter->setLegend(0, 3, "error_feat_p2_y");
275  plotter->setLegend(0, 4, "error_feat_p3_x");
276  plotter->setLegend(0, 5, "error_feat_p3_y");
277  plotter->setLegend(0, 6, "error_feat_p4_x");
278  plotter->setLegend(0, 7, "error_feat_p4_y");
279  plotter->setLegend(1, 0, "vc_x");
280  plotter->setLegend(1, 1, "vc_y");
281  plotter->setLegend(1, 2, "vc_z");
282  plotter->setLegend(1, 3, "wc_x");
283  plotter->setLegend(1, 4, "wc_y");
284  plotter->setLegend(1, 5, "wc_z");
285  }
286 
287  bool final_quit = false;
288  bool has_converged = false;
289  bool send_velocities = false;
290  bool servo_started = false;
291  std::vector<vpImagePoint> *traj_corners = nullptr; // To memorize point trajectory
292 
293  static double t_init_servo = vpTime::measureTimeMs();
294 
295  robot.set_eMc(eMc); // Set location of the camera wrt end-effector frame
297 
298  while (!has_converged && !final_quit) {
299  double t_start = vpTime::measureTimeMs();
300 
301  rs.acquire(I);
302 
304 
305  std::vector<vpHomogeneousMatrix> cMo_vec;
306  detector.detect(I, opt_tagSize, cam, cMo_vec);
307 
308  {
309  std::stringstream ss;
310  ss << "Left click to " << (send_velocities ? "stop the robot" : "servo the robot") << ", right click to quit.";
311  vpDisplay::displayText(I, 20, 20, ss.str(), vpColor::red);
312  }
313 
314  vpColVector v_c(6);
315 
316  // Only one tag is detected
317  if (cMo_vec.size() == 1) {
318  cMo = cMo_vec[0];
319 
320  static bool first_time = true;
321  if (first_time) {
322  // Introduce security wrt tag positioning in order to avoid PI rotation
323  std::vector<vpHomogeneousMatrix> v_oMo(2), v_cdMc(2);
324  v_oMo[1].buildFrom(0, 0, 0, 0, 0, M_PI);
325  for (size_t i = 0; i < 2; i++) {
326  v_cdMc[i] = cdMo * v_oMo[i] * cMo.inverse();
327  }
328  if (std::fabs(v_cdMc[0].getThetaUVector().getTheta()) < std::fabs(v_cdMc[1].getThetaUVector().getTheta())) {
329  oMo = v_oMo[0];
330  }
331  else {
332  std::cout << "Desired frame modified to avoid PI rotation of the camera" << std::endl;
333  oMo = v_oMo[1]; // Introduce PI rotation
334  }
335 
336  // Compute the desired position of the features from the desired pose
337  for (size_t i = 0; i < point.size(); i++) {
338  vpColVector cP, p_;
339  point[i].changeFrame(cdMo * oMo, cP);
340  point[i].projection(cP, p_);
341 
342  pd[i].set_x(p_[0]);
343  pd[i].set_y(p_[1]);
344  pd[i].set_Z(cP[2]);
345  }
346  }
347 
348  // Get tag corners
349  std::vector<vpImagePoint> corners = detector.getPolygon(0);
350 
351  // Update visual features
352  for (size_t i = 0; i < corners.size(); i++) {
353  // Update the point feature from the tag corners location
354  vpFeatureBuilder::create(p[i], cam, corners[i]);
355  // Set the feature Z coordinate from the pose
356  vpColVector cP;
357  point[i].changeFrame(cMo, cP);
358 
359  p[i].set_Z(cP[2]);
360  }
361 
362  if (opt_task_sequencing) {
363  if (!servo_started) {
364  if (send_velocities) {
365  servo_started = true;
366  }
367  t_init_servo = vpTime::measureTimeMs();
368  }
369  v_c = task.computeControlLaw((vpTime::measureTimeMs() - t_init_servo) / 1000.);
370  }
371  else {
372  v_c = task.computeControlLaw();
373  }
374 
375  // Display the current and desired feature points in the image display
376  vpServoDisplay::display(task, cam, I);
377  for (size_t i = 0; i < corners.size(); i++) {
378  std::stringstream ss;
379  ss << i;
380  // Display current point indexes
381  vpDisplay::displayText(I, corners[i] + vpImagePoint(15, 15), ss.str(), vpColor::red);
382  // Display desired point indexes
383  vpImagePoint ip;
384  vpMeterPixelConversion::convertPoint(cam, pd[i].get_x(), pd[i].get_y(), ip);
385  vpDisplay::displayText(I, ip + vpImagePoint(15, 15), ss.str(), vpColor::red);
386  }
387  if (first_time) {
388  traj_corners = new std::vector<vpImagePoint>[corners.size()];
389  }
390  // Display the trajectory of the points used as features
391  display_point_trajectory(I, corners, traj_corners);
392 
393  if (opt_plot) {
394  plotter->plot(0, iter_plot, task.getError());
395  plotter->plot(1, iter_plot, v_c);
396  iter_plot++;
397  }
398 
399  if (opt_verbose) {
400  std::cout << "v_c: " << v_c.t() << std::endl;
401  }
402 
403  double error = task.getError().sumSquare();
404  std::stringstream ss;
405  ss << "error: " << error;
406  vpDisplay::displayText(I, 20, static_cast<int>(I.getWidth()) - 150, ss.str(), vpColor::red);
407 
408  if (opt_verbose)
409  std::cout << "error: " << error << std::endl;
410 
411  if (error < convergence_threshold) {
412  has_converged = true;
413  std::cout << "Servo task has converged"
414  << "\n";
415  vpDisplay::displayText(I, 100, 20, "Servo task has converged", vpColor::red);
416  }
417  if (first_time) {
418  first_time = false;
419  }
420  } // end if (cMo_vec.size() == 1)
421  else {
422  v_c = 0;
423  }
424 
425  if (!send_velocities) {
426  v_c = 0;
427  }
428 
429  // Send to the robot
431 
432  {
433  std::stringstream ss;
434  ss << "Loop time: " << vpTime::measureTimeMs() - t_start << " ms";
435  vpDisplay::displayText(I, 40, 20, ss.str(), vpColor::red);
436  }
437  vpDisplay::flush(I);
438 
440  if (vpDisplay::getClick(I, button, false)) {
441  switch (button) {
443  send_velocities = !send_velocities;
444  break;
445 
447  final_quit = true;
448  v_c = 0;
449  break;
450 
451  default:
452  break;
453  }
454  }
455  }
456  std::cout << "Stop the robot " << std::endl;
458 
459  if (opt_plot && plotter != nullptr) {
460  delete plotter;
461  plotter = nullptr;
462  }
463 
464  if (!final_quit) {
465  while (!final_quit) {
466  rs.acquire(I);
468 
469  vpDisplay::displayText(I, 20, 20, "Click to quit the program.", vpColor::red);
470  vpDisplay::displayText(I, 40, 20, "Visual servo converged.", vpColor::red);
471 
472  if (vpDisplay::getClick(I, false)) {
473  final_quit = true;
474  }
475 
476  vpDisplay::flush(I);
477  }
478  }
479  if (traj_corners) {
480  delete[] traj_corners;
481  }
482  }
483  catch (const vpException &e) {
484  std::cout << "ViSP exception: " << e.what() << std::endl;
485  std::cout << "Stop the robot " << std::endl;
487  return EXIT_FAILURE;
488  }
489  catch (const std::exception &e) {
490  std::cout << "ur_rtde exception: " << e.what() << std::endl;
491  return EXIT_FAILURE;
492  }
493 
494  return EXIT_SUCCESS;
495 }
496 #else
497 int main()
498 {
499 #if !defined(VISP_HAVE_REALSENSE2)
500  std::cout << "Install librealsense-2.x" << std::endl;
501 #endif
502 #if !defined(VISP_HAVE_UR_RTDE)
503  std::cout << "ViSP is not build with libur_rtde 3rd party used to control a robot from Universal Robots..."
504  << std::endl;
505 #endif
506  return EXIT_SUCCESS;
507 }
508 #endif
Adaptive gain computation.
static bool loadYAML(const std::string &filename, vpArray2D< Type > &A, char *header=nullptr)
Definition: vpArray2D.h:783
Generic class defining intrinsic camera parameters.
@ perspectiveProjWithDistortion
Perspective projection with distortion model.
Implementation of column vector and the associated operations.
Definition: vpColVector.h:191
double sumSquare() const
static const vpColor red
Definition: vpColor.h:217
static const vpColor green
Definition: vpColor.h:220
@ TAG_36h11
AprilTag 36h11 pattern (recommended)
Display for windows using GDI (available on any windows 32 platform).
Definition: vpDisplayGDI.h:130
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:60
const char * what() const
Definition: vpException.cpp:71
static void create(vpFeaturePoint &s, const vpCameraParameters &cam, const vpImagePoint &t)
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:242
static double rad(double deg)
Definition: vpMath.h:129
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:112
void initGraph(unsigned int graphNum, unsigned int curveNbr)
Definition: vpPlot.cpp:203
void setLegend(unsigned int graphNum, unsigned int curveNum, const std::string &legend)
Definition: vpPlot.cpp:552
void plot(unsigned int graphNum, unsigned int curveNum, double x, double y)
Definition: vpPlot.cpp:270
void setTitle(unsigned int graphNum, const std::string &title)
Definition: vpPlot.cpp:510
Implementation of a pose vector and operations on poses.
Definition: vpPoseVector.h:203
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())
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel) VP_OVERRIDE
@ JOINT_STATE
Definition: vpRobot.h:82
@ CAMERA_FRAME
Definition: vpRobot.h:84
@ STATE_POSITION_CONTROL
Initialize the position controller.
Definition: vpRobot.h:68
@ STATE_VELOCITY_CONTROL
Initialize the velocity controller.
Definition: vpRobot.h:67
@ STATE_STOP
Stops robot motion especially in velocity and acceleration control.
Definition: vpRobot.h:66
virtual vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
Definition: vpRobot.cpp:202
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:380
@ EYEINHAND_CAMERA
Definition: vpServo.h:161
void addFeature(vpBasicFeature &s_cur, vpBasicFeature &s_star, unsigned int select=vpBasicFeature::FEATURE_ALL)
Definition: vpServo.cpp:331
void setLambda(double c)
Definition: vpServo.h:986
void setServo(const vpServoType &servo_type)
Definition: vpServo.cpp:134
vpColVector getError() const
Definition: vpServo.h:510
vpColVector computeControlLaw()
Definition: vpServo.cpp:705
@ CURRENT
Definition: vpServo.h:202
Class that consider the case of a translation vector.
VISP_EXPORT double measureTimeMs()