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