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