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