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