Visual Servoing Platform version 3.6.0
Loading...
Searching...
No Matches
servoUniversalRobotsPBVS.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
56#include <iostream>
57
58#include <visp3/core/vpCameraParameters.h>
59#include <visp3/detection/vpDetectorAprilTag.h>
60#include <visp3/gui/vpDisplayGDI.h>
61#include <visp3/gui/vpDisplayX.h>
62#include <visp3/gui/vpPlot.h>
63#include <visp3/io/vpImageIo.h>
64#include <visp3/robot/vpRobotUniversalRobots.h>
65#include <visp3/sensor/vpRealSense2.h>
66#include <visp3/visual_features/vpFeatureThetaU.h>
67#include <visp3/visual_features/vpFeatureTranslation.h>
68#include <visp3/vs/vpServo.h>
69#include <visp3/vs/vpServoDisplay.h>
70
71#if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && \
72 (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && defined(VISP_HAVE_UR_RTDE)
73
74void display_point_trajectory(const vpImage<unsigned char> &I, const std::vector<vpImagePoint> &vip,
75 std::vector<vpImagePoint> *traj_vip)
76{
77 for (size_t i = 0; i < vip.size(); i++) {
78 if (traj_vip[i].size()) {
79 // Add the point only if distance with the previous > 1 pixel
80 if (vpImagePoint::distance(vip[i], traj_vip[i].back()) > 1.) {
81 traj_vip[i].push_back(vip[i]);
82 }
83 } else {
84 traj_vip[i].push_back(vip[i]);
85 }
86 }
87 for (size_t i = 0; i < vip.size(); i++) {
88 for (size_t j = 1; j < traj_vip[i].size(); j++) {
89 vpDisplay::displayLine(I, traj_vip[i][j - 1], traj_vip[i][j], vpColor::green, 2);
90 }
91 }
92}
93
94int main(int argc, char **argv)
95{
96 double opt_tagSize = 0.120;
97 std::string opt_robot_ip = "192.168.0.100";
98 std::string opt_eMc_filename = "";
99 bool display_tag = true;
100 int opt_quad_decimate = 2;
101 bool opt_verbose = false;
102 bool opt_plot = false;
103 bool opt_adaptive_gain = false;
104 bool opt_task_sequencing = false;
105 double convergence_threshold_t = 0.0005; // Value in [m]
106 double convergence_threshold_tu = 0.5; // Value in [deg]
107
108 for (int i = 1; i < argc; i++) {
109 if (std::string(argv[i]) == "--tag_size" && i + 1 < argc) {
110 opt_tagSize = std::stod(argv[i + 1]);
111 } else if (std::string(argv[i]) == "--ip" && i + 1 < argc) {
112 opt_robot_ip = std::string(argv[i + 1]);
113 } else if (std::string(argv[i]) == "--eMc" && i + 1 < argc) {
114 opt_eMc_filename = std::string(argv[i + 1]);
115 } else if (std::string(argv[i]) == "--verbose") {
116 opt_verbose = true;
117 } else if (std::string(argv[i]) == "--plot") {
118 opt_plot = true;
119 } else if (std::string(argv[i]) == "--adaptive_gain") {
120 opt_adaptive_gain = true;
121 } else if (std::string(argv[i]) == "--task_sequencing") {
122 opt_task_sequencing = true;
123 } else if (std::string(argv[i]) == "--quad_decimate" && i + 1 < argc) {
124 opt_quad_decimate = std::stoi(argv[i + 1]);
125 } else if (std::string(argv[i]) == "--no-convergence-threshold") {
126 convergence_threshold_t = 0.;
127 convergence_threshold_tu = 0.;
128 } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") {
129 std::cout
130 << argv[0] << " [--ip <default " << opt_robot_ip << ">] [--tag_size <marker size in meter; default "
131 << opt_tagSize << ">] [--eMc <eMc extrinsic file>] "
132 << "[--quad_decimate <decimation; default " << opt_quad_decimate
133 << ">] [--adaptive_gain] [--plot] [--task_sequencing] [--no-convergence-threshold] [--verbose] [--help] [-h]"
134 << "\n";
135 return EXIT_SUCCESS;
136 }
137 }
138
140
141 try {
142 robot.connect(opt_robot_ip);
143
144 std::cout << "WARNING: This example will move the robot! "
145 << "Please make sure to have the user stop button at hand!" << std::endl
146 << "Press Enter to continue..." << std::endl;
147 std::cin.ignore();
148
149 /*
150 * Move to a safe position
151 */
152 vpColVector q(6, 0);
153 q[0] = -vpMath::rad(16);
154 q[1] = -vpMath::rad(120);
155 q[2] = vpMath::rad(120);
156 q[3] = -vpMath::rad(90);
157 q[4] = -vpMath::rad(90);
158 q[5] = 0;
159 std::cout << "Move to joint position: " << q.t() << std::endl;
161 robot.setPosition(vpRobot::JOINT_STATE, q);
162
163 vpRealSense2 rs;
164 rs2::config config;
165 unsigned int width = 640, height = 480;
166 config.enable_stream(RS2_STREAM_COLOR, 640, 480, RS2_FORMAT_RGBA8, 30);
167 config.enable_stream(RS2_STREAM_DEPTH, 640, 480, RS2_FORMAT_Z16, 30);
168 config.enable_stream(RS2_STREAM_INFRARED, 640, 480, RS2_FORMAT_Y8, 30);
169 rs.open(config);
170
171 // Get camera extrinsics
172 vpPoseVector ePc;
173 // Set camera extrinsics default values
174 ePc[0] = -0.0312543;
175 ePc[1] = -0.0584638;
176 ePc[2] = 0.0309834;
177 ePc[3] = -0.00506562;
178 ePc[4] = -0.00293325;
179 ePc[5] = 0.0117901;
180
181 // If provided, read camera extrinsics from --eMc <file>
182 if (!opt_eMc_filename.empty()) {
183 ePc.loadYAML(opt_eMc_filename, ePc);
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
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 to reach
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 cdMc = cdMo * cMo.inverse();
222 t.buildFrom(cdMc);
223 tu.buildFrom(cdMc);
224
227
228 vpServo task;
229 task.addFeature(t, td);
230 task.addFeature(tu, tud);
233
234 if (opt_adaptive_gain) {
235 vpAdaptiveGain lambda(1.5, 0.4, 30); // lambda(0)=4, lambda(oo)=0.4 and lambda'(0)=30
236 task.setLambda(lambda);
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 } else {
307 std::cout << "Desired frame modified to avoid PI rotation of the camera" << std::endl;
308 oMo = v_oMo[1]; // Introduce PI rotation
309 }
310 }
311
312 // Update visual features
313 cdMc = cdMo * oMo * cMo.inverse();
314 t.buildFrom(cdMc);
315 tu.buildFrom(cdMc);
316
317 if (opt_task_sequencing) {
318 if (!servo_started) {
319 if (send_velocities) {
320 servo_started = true;
321 }
322 t_init_servo = vpTime::measureTimeMs();
323 }
324 v_c = task.computeControlLaw((vpTime::measureTimeMs() - t_init_servo) / 1000.);
325 } else {
326 v_c = task.computeControlLaw();
327 }
328
329 // Display desired and current pose features
330 vpDisplay::displayFrame(I, cdMo * oMo, cam, opt_tagSize / 1.5, vpColor::yellow, 2);
331 vpDisplay::displayFrame(I, cMo, cam, opt_tagSize / 2, vpColor::none, 3);
332 // Get tag corners
333 std::vector<vpImagePoint> vip = detector.getPolygon(0);
334 // Get the tag cog corresponding to the projection of the tag frame in the image
335 vip.push_back(detector.getCog(0));
336 // Display the trajectory of the points
337 if (first_time) {
338 traj_vip = new std::vector<vpImagePoint>[vip.size()];
339 }
340 display_point_trajectory(I, vip, traj_vip);
341
342 if (opt_plot) {
343 plotter->plot(0, iter_plot, task.getError());
344 plotter->plot(1, iter_plot, v_c);
345 iter_plot++;
346 }
347
348 if (opt_verbose) {
349 std::cout << "v_c: " << v_c.t() << std::endl;
350 }
351
353 vpThetaUVector cd_tu_c = cdMc.getThetaUVector();
354 double error_tr = sqrt(cd_t_c.sumSquare());
355 double error_tu = vpMath::deg(sqrt(cd_tu_c.sumSquare()));
356
357 ss.str("");
358 ss << "error_t: " << error_tr;
359 vpDisplay::displayText(I, 20, static_cast<int>(I.getWidth()) - 150, ss.str(), vpColor::red);
360 ss.str("");
361 ss << "error_tu: " << error_tu;
362 vpDisplay::displayText(I, 40, static_cast<int>(I.getWidth()) - 150, ss.str(), vpColor::red);
363
364 if (opt_verbose)
365 std::cout << "error translation: " << error_tr << " ; error rotation: " << error_tu << std::endl;
366
367 if (error_tr < convergence_threshold_t && error_tu < convergence_threshold_tu) {
368 has_converged = true;
369 std::cout << "Servo task has converged" << std::endl;
370 ;
371 vpDisplay::displayText(I, 100, 20, "Servo task has converged", vpColor::red);
372 }
373
374 if (first_time) {
375 first_time = false;
376 }
377 } // end if (cMo_vec.size() == 1)
378 else {
379 v_c = 0;
380 }
381
382 if (!send_velocities) {
383 v_c = 0;
384 }
385
386 // Send to the robot
388
389 ss.str("");
390 ss << "Loop time: " << vpTime::measureTimeMs() - t_start << " ms";
391 vpDisplay::displayText(I, 40, 20, ss.str(), vpColor::red);
393
395 if (vpDisplay::getClick(I, button, false)) {
396 switch (button) {
398 send_velocities = !send_velocities;
399 break;
400
402 final_quit = true;
403 v_c = 0;
404 break;
405
406 default:
407 break;
408 }
409 }
410 }
411 std::cout << "Stop the robot " << std::endl;
413
414 if (opt_plot && plotter != nullptr) {
415 delete plotter;
416 plotter = nullptr;
417 }
418
419 if (!final_quit) {
420 while (!final_quit) {
421 rs.acquire(I);
423
424 vpDisplay::displayText(I, 20, 20, "Click to quit the program.", vpColor::red);
425 vpDisplay::displayText(I, 40, 20, "Visual servo converged.", vpColor::red);
426
427 if (vpDisplay::getClick(I, false)) {
428 final_quit = true;
429 }
430
432 }
433 }
434
435 if (traj_vip) {
436 delete[] traj_vip;
437 }
438 } catch (const vpException &e) {
439 std::cout << "ViSP exception: " << e.what() << std::endl;
440 std::cout << "Stop the robot " << std::endl;
442 return EXIT_FAILURE;
443 } catch (const std::exception &e) {
444 std::cout << "ur_rtde exception: " << e.what() << std::endl;
445 return EXIT_FAILURE;
446 }
447
448 return EXIT_SUCCESS;
449}
450#else
451int main()
452{
453#if !defined(VISP_HAVE_REALSENSE2)
454 std::cout << "Install librealsense-2.x" << std::endl;
455#endif
456#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
457 std::cout << "Build ViSP with c++11 or higher compiler flag (cmake -DUSE_CXX_STANDARD=11)." << std::endl;
458#endif
459#if !defined(VISP_HAVE_UR_RTDE)
460 std::cout << "ViSP is not build with libur_rtde 3rd party used to control a robot from Universal Robots..."
461 << std::endl;
462#endif
463 return EXIT_SUCCESS;
464}
465#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.
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).
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 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
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)
Definition of the vpImage class member functions.
Definition vpImage.h:135
unsigned int getWidth() const
Definition vpImage.h:242
static double rad(double deg)
Definition vpMath.h:116
static double deg(double rad)
Definition vpMath.h:106
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)
@ JOINT_STATE
Definition vpRobot.h:78
@ CAMERA_FRAME
Definition vpRobot.h:80
@ STATE_POSITION_CONTROL
Initialize the position controller.
Definition vpRobot.h:65
@ 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.
double sumSquare() const
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
Implementation of a rotation vector as axis-angle minimal representation.
Class that consider the case of a translation vector.
VISP_EXPORT double measureTimeMs()