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