Visual Servoing Platform version 3.6.0
Loading...
Searching...
No Matches
servoUniversalRobotsIBVS.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*****************************************************************************/
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/vpRobotUniversalRobots.h>
68#include <visp3/sensor/vpRealSense2.h>
69#include <visp3/visual_features/vpFeatureBuilder.h>
70#include <visp3/visual_features/vpFeaturePoint.h>
71#include <visp3/vs/vpServo.h>
72#include <visp3/vs/vpServoDisplay.h>
73
74#if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && \
75 (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && defined(VISP_HAVE_UR_RTDE)
76
77void display_point_trajectory(const vpImage<unsigned char> &I, const std::vector<vpImagePoint> &vip,
78 std::vector<vpImagePoint> *traj_vip)
79{
80 for (size_t i = 0; i < vip.size(); i++) {
81 if (traj_vip[i].size()) {
82 // Add the point only if distance with the previous > 1 pixel
83 if (vpImagePoint::distance(vip[i], traj_vip[i].back()) > 1.) {
84 traj_vip[i].push_back(vip[i]);
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
97int main(int argc, char **argv)
98{
99 double opt_tagSize = 0.120;
100 std::string opt_robot_ip = "192.168.0.100";
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 = 0.00005;
109
110 for (int i = 1; i < argc; i++) {
111 if (std::string(argv[i]) == "--tag_size" && i + 1 < argc) {
112 opt_tagSize = std::stod(argv[i + 1]);
113 } else if (std::string(argv[i]) == "--ip" && i + 1 < argc) {
114 opt_robot_ip = std::string(argv[i + 1]);
115 } else if (std::string(argv[i]) == "--eMc" && i + 1 < argc) {
116 opt_eMc_filename = std::string(argv[i + 1]);
117 } else if (std::string(argv[i]) == "--verbose") {
118 opt_verbose = true;
119 } else if (std::string(argv[i]) == "--plot") {
120 opt_plot = true;
121 } else if (std::string(argv[i]) == "--adaptive_gain") {
122 opt_adaptive_gain = true;
123 } else if (std::string(argv[i]) == "--task_sequencing") {
124 opt_task_sequencing = true;
125 } else if (std::string(argv[i]) == "--quad_decimate" && i + 1 < argc) {
126 opt_quad_decimate = std::stoi(argv[i + 1]);
127 } else if (std::string(argv[i]) == "--no-convergence-threshold") {
128 convergence_threshold = 0.;
129 } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") {
130 std::cout
131 << argv[0] << " [--ip <default " << opt_robot_ip << ">] [--tag_size <marker size in meter; default "
132 << opt_tagSize << ">] [--eMc <eMc extrinsic file>] "
133 << "[--quad_decimate <decimation; default " << opt_quad_decimate
134 << ">] [--adaptive_gain] [--plot] [--task_sequencing] [--no-convergence-threshold] [--verbose] [--help] [-h]"
135 << "\n";
136 return EXIT_SUCCESS;
137 }
138 }
139
141
142 try {
143 robot.connect(opt_robot_ip);
144
145 std::cout << "WARNING: This example will move the robot! "
146 << "Please make sure to have the user stop button at hand!" << std::endl
147 << "Press Enter to continue..." << std::endl;
148 std::cin.ignore();
149
150 /*
151 * Move to a safe position
152 */
153 vpColVector q(6, 0);
154 q[0] = -vpMath::rad(16);
155 q[1] = -vpMath::rad(120);
156 q[2] = vpMath::rad(120);
157 q[3] = -vpMath::rad(90);
158 q[4] = -vpMath::rad(90);
159 q[5] = 0;
160 std::cout << "Move to joint position: " << q.t() << std::endl;
162 robot.setPosition(vpRobot::JOINT_STATE, q);
163
164 vpRealSense2 rs;
165 rs2::config config;
166 unsigned int width = 640, height = 480;
167 config.enable_stream(RS2_STREAM_COLOR, 640, 480, RS2_FORMAT_RGBA8, 30);
168 config.enable_stream(RS2_STREAM_DEPTH, 640, 480, RS2_FORMAT_Z16, 30);
169 config.enable_stream(RS2_STREAM_INFRARED, 640, 480, RS2_FORMAT_Y8, 30);
170 rs.open(config);
171
172 // Get camera extrinsics
173 vpPoseVector ePc;
174 // Set camera extrinsics default values
175 ePc[0] = -0.0312543;
176 ePc[1] = -0.0584638;
177 ePc[2] = 0.0309834;
178 ePc[3] = -0.00506562;
179 ePc[4] = -0.00293325;
180 ePc[5] = 0.0117901;
181
182 // If provided, read camera extrinsics from --eMc <file>
183 if (!opt_eMc_filename.empty()) {
184 ePc.loadYAML(opt_eMc_filename, ePc);
185 } else {
186 std::cout << "Warning, opt_eMc_filename is empty! Use hard coded values."
187 << "\n";
188 }
189 vpHomogeneousMatrix eMc(ePc);
190 std::cout << "eMc:\n" << eMc << "\n";
191
192 // Get camera intrinsics
195 std::cout << "cam:\n" << cam << "\n";
196
197 vpImage<unsigned char> I(height, width);
198
199#if defined(VISP_HAVE_X11)
200 vpDisplayX dc(I, 10, 10, "Color image");
201#elif defined(VISP_HAVE_GDI)
202 vpDisplayGDI dc(I, 10, 10, "Color image");
203#endif
204
207 // vpDetectorAprilTag::vpPoseEstimationMethod poseEstimationMethod = vpDetectorAprilTag::BEST_RESIDUAL_VIRTUAL_VS;
208 vpDetectorAprilTag detector(tagFamily);
209 detector.setAprilTagPoseEstimationMethod(poseEstimationMethod);
210 detector.setDisplayTag(display_tag);
211 detector.setAprilTagQuadDecimate(opt_quad_decimate);
212
213 // Servo
214 vpHomogeneousMatrix cdMc, cMo, oMo;
215
216 // Desired pose used to compute the desired features
217 vpHomogeneousMatrix cdMo(vpTranslationVector(0, 0, opt_tagSize * 3), // 3 times tag with along camera z axis
218 vpRotationMatrix({1, 0, 0, 0, -1, 0, 0, 0, -1}));
219
220 // Create visual features
221 std::vector<vpFeaturePoint> p(4), pd(4); // We use 4 points
222
223 // Define 4 3D points corresponding to the CAD model of the Apriltag
224 std::vector<vpPoint> point(4);
225 point[0].setWorldCoordinates(-opt_tagSize / 2., -opt_tagSize / 2., 0);
226 point[1].setWorldCoordinates(opt_tagSize / 2., -opt_tagSize / 2., 0);
227 point[2].setWorldCoordinates(opt_tagSize / 2., opt_tagSize / 2., 0);
228 point[3].setWorldCoordinates(-opt_tagSize / 2., opt_tagSize / 2., 0);
229
230 vpServo task;
231 // Add the 4 visual feature points
232 for (size_t i = 0; i < p.size(); i++) {
233 task.addFeature(p[i], pd[i]);
234 }
237
238 if (opt_adaptive_gain) {
239 vpAdaptiveGain lambda(1.5, 0.4, 30); // lambda(0)=4, lambda(oo)=0.4 and lambda'(0)=30
240 task.setLambda(lambda);
241 } else {
242 task.setLambda(0.5);
243 }
244
245 vpPlot *plotter = nullptr;
246 int iter_plot = 0;
247
248 if (opt_plot) {
249 plotter = new vpPlot(2, static_cast<int>(250 * 2), 500, static_cast<int>(I.getWidth()) + 80, 10,
250 "Real time curves plotter");
251 plotter->setTitle(0, "Visual features error");
252 plotter->setTitle(1, "Camera velocities");
253 plotter->initGraph(0, 8);
254 plotter->initGraph(1, 6);
255 plotter->setLegend(0, 0, "error_feat_p1_x");
256 plotter->setLegend(0, 1, "error_feat_p1_y");
257 plotter->setLegend(0, 2, "error_feat_p2_x");
258 plotter->setLegend(0, 3, "error_feat_p2_y");
259 plotter->setLegend(0, 4, "error_feat_p3_x");
260 plotter->setLegend(0, 5, "error_feat_p3_y");
261 plotter->setLegend(0, 6, "error_feat_p4_x");
262 plotter->setLegend(0, 7, "error_feat_p4_y");
263 plotter->setLegend(1, 0, "vc_x");
264 plotter->setLegend(1, 1, "vc_y");
265 plotter->setLegend(1, 2, "vc_z");
266 plotter->setLegend(1, 3, "wc_x");
267 plotter->setLegend(1, 4, "wc_y");
268 plotter->setLegend(1, 5, "wc_z");
269 }
270
271 bool final_quit = false;
272 bool has_converged = false;
273 bool send_velocities = false;
274 bool servo_started = false;
275 std::vector<vpImagePoint> *traj_corners = nullptr; // To memorize point trajectory
276
277 static double t_init_servo = vpTime::measureTimeMs();
278
279 robot.set_eMc(eMc); // Set location of the camera wrt end-effector frame
281
282 while (!has_converged && !final_quit) {
283 double t_start = vpTime::measureTimeMs();
284
285 rs.acquire(I);
286
288
289 std::vector<vpHomogeneousMatrix> cMo_vec;
290 detector.detect(I, opt_tagSize, cam, cMo_vec);
291
292 {
293 std::stringstream ss;
294 ss << "Left click to " << (send_velocities ? "stop the robot" : "servo the robot") << ", right click to quit.";
295 vpDisplay::displayText(I, 20, 20, ss.str(), vpColor::red);
296 }
297
298 vpColVector v_c(6);
299
300 // Only one tag is detected
301 if (cMo_vec.size() == 1) {
302 cMo = cMo_vec[0];
303
304 static bool first_time = true;
305 if (first_time) {
306 // Introduce security wrt tag positioning in order to avoid PI rotation
307 std::vector<vpHomogeneousMatrix> v_oMo(2), v_cdMc(2);
308 v_oMo[1].buildFrom(0, 0, 0, 0, 0, M_PI);
309 for (size_t i = 0; i < 2; i++) {
310 v_cdMc[i] = cdMo * v_oMo[i] * cMo.inverse();
311 }
312 if (std::fabs(v_cdMc[0].getThetaUVector().getTheta()) < std::fabs(v_cdMc[1].getThetaUVector().getTheta())) {
313 oMo = v_oMo[0];
314 } else {
315 std::cout << "Desired frame modified to avoid PI rotation of the camera" << std::endl;
316 oMo = v_oMo[1]; // Introduce PI rotation
317 }
318
319 // Compute the desired position of the features from the desired pose
320 for (size_t i = 0; i < point.size(); i++) {
321 vpColVector cP, p_;
322 point[i].changeFrame(cdMo * oMo, cP);
323 point[i].projection(cP, p_);
324
325 pd[i].set_x(p_[0]);
326 pd[i].set_y(p_[1]);
327 pd[i].set_Z(cP[2]);
328 }
329 }
330
331 // Get tag corners
332 std::vector<vpImagePoint> corners = detector.getPolygon(0);
333
334 // Update visual features
335 for (size_t i = 0; i < corners.size(); i++) {
336 // Update the point feature from the tag corners location
337 vpFeatureBuilder::create(p[i], cam, corners[i]);
338 // Set the feature Z coordinate from the pose
339 vpColVector cP;
340 point[i].changeFrame(cMo, cP);
341
342 p[i].set_Z(cP[2]);
343 }
344
345 if (opt_task_sequencing) {
346 if (!servo_started) {
347 if (send_velocities) {
348 servo_started = true;
349 }
350 t_init_servo = vpTime::measureTimeMs();
351 }
352 v_c = task.computeControlLaw((vpTime::measureTimeMs() - t_init_servo) / 1000.);
353 } else {
354 v_c = task.computeControlLaw();
355 }
356
357 // Display the current and desired feature points in the image display
358 vpServoDisplay::display(task, cam, I);
359 for (size_t i = 0; i < corners.size(); i++) {
360 std::stringstream ss;
361 ss << i;
362 // Display current point indexes
363 vpDisplay::displayText(I, corners[i] + vpImagePoint(15, 15), ss.str(), vpColor::red);
364 // Display desired point indexes
365 vpImagePoint ip;
366 vpMeterPixelConversion::convertPoint(cam, pd[i].get_x(), pd[i].get_y(), ip);
367 vpDisplay::displayText(I, ip + vpImagePoint(15, 15), ss.str(), vpColor::red);
368 }
369 if (first_time) {
370 traj_corners = new std::vector<vpImagePoint>[corners.size()];
371 }
372 // Display the trajectory of the points used as features
373 display_point_trajectory(I, corners, traj_corners);
374
375 if (opt_plot) {
376 plotter->plot(0, iter_plot, task.getError());
377 plotter->plot(1, iter_plot, v_c);
378 iter_plot++;
379 }
380
381 if (opt_verbose) {
382 std::cout << "v_c: " << v_c.t() << std::endl;
383 }
384
385 double error = task.getError().sumSquare();
386 std::stringstream ss;
387 ss << "error: " << error;
388 vpDisplay::displayText(I, 20, static_cast<int>(I.getWidth()) - 150, ss.str(), vpColor::red);
389
390 if (opt_verbose)
391 std::cout << "error: " << error << std::endl;
392
393 if (error < convergence_threshold) {
394 has_converged = true;
395 std::cout << "Servo task has converged"
396 << "\n";
397 vpDisplay::displayText(I, 100, 20, "Servo task has converged", vpColor::red);
398 }
399 if (first_time) {
400 first_time = false;
401 }
402 } // end if (cMo_vec.size() == 1)
403 else {
404 v_c = 0;
405 }
406
407 if (!send_velocities) {
408 v_c = 0;
409 }
410
411 // Send to the robot
413
414 {
415 std::stringstream ss;
416 ss << "Loop time: " << vpTime::measureTimeMs() - t_start << " ms";
417 vpDisplay::displayText(I, 40, 20, ss.str(), vpColor::red);
418 }
420
422 if (vpDisplay::getClick(I, button, false)) {
423 switch (button) {
425 send_velocities = !send_velocities;
426 break;
427
429 final_quit = true;
430 v_c = 0;
431 break;
432
433 default:
434 break;
435 }
436 }
437 }
438 std::cout << "Stop the robot " << std::endl;
440
441 if (opt_plot && plotter != nullptr) {
442 delete plotter;
443 plotter = nullptr;
444 }
445
446 if (!final_quit) {
447 while (!final_quit) {
448 rs.acquire(I);
450
451 vpDisplay::displayText(I, 20, 20, "Click to quit the program.", vpColor::red);
452 vpDisplay::displayText(I, 40, 20, "Visual servo converged.", vpColor::red);
453
454 if (vpDisplay::getClick(I, false)) {
455 final_quit = true;
456 }
457
459 }
460 }
461 if (traj_corners) {
462 delete[] traj_corners;
463 }
464 } catch (const vpException &e) {
465 std::cout << "ViSP exception: " << e.what() << std::endl;
466 std::cout << "Stop the robot " << std::endl;
468 return EXIT_FAILURE;
469 } catch (const std::exception &e) {
470 std::cout << "ur_rtde exception: " << e.what() << std::endl;
471 return EXIT_FAILURE;
472 }
473
474 return EXIT_SUCCESS;
475}
476#else
477int main()
478{
479#if !defined(VISP_HAVE_REALSENSE2)
480 std::cout << "Install librealsense-2.x" << std::endl;
481#endif
482#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
483 std::cout << "Build ViSP with c++11 or higher compiler flag (cmake -DUSE_CXX_STANDARD=11)." << std::endl;
484#endif
485#if !defined(VISP_HAVE_UR_RTDE)
486 std::cout << "ViSP is not build with libur_rtde 3rd party used to control a robot from Universal Robots..."
487 << std::endl;
488#endif
489 return EXIT_SUCCESS;
490}
491#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 double rad(double deg)
Definition vpMath.h:116
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)
@ 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.
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()