Visual Servoing Platform  version 3.2.0 under development (2019-01-22)
servoFrankaPBVS.cpp
1 /****************************************************************************
2  *
3  * ViSP, open source Visual Servoing Platform software.
4  * Copyright (C) 2005 - 2019 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 http://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 
42 #include <iostream>
43 
44 #include <visp3/core/vpImageConvert.h>
45 #include <visp3/core/vpCameraParameters.h>
46 #include <visp3/core/vpXmlParserCamera.h>
47 #include <visp3/gui/vpDisplayGDI.h>
48 #include <visp3/gui/vpDisplayX.h>
49 #include <visp3/io/vpImageIo.h>
50 #include <visp3/sensor/vpRealSense2.h>
51 #include <visp3/robot/vpRobotFranka.h>
52 #include <visp3/detection/vpDetectorAprilTag.h>
53 #include <visp3/visual_features/vpFeatureThetaU.h>
54 #include <visp3/visual_features/vpFeatureTranslation.h>
55 #include <visp3/vs/vpServo.h>
56 #include <visp3/gui/vpPlot.h>
57 
58 #if defined(VISP_HAVE_REALSENSE2) && defined(VISP_HAVE_CPP11_COMPATIBILITY) && \
59  (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && defined(VISP_HAVE_FRANKA)
60 
61 int main(int argc, char **argv)
62 {
63  double opt_tagSize = 0.120;
64  std::string opt_robot_ip = "192.168.1.1";
65  std::string opt_eMc_filename = "";
66  bool display_tag = true;
67  int opt_quad_decimate = 2;
68  bool opt_verbose = false;
69  bool opt_plot = false;
70  bool opt_adaptive_gain = false;
71  bool opt_task_sequencing = false;
72  double convergence_threshold_t = 0.0005, convergence_threshold_tu = vpMath::rad(0.5);
73 
74  for (int i = 1; i < argc; i++) {
75  if (std::string(argv[i]) == "--tag_size" && i + 1 < argc) {
76  opt_tagSize = std::stod(argv[i + 1]);
77  }
78  else if (std::string(argv[i]) == "--ip" && i + 1 < argc) {
79  opt_robot_ip = std::string(argv[i + 1]);
80  }
81  else if (std::string(argv[i]) == "--eMc" && i + 1 < argc) {
82  opt_eMc_filename = std::string(argv[i + 1]);
83  }
84  else if (std::string(argv[i]) == "--verbose") {
85  opt_verbose = true;
86  }
87  else if (std::string(argv[i]) == "--plot") {
88  opt_plot = true;
89  }
90  else if (std::string(argv[i]) == "--adaptive_gain") {
91  opt_adaptive_gain = true;
92  }
93  else if (std::string(argv[i]) == "--task_sequencing") {
94  opt_task_sequencing = true;
95  }
96  else if (std::string(argv[i]) == "--quad_decimate" && i + 1 < argc) {
97  opt_quad_decimate = std::stod(argv[i + 1]);
98  }
99  else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") {
100  std::cout << argv[0] << " [--ip <default " << opt_robot_ip << ">] [--tag_size <marker size in meter; default " << opt_tagSize << ">] [--eMc <eMc extrinsic file>] "
101  << "[--quad_decimate <decimation; default " << opt_quad_decimate << ">] [--adaptive_gain] [--plot] [--task_sequencing] [--verbose] [--help] [-h]"
102  << "\n";
103  return EXIT_SUCCESS;
104  }
105  }
106 
107  vpRobotFranka robot;
108 
109  try {
110  robot.connect(opt_robot_ip);
111 
112  vpRealSense2 rs;
113  rs2::config config;
114  unsigned int width = 640, height = 480;
115  config.enable_stream(RS2_STREAM_COLOR, 640, 480, RS2_FORMAT_RGBA8, 30);
116  config.enable_stream(RS2_STREAM_DEPTH, 640, 480, RS2_FORMAT_Z16, 30);
117  config.enable_stream(RS2_STREAM_INFRARED, 640, 480, RS2_FORMAT_Y8, 30);
118  rs.open(config);
119 
120  // Get camera extrinsics
121  vpPoseVector ePc;
122  ePc[0] = 0.0337731; ePc[1] = -0.00535012; ePc[2] = -0.0523339;
123  ePc[3] = -0.247294; ePc[4] = -0.306729; ePc[5] = 1.53055;
124 
125  if (!opt_eMc_filename.empty()) {
126  ePc.loadYAML(opt_eMc_filename, ePc);
127  }
128  else {
129  std::cout << "Warning, opt_eMc_filename is empty! Use hard coded values." << "\n";
130  }
131  vpHomogeneousMatrix eMc(ePc);
132  std::cout << "eMc:\n" << eMc << "\n";
133 
134  // Get camera intrinsics
136  std::cout << "cam:\n" << cam << "\n";
137 
138  vpImage<unsigned char> I(height, width);
139 
140 #if defined(VISP_HAVE_X11)
141  vpDisplayX dc(I, 10, 10, "Color image");
142 #elif defined(VISP_HAVE_GDI)
143  vpDisplayGDI dc(I, 10, 10, "Color image");
144 #endif
145 
148  //vpDetectorAprilTag::vpPoseEstimationMethod poseEstimationMethod = vpDetectorAprilTag::BEST_RESIDUAL_VIRTUAL_VS;
149  vpDetectorAprilTag detector(tagFamily);
150  detector.setAprilTagPoseEstimationMethod(poseEstimationMethod);
151  detector.setDisplayTag(display_tag);
152  detector.setAprilTagQuadDecimate(opt_quad_decimate);
153 
154  // Servo
155  vpHomogeneousMatrix cdMc, cMo, cdMo, oMo;
156 
157  // Desired pose to reach
158  cdMo[0][0] = 1; cdMo[0][1] = 0; cdMo[0][2] = 0;
159  cdMo[1][0] = 0; cdMo[1][1] = -1; cdMo[1][2] = 0;
160  cdMo[2][0] = 0; cdMo[2][1] = 0; cdMo[2][2] = -1;
161  cdMo[0][3] = 0;
162  cdMo[1][3] = 0;
163  cdMo[2][3] = 0.3; // 30 cm along camera z axis
164 
165  cdMc = cdMo * cMo.inverse();
168  t.buildFrom(cdMc);
169  tu.buildFrom(cdMc);
170 
173 
174  vpServo task;
175  task.addFeature(t, td);
176  task.addFeature(tu, tud);
179 
180  if (opt_adaptive_gain) {
181  vpAdaptiveGain lambda(1.5, 0.4, 30); // lambda(0)=4, lambda(oo)=0.4 and lambda'(0)=30
182  task.setLambda(lambda);
183  }
184  else {
185  task.setLambda(0.5);
186  }
187 
188  vpPlot *plotter = NULL;
189  int iter_plot = 0;
190 
191  if (opt_plot) {
192  plotter = new vpPlot(2, 250 * 2, 500, I.getWidth() + 80, 10, "Real time curves plotter");
193  plotter->setTitle(0, "Visual features error");
194  plotter->setTitle(1, "Camera velocities");
195  plotter->initGraph(0, 6);
196  plotter->initGraph(1, 6);
197  plotter->setLegend(0, 0, "error_feat_tx");
198  plotter->setLegend(0, 1, "error_feat_ty");
199  plotter->setLegend(0, 2, "error_feat_tz");
200  plotter->setLegend(0, 3, "error_feat_theta_ux");
201  plotter->setLegend(0, 4, "error_feat_theta_uy");
202  plotter->setLegend(0, 5, "error_feat_theta_uz");
203  plotter->setLegend(1, 0, "vc_x");
204  plotter->setLegend(1, 1, "vc_y");
205  plotter->setLegend(1, 2, "vc_z");
206  plotter->setLegend(1, 3, "wc_x");
207  plotter->setLegend(1, 4, "wc_y");
208  plotter->setLegend(1, 5, "wc_z");
209  }
210 
211  bool final_quit = false;
212  bool has_converged = false;
213  bool send_velocities = false;
214  bool servo_started = false;
215 
216  static double t_init_servo = vpTime::measureTimeMs();
217 
218  robot.set_eMc(eMc); // Set location of the camera wrt end-effector frame
220 
221  while (!has_converged && !final_quit) {
222  double t_start = vpTime::measureTimeMs();
223 
224  rs.acquire(I);
225 
227 
228  std::vector<vpHomogeneousMatrix> cMo_vec;
229  detector.detect(I, opt_tagSize, cam, cMo_vec);
230 
231  std::stringstream ss;
232  ss << "Left click to " << (send_velocities ? "stop the robot" : "servo the robot") << ", right click to quit.";
233  vpDisplay::displayText(I, 20, 20, ss.str(), vpColor::red);
234 
235  vpColVector v_c(6);
236 
237  // Only one tag is detected
238  if (cMo_vec.size() == 1) {
239  cMo = cMo_vec[0];
240 
241  static bool first_time = true;
242  if (first_time) {
243  // Introduce security wrt tag positionning in order to avoid PI rotation
244  std::vector<vpHomogeneousMatrix> v_oMo(2), v_cdMc(2);
245  v_oMo[1].buildFrom(0, 0, 0, 0, 0, M_PI);
246  for (size_t i = 0; i < 2; i++) {
247  v_cdMc[i] = cdMo * v_oMo[i] * cMo.inverse();
248  }
249  if (std::fabs(v_cdMc[0].getThetaUVector().getTheta()) < std::fabs(v_cdMc[1].getThetaUVector().getTheta())) {
250  oMo = v_oMo[0];
251  }
252  else {
253  std::cout << "Desired frame modified to avoid PI rotation of the camera" << std::endl;
254  oMo = v_oMo[1]; // Introduce PI rotation
255  }
256 
257  first_time = false;
258  }
259  // Display desired and current pose
260  vpDisplay::displayFrame(I, cdMo * oMo, cam, opt_tagSize / 1.5, vpColor::yellow, 2);
261  vpDisplay::displayFrame(I, cMo, cam, opt_tagSize / 2, vpColor::none, 3);
262 
263  // VVS
264  cdMc = cdMo * oMo * cMo.inverse();
265  t.buildFrom(cdMc);
266  tu.buildFrom(cdMc);
267 
268  if (opt_task_sequencing) {
269  if (! servo_started) {
270  if (send_velocities) {
271  servo_started = true;
272  }
273  t_init_servo = vpTime::measureTimeMs();
274  }
275  v_c = task.computeControlLaw((vpTime::measureTimeMs() - t_init_servo)/1000.);
276  }
277  else {
278  v_c = task.computeControlLaw();
279  }
280 
281  if (opt_plot) {
282  plotter->plot(0, iter_plot, task.getError());
283  plotter->plot(1, iter_plot, v_c);
284  iter_plot++;
285  }
286 
287  if (opt_verbose) {
288  std::cout << "v_c: " << v_c.t() << std::endl;
289  }
290 
292  vpThetaUVector cd_tu_c = cdMc.getThetaUVector();
293  double error_t = sqrt(cd_t_c.sumSquare());
294  double error_tu = vpMath::deg(sqrt(cd_tu_c.sumSquare()));
295 
296  ss.str("");
297  ss << "error_t: " << error_t;
298  vpDisplay::displayText(I, 20, I.getWidth() - 150, ss.str(), vpColor::red);
299  ss.str("");
300  ss << "error_tu: " << error_tu;
301  vpDisplay::displayText(I, 40, I.getWidth() - 150, ss.str(), vpColor::red);
302 
303  if (opt_verbose)
304  std::cout << "error translation: " << error_t << " ; error rotation: " << error_tu << "\n";
305 
306  if (error_t < convergence_threshold_t && error_tu < convergence_threshold_tu) {
307  has_converged = true;
308  std::cout << "Servo task has converged" << "\n";
309  vpDisplay::displayText(I, 100, 20, "Servo task has converged, wait for robot go to init position", vpColor::red);
310  }
311  } //if (cMo_vec.size() == 1)
312  else {
313  v_c = 0;
314  }
315 
316  if (!send_velocities) {
317  v_c = 0;
318  }
319 
320  // Send to the robot
322 
323  ss.str("");
324  ss << "Loop time: " << vpTime::measureTimeMs() - t_start << " ms";
325  vpDisplay::displayText(I, 40, 20, ss.str(), vpColor::red);
326  vpDisplay::flush(I);
327 
329  if (vpDisplay::getClick(I, button, false)) {
330  switch (button) {
332  send_velocities = !send_velocities;
333  break;
334 
336  final_quit = true;
337  v_c = 0;
338  break;
339 
340  default:
341  break;
342  }
343  }
344  }
345  std::cout << "Stop the robot " << std::endl;
347 
348  if (opt_plot && plotter != NULL) {
349  delete plotter;
350  plotter = NULL;
351  }
352 
353  task.kill();
354 
355  if (!final_quit) {
356  while (!final_quit) {
357  rs.acquire(I);
359 
360  vpDisplay::displayText(I, 20, 20, "Click to quit the program.", vpColor::red);
361  vpDisplay::displayText(I, 40, 20, "Visual servo converged.", vpColor::red);
362 
363  if (vpDisplay::getClick(I, false)) {
364  final_quit = true;
365  }
366 
367  vpDisplay::flush(I);
368  }
369  }
370  }
371  catch(const vpException &e) {
372  std::cout << "ViSP exception: " << e.what() << std::endl;
373  std::cout << "Stop the robot " << std::endl;
375  return EXIT_FAILURE;
376  }
377  catch(const franka::NetworkException &e) {
378  std::cout << "Franka network exception: " << e.what() << std::endl;
379  std::cout << "Check if you are connected to the Franka robot"
380  << " or if you specified the right IP using --ip command line option set by default to 192.168.1.1. " << std::endl;
381  return EXIT_FAILURE;
382  }
383  catch(const std::exception &e) {
384  std::cout << "Franka exception: " << e.what() << std::endl;
385  return EXIT_FAILURE;
386  }
387 
388  return 0;
389 }
390 #else
391 int main()
392 {
393 #if !defined(VISP_HAVE_REALSENSE2)
394  std::cout << "Install librealsense-2.x" << std::endl;
395 #endif
396 #if !defined(VISP_HAVE_CPP11_COMPATIBILITY)
397  std::cout << "Build ViSP with C++11 compiler flag (cmake -DUSE_CPP11=ON)." << std::endl;
398 #endif
399 #if !defined(VISP_HAVE_FRANKA)
400  std::cout << "Install libfranka." << std::endl;
401 #endif
402  return 0;
403 }
404 #endif
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel)
void setAprilTagQuadDecimate(const float quadDecimate)
Adaptive gain computation.
Class that defines the translation visual feature .
static bool getClick(const vpImage< unsigned char > &I, bool blocking=true)
void setAprilTagPoseEstimationMethod(const vpPoseEstimationMethod &poseEstimationMethod)
static bool loadYAML(const std::string &filename, vpArray2D< Type > &A, char *header=NULL)
Definition: vpArray2D.h:434
vpRobot::vpRobotStateType setRobotState(vpRobot::vpRobotStateType newState)
unsigned int getWidth() const
Definition: vpImage.h:239
Implementation of an homogeneous matrix and operations on such kind of matrices.
Display for windows using GDI (available on any windows 32 platform).
Definition: vpDisplayGDI.h:129
static void displayText(const vpImage< unsigned char > &I, const vpImagePoint &ip, const std::string &s, const vpColor &color)
Use the X11 console to display images on unix-like OS. Thus to enable this class X11 should be instal...
Definition: vpDisplayX.h:151
void addFeature(vpBasicFeature &s, vpBasicFeature &s_star, const unsigned int select=vpBasicFeature::FEATURE_ALL)
Definition: vpServo.cpp:497
static const vpColor none
Definition: vpColor.h:192
error that can be emited by ViSP classes.
Definition: vpException.h:71
void plot(const unsigned int graphNum, const unsigned int curveNum, const double x, const double y)
Definition: vpPlot.cpp:286
void open(const rs2::config &cfg=rs2::config())
static void flush(const vpImage< unsigned char > &I)
vpThetaUVector getThetaUVector() const
void setTitle(const unsigned int graphNum, const std::string &title)
Definition: vpPlot.cpp:498
vpCameraParameters getCameraParameters(const rs2_stream &stream, vpCameraParameters::vpCameraParametersProjType type=vpCameraParameters::perspectiveProjWithDistortion) const
VISP_EXPORT double measureTimeMs()
Definition: vpTime.cpp:88
static const vpColor red
Definition: vpColor.h:180
void set_eMc(const vpHomogeneousMatrix &eMc)
const char * what() const
void kill()
Definition: vpServo.cpp:192
Initialize the velocity controller.
Definition: vpRobot.h:67
vpColVector getError() const
Definition: vpServo.h:282
vpColVector computeControlLaw()
Definition: vpServo.cpp:935
vpTranslationVector getTranslationVector() const
static void display(const vpImage< unsigned char > &I)
Generic class defining intrinsic camera parameters.
void setLambda(double c)
Definition: vpServo.h:406
void acquire(vpImage< unsigned char > &grey)
void buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
void setInteractionMatrixType(const vpServoIteractionMatrixType &interactionMatrixType, const vpServoInversionType &interactionMatrixInversion=PSEUDO_INVERSE)
Definition: vpServo.cpp:574
static double rad(double deg)
Definition: vpMath.h:102
void setLegend(const unsigned int graphNum, const unsigned int curveNum, const std::string &legend)
Definition: vpPlot.cpp:547
void initGraph(unsigned int graphNum, unsigned int curveNbr)
Definition: vpPlot.cpp:206
static double deg(double rad)
Definition: vpMath.h:95
Implementation of column vector and the associated operations.
Definition: vpColVector.h:72
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))
Implementation of a pose vector and operations on poses.
Definition: vpPoseVector.h:92
vpHomogeneousMatrix inverse() const
Class that defines a 3D visual feature from a axis/angle parametrization that represent the rotatio...
void connect(const std::string &franka_address, franka::RealtimeConfig realtime_config=franka::RealtimeConfig::kEnforce)
This class enables real time drawing of 2D or 3D graphics. An instance of the class open a window whi...
Definition: vpPlot.h:115
double sumSquare() const
static const vpColor yellow
Definition: vpColor.h:188
void setServo(const vpServoType &servo_type)
Definition: vpServo.cpp:223
Class that consider the case of a translation vector.
Implementation of a rotation vector as axis-angle minimal representation.
void setDisplayTag(const bool display, const vpColor &color=vpColor::none, const unsigned int thickness=2)
bool detect(const vpImage< unsigned char > &I)