Visual Servoing Platform  version 3.6.1 under development (2024-04-20)
servoFrankaIBVS.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 *****************************************************************************/
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/vpRobotFranka.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) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && defined(VISP_HAVE_FRANKA)
78 
79 void display_point_trajectory(const vpImage<unsigned char> &I, const std::vector<vpImagePoint> &vip,
80  std::vector<vpImagePoint> *traj_vip)
81 {
82  for (size_t i = 0; i < vip.size(); i++) {
83  if (traj_vip[i].size()) {
84  // Add the point only if distance with the previous > 1 pixel
85  if (vpImagePoint::distance(vip[i], traj_vip[i].back()) > 1.) {
86  traj_vip[i].push_back(vip[i]);
87  }
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.1.1";
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  }
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 = 0.;
140  }
141  else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") {
142  std::cout
143  << argv[0] << " [--ip <default " << opt_robot_ip << ">] [--tag_size <marker size in meter; default "
144  << opt_tagSize << ">] [--eMc <eMc extrinsic file>] "
145  << "[--quad_decimate <decimation; default " << opt_quad_decimate
146  << ">] [--adaptive_gain] [--plot] [--task_sequencing] [--no-convergence-threshold] [--verbose] [--help] [-h]"
147  << "\n";
148  return EXIT_SUCCESS;
149  }
150  }
151 
152  vpRobotFranka robot;
153 
154  try {
155  robot.connect(opt_robot_ip);
156 
157  vpRealSense2 rs;
158  rs2::config config;
159  unsigned int width = 640, height = 480;
160  config.enable_stream(RS2_STREAM_COLOR, 640, 480, RS2_FORMAT_RGBA8, 30);
161  config.enable_stream(RS2_STREAM_DEPTH, 640, 480, RS2_FORMAT_Z16, 30);
162  config.enable_stream(RS2_STREAM_INFRARED, 640, 480, RS2_FORMAT_Y8, 30);
163  rs.open(config);
164 
165  // Get camera extrinsics
166  vpPoseVector ePc;
167  // Set camera extrinsics default values
168  ePc[0] = 0.0337731;
169  ePc[1] = -0.00535012;
170  ePc[2] = -0.0523339;
171  ePc[3] = -0.247294;
172  ePc[4] = -0.306729;
173  ePc[5] = 1.53055;
174 
175  // If provided, read camera extrinsics from --eMc <file>
176  if (!opt_eMc_filename.empty()) {
177  ePc.loadYAML(opt_eMc_filename, ePc);
178  }
179  else {
180  std::cout << "Warning, opt_eMc_filename is empty! Use hard coded values."
181  << "\n";
182  }
183  vpHomogeneousMatrix eMc(ePc);
184  std::cout << "eMc:\n" << eMc << "\n";
185 
186  // Get camera intrinsics
187  vpCameraParameters cam =
189  std::cout << "cam:\n" << cam << "\n";
190 
191  vpImage<unsigned char> I(height, width);
192 
193 #if defined(VISP_HAVE_X11)
194  vpDisplayX dc(I, 10, 10, "Color image");
195 #elif defined(VISP_HAVE_GDI)
196  vpDisplayGDI dc(I, 10, 10, "Color image");
197 #endif
198 
201  // vpDetectorAprilTag::vpPoseEstimationMethod poseEstimationMethod = vpDetectorAprilTag::BEST_RESIDUAL_VIRTUAL_VS;
202  vpDetectorAprilTag detector(tagFamily);
203  detector.setAprilTagPoseEstimationMethod(poseEstimationMethod);
204  detector.setDisplayTag(display_tag);
205  detector.setAprilTagQuadDecimate(opt_quad_decimate);
206 
207  // Servo
208  vpHomogeneousMatrix cdMc, cMo, oMo;
209 
210  // Desired pose used to compute the desired features
211  vpHomogeneousMatrix cdMo(vpTranslationVector(0, 0, opt_tagSize * 3), // 3 times tag with along camera z axis
212  vpRotationMatrix({ 1, 0, 0, 0, -1, 0, 0, 0, -1 }));
213 
214  // Create visual features
215  std::vector<vpFeaturePoint> p(4), pd(4); // We use 4 points
216 
217  // Define 4 3D points corresponding to the CAD model of the Apriltag
218  std::vector<vpPoint> point(4);
219  point[0].setWorldCoordinates(-opt_tagSize / 2., -opt_tagSize / 2., 0);
220  point[1].setWorldCoordinates(opt_tagSize / 2., -opt_tagSize / 2., 0);
221  point[2].setWorldCoordinates(opt_tagSize / 2., opt_tagSize / 2., 0);
222  point[3].setWorldCoordinates(-opt_tagSize / 2., opt_tagSize / 2., 0);
223 
224  vpServo task;
225  // Add the 4 visual feature points
226  for (size_t i = 0; i < p.size(); i++) {
227  task.addFeature(p[i], pd[i]);
228  }
231 
232  if (opt_adaptive_gain) {
233  vpAdaptiveGain lambda(1.5, 0.4, 30); // lambda(0)=4, lambda(oo)=0.4 and lambda'(0)=30
234  task.setLambda(lambda);
235  }
236  else {
237  task.setLambda(0.5);
238  }
239 
240  vpPlot *plotter = nullptr;
241  int iter_plot = 0;
242 
243  if (opt_plot) {
244  plotter = new vpPlot(2, static_cast<int>(250 * 2), 500, static_cast<int>(I.getWidth()) + 80, 10,
245  "Real time curves plotter");
246  plotter->setTitle(0, "Visual features error");
247  plotter->setTitle(1, "Camera velocities");
248  plotter->initGraph(0, 8);
249  plotter->initGraph(1, 6);
250  plotter->setLegend(0, 0, "error_feat_p1_x");
251  plotter->setLegend(0, 1, "error_feat_p1_y");
252  plotter->setLegend(0, 2, "error_feat_p2_x");
253  plotter->setLegend(0, 3, "error_feat_p2_y");
254  plotter->setLegend(0, 4, "error_feat_p3_x");
255  plotter->setLegend(0, 5, "error_feat_p3_y");
256  plotter->setLegend(0, 6, "error_feat_p4_x");
257  plotter->setLegend(0, 7, "error_feat_p4_y");
258  plotter->setLegend(1, 0, "vc_x");
259  plotter->setLegend(1, 1, "vc_y");
260  plotter->setLegend(1, 2, "vc_z");
261  plotter->setLegend(1, 3, "wc_x");
262  plotter->setLegend(1, 4, "wc_y");
263  plotter->setLegend(1, 5, "wc_z");
264  }
265 
266  bool final_quit = false;
267  bool has_converged = false;
268  bool send_velocities = false;
269  bool servo_started = false;
270  std::vector<vpImagePoint> *traj_corners = nullptr; // To memorize point trajectory
271 
272  static double t_init_servo = vpTime::measureTimeMs();
273 
274  robot.set_eMc(eMc); // Set location of the camera wrt end-effector frame
276 
277  while (!has_converged && !final_quit) {
278  double t_start = vpTime::measureTimeMs();
279 
280  rs.acquire(I);
281 
283 
284  std::vector<vpHomogeneousMatrix> cMo_vec;
285  detector.detect(I, opt_tagSize, cam, cMo_vec);
286 
287  {
288  std::stringstream ss;
289  ss << "Left click to " << (send_velocities ? "stop the robot" : "servo the robot") << ", right click to quit.";
290  vpDisplay::displayText(I, 20, 20, ss.str(), vpColor::red);
291  }
292 
293  vpColVector v_c(6);
294 
295  // Only one tag is detected
296  if (cMo_vec.size() == 1) {
297  cMo = cMo_vec[0];
298 
299  static bool first_time = true;
300  if (first_time) {
301  // Introduce security wrt tag positioning in order to avoid PI rotation
302  std::vector<vpHomogeneousMatrix> v_oMo(2), v_cdMc(2);
303  v_oMo[1].buildFrom(0, 0, 0, 0, 0, M_PI);
304  for (size_t i = 0; i < 2; i++) {
305  v_cdMc[i] = cdMo * v_oMo[i] * cMo.inverse();
306  }
307  if (std::fabs(v_cdMc[0].getThetaUVector().getTheta()) < std::fabs(v_cdMc[1].getThetaUVector().getTheta())) {
308  oMo = v_oMo[0];
309  }
310  else {
311  std::cout << "Desired frame modified to avoid PI rotation of the camera" << std::endl;
312  oMo = v_oMo[1]; // Introduce PI rotation
313  }
314 
315  // Compute the desired position of the features from the desired pose
316  for (size_t i = 0; i < point.size(); i++) {
317  vpColVector cP, p_;
318  point[i].changeFrame(cdMo * oMo, cP);
319  point[i].projection(cP, p_);
320 
321  pd[i].set_x(p_[0]);
322  pd[i].set_y(p_[1]);
323  pd[i].set_Z(cP[2]);
324  }
325  }
326 
327  // Get tag corners
328  std::vector<vpImagePoint> corners = detector.getPolygon(0);
329 
330  // Update visual features
331  for (size_t i = 0; i < corners.size(); i++) {
332  // Update the point feature from the tag corners location
333  vpFeatureBuilder::create(p[i], cam, corners[i]);
334  // Set the feature Z coordinate from the pose
335  vpColVector cP;
336  point[i].changeFrame(cMo, cP);
337 
338  p[i].set_Z(cP[2]);
339  }
340 
341  if (opt_task_sequencing) {
342  if (!servo_started) {
343  if (send_velocities) {
344  servo_started = true;
345  }
346  t_init_servo = vpTime::measureTimeMs();
347  }
348  v_c = task.computeControlLaw((vpTime::measureTimeMs() - t_init_servo) / 1000.);
349  }
350  else {
351  v_c = task.computeControlLaw();
352  }
353 
354  // Display the current and desired feature points in the image display
355  vpServoDisplay::display(task, cam, I);
356  for (size_t i = 0; i < corners.size(); i++) {
357  std::stringstream ss;
358  ss << i;
359  // Display current point indexes
360  vpDisplay::displayText(I, corners[i] + vpImagePoint(15, 15), ss.str(), vpColor::red);
361  // Display desired point indexes
362  vpImagePoint ip;
363  vpMeterPixelConversion::convertPoint(cam, pd[i].get_x(), pd[i].get_y(), ip);
364  vpDisplay::displayText(I, ip + vpImagePoint(15, 15), ss.str(), vpColor::red);
365  }
366  if (first_time) {
367  traj_corners = new std::vector<vpImagePoint>[corners.size()];
368  }
369  // Display the trajectory of the points used as features
370  display_point_trajectory(I, corners, traj_corners);
371 
372  if (opt_plot) {
373  plotter->plot(0, iter_plot, task.getError());
374  plotter->plot(1, iter_plot, v_c);
375  iter_plot++;
376  }
377 
378  if (opt_verbose) {
379  std::cout << "v_c: " << v_c.t() << std::endl;
380  }
381 
382  double error = task.getError().sumSquare();
383  std::stringstream ss;
384  ss << "error: " << error;
385  vpDisplay::displayText(I, 20, static_cast<int>(I.getWidth()) - 150, ss.str(), vpColor::red);
386 
387  if (opt_verbose)
388  std::cout << "error: " << error << std::endl;
389 
390  if (error < convergence_threshold) {
391  has_converged = true;
392  std::cout << "Servo task has converged"
393  << "\n";
394  vpDisplay::displayText(I, 100, 20, "Servo task has converged", vpColor::red);
395  }
396  if (first_time) {
397  first_time = false;
398  }
399  } // end if (cMo_vec.size() == 1)
400  else {
401  v_c = 0;
402  }
403 
404  if (!send_velocities) {
405  v_c = 0;
406  }
407 
408  // Send to the robot
410 
411  {
412  std::stringstream ss;
413  ss << "Loop time: " << vpTime::measureTimeMs() - t_start << " ms";
414  vpDisplay::displayText(I, 40, 20, ss.str(), vpColor::red);
415  }
416  vpDisplay::flush(I);
417 
419  if (vpDisplay::getClick(I, button, false)) {
420  switch (button) {
422  send_velocities = !send_velocities;
423  break;
424 
426  final_quit = true;
427  v_c = 0;
428  break;
429 
430  default:
431  break;
432  }
433  }
434  }
435  std::cout << "Stop the robot " << std::endl;
437 
438  if (opt_plot && plotter != nullptr) {
439  delete plotter;
440  plotter = nullptr;
441  }
442 
443  if (!final_quit) {
444  while (!final_quit) {
445  rs.acquire(I);
447 
448  vpDisplay::displayText(I, 20, 20, "Click to quit the program.", vpColor::red);
449  vpDisplay::displayText(I, 40, 20, "Visual servo converged.", vpColor::red);
450 
451  if (vpDisplay::getClick(I, false)) {
452  final_quit = true;
453  }
454 
455  vpDisplay::flush(I);
456  }
457  }
458  if (traj_corners) {
459  delete[] traj_corners;
460  }
461  }
462  catch (const vpException &e) {
463  std::cout << "ViSP exception: " << e.what() << std::endl;
464  std::cout << "Stop the robot " << std::endl;
466  return EXIT_FAILURE;
467  }
468  catch (const franka::NetworkException &e) {
469  std::cout << "Franka network exception: " << e.what() << std::endl;
470  std::cout << "Check if you are connected to the Franka robot"
471  << " or if you specified the right IP using --ip command line option set by default to 192.168.1.1. "
472  << std::endl;
473  return EXIT_FAILURE;
474  }
475  catch (const std::exception &e) {
476  std::cout << "Franka exception: " << e.what() << std::endl;
477  return EXIT_FAILURE;
478  }
479 
480  return EXIT_SUCCESS;
481 }
482 #else
483 int main()
484 {
485 #if !defined(VISP_HAVE_REALSENSE2)
486  std::cout << "Install librealsense-2.x" << std::endl;
487 #endif
488 #if !defined(VISP_HAVE_FRANKA)
489  std::cout << "Install libfranka." << std::endl;
490 #endif
491  return EXIT_SUCCESS;
492 }
493 #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 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
@ CAMERA_FRAME
Definition: vpRobot.h:82
@ 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()