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