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