Visual Servoing Platform version 3.7.0
Loading...
Searching...
No Matches
servoAfma6FourPoints2DCamVelocityLs_cur_integrator.cpp
1/*
2 * ViSP, open source Visual Servoing Platform software.
3 * Copyright (C) 2005 - 2024 by Inria. All rights reserved.
4 *
5 * This software is free software; you can redistribute it and/or modify
6 * it under the terms of the GNU General Public License as published by
7 * the Free Software Foundation; either version 2 of the License, or
8 * (at your option) any later version.
9 * See the file LICENSE.txt at the root directory of this source
10 * distribution for additional information about the GNU GPL.
11 *
12 * For using ViSP with software that can not be combined with the GNU
13 * GPL, please contact Inria about acquiring a ViSP Professional
14 * Edition License.
15 *
16 * See https://visp.inria.fr for more information.
17 *
18 * This software was developed at:
19 * Inria Rennes - Bretagne Atlantique
20 * Campus Universitaire de Beaulieu
21 * 35042 Rennes Cedex
22 * France
23 *
24 * If you have questions regarding the use of this file, please contact
25 * Inria at visp@inria.fr
26 *
27 * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
28 * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
29 *
30 * Description:
31 * tests the control law
32 * eye-in-hand control
33 * velocity computed in the camera frame
34 * compensate target motion by integrator
35 */
36
47
48#include <iostream>
49#include <visp3/core/vpConfig.h>
50
51#if defined(VISP_HAVE_AFMA6) && defined(VISP_HAVE_REALSENSE2) && defined(VISP_HAVE_DISPLAY)
52
53#include <visp3/core/vpImage.h>
54#include <visp3/core/vpIoTools.h>
55#include <visp3/gui/vpDisplayFactory.h>
56#include <visp3/sensor/vpRealSense2.h>
57#include <visp3/blob/vpDot2.h>
58#include <visp3/robot/vpRobotAfma6.h>
59#include <visp3/vision/vpPose.h>
60#include <visp3/visual_features/vpFeatureBuilder.h>
61#include <visp3/visual_features/vpFeaturePoint.h>
62#include <visp3/vs/vpServo.h>
63#include <visp3/vs/vpServoDisplay.h>
64
65// Define the object CAD model
66// Here we consider 4 black blobs whose centers are located on the corners of a square.
67#define L 0.06 // To deal with a 12cm by 12cm square
68
69#ifdef ENABLE_VISP_NAMESPACE
70using namespace VISP_NAMESPACE_NAME;
71#endif
72
86void compute_pose(std::vector<vpPoint> &point, const std::vector<vpDot2> &dot, const vpCameraParameters &cam,
87 vpHomogeneousMatrix &c_M_o, bool init)
88{
89 vpRotationMatrix c_R_o;
90 vpPose pose;
91 vpImagePoint cog;
92
93 for (size_t i = 0; i < point.size(); ++i) {
94 double x = 0, y = 0;
95 cog = dot[i].getCog();
96 vpPixelMeterConversion::convertPoint(cam, cog, x, y); // Pixel to meter conversion
97 point[i].set_x(x); // Perspective projection
98 point[i].set_y(y);
99 pose.addPoint(point[i]);
100 }
101
102 if (init == true) {
104 }
105 else { // init = false; use of the previous pose to initialise VIRTUAL_VS
106 pose.computePose(vpPose::VIRTUAL_VS, c_M_o);
107 }
108}
109
110int main()
111{
112 double opt_mu = 0.02; // Integrator gain
113 double opt_target_tracking_min_error = 0.0001; // Min task error to trigger integrator for target motion compensation
114
115 // Log file creation in /tmp/$USERNAME/log.dat
116 // This file contains by line:
117 // - the 6 computed camera velocities (m/s, rad/s) to achieve the task
118 // - the 6 measured joint velocities (m/s, rad/s)
119 // - the 6 measured joint positions (m, rad)
120 // - the 8 values of s - s*
121 // - the 6 values of the pose c_M_o (tx,ty,tz, rx,ry,rz) with translation
122 // in meters and rotations in radians
123
124 // Get the user login name
125 std::string username = vpIoTools::getUserName();
126
127 // Create a log filename to save velocities...
128 std::string logdirname = "/tmp/" + username;
129
130 // Test if the output path exist. If no try to create it
131 if (vpIoTools::checkDirectory(logdirname) == false) {
132 try {
133 // Create the dirname
134 vpIoTools::makeDirectory(logdirname);
135 }
136 catch (...) {
137 std::cerr << std::endl << "ERROR:" << std::endl;
138 std::cerr << " Cannot create " << logdirname << std::endl;
139 return EXIT_FAILURE;
140 }
141 }
142 std::string logfilename = logdirname + "/log.dat";
143
144 // Open the log file name
145 std::ofstream flog(logfilename.c_str());
146
147 try {
148 vpRealSense2 rs;
149 rs2::config config;
150 unsigned int width = 640, height = 480, fps = 60;
151 config.enable_stream(RS2_STREAM_COLOR, width, height, RS2_FORMAT_RGBA8, fps);
152 config.enable_stream(RS2_STREAM_DEPTH, width, height, RS2_FORMAT_Z16, fps);
153 config.enable_stream(RS2_STREAM_INFRARED, width, height, RS2_FORMAT_Y8, fps);
154 rs.open(config);
155
157
158 // Warm up camera
159 for (size_t i = 0; i < 10; ++i) {
160 rs.acquire(I);
161 }
162
163 std::shared_ptr<vpDisplay> d = vpDisplayFactory::createDisplay(I, 100, 100, "Current image");
164
167
168 std::cout << "-------------------------------------------------------" << std::endl;
169 std::cout << " Test program for vpServo " << std::endl;
170 std::cout << " Eye-in-hand task control, velocity computed in the camera frame" << std::endl;
171 std::cout << " Use of the Afma6 robot " << std::endl;
172 std::cout << " Interaction matrix computed with the current features " << std::endl;
173 std::cout << " task : servo 4 points on a square with dimension " << L << " meters" << std::endl;
174 std::cout << "-------------------------------------------------------" << std::endl;
175
176 std::vector<vpDot2> dot(4);
177
178 std::cout << "Click on the 4 dots clockwise starting from upper/left dot..." << std::endl;
179 for (size_t i = 0; i < dot.size(); ++i) {
180 dot[i].initTracking(I);
181 vpImagePoint cog = dot[i].getCog();
184 }
185
186 vpRobotAfma6 robot;
188
189 // Load the end-effector to camera frame transformation obtained
190 // using a camera intrinsic model with distortion
191 robot.init(vpAfma6::TOOL_INTEL_D435_CAMERA, projModel);
192
193 // Get camera intrinsics
195 robot.getCameraParameters(cam, I);
196
197 // Sets the current position of the visual feature
198 std::vector<vpFeaturePoint> s(4);
199 for (size_t i = 0; i < s.size(); ++i) {
200 vpFeatureBuilder::create(s[i], cam, dot[i]); // retrieve x,y of the vpFeaturePoint structure
201 }
202
203 // Set the position of the square target in a frame which origin is
204 // centered in the middle of the square
205 std::vector<vpPoint> point(4);
206 point[0].setWorldCoordinates(-L, -L, 0);
207 point[1].setWorldCoordinates(+L, -L, 0);
208 point[2].setWorldCoordinates(+L, +L, 0);
209 point[3].setWorldCoordinates(-L, +L, 0);
210
211 // Initialise a desired pose to compute s*, the desired 2D point features
213 vpTranslationVector c_t_o(0, 0, 0.5); // tz = 0.5 meter
214 vpRxyzVector c_r_o(vpMath::rad(0), vpMath::rad(-20), vpMath::rad(0)); // No rotations
215 vpRotationMatrix c_R_o(c_r_o); // Build the rotation matrix
216 c_M_o.buildFrom(c_t_o, c_R_o); // Build the homogeneous matrix
217
218 // Sets the desired position of the 2D visual feature
219 std::vector<vpFeaturePoint> s_d(4);
220 // Compute the desired position of the features from the desired pose
221 for (size_t i = 0; i < s_d.size(); ++i) {
222 vpColVector cP, p;
223 point[i].changeFrame(c_M_o, cP);
224 point[i].projection(cP, p);
225
226 s_d[i].set_x(p[0]);
227 s_d[i].set_y(p[1]);
228 s_d[i].set_Z(cP[2]);
229 }
230
231 // Define the task
232 // - we want an eye-in-hand control law
233 // - robot is controlled in the camera frame
234 // - Interaction matrix is computed with the current visual features
237 task.setInteractionMatrixType(vpServo::CURRENT, vpServo::PSEUDO_INVERSE);
238
239 // We want to see a point on a point
240 for (size_t i = 0; i < s.size(); ++i) {
241 task.addFeature(s[i], s_d[i]);
242 }
243
244 // - set the task adaptive gain
245 vpAdaptiveGain lambda_adaptive;
246 lambda_adaptive.initStandard(1.7, 0.3, 1.5); // lambda(0)=4, lambda(oo)=0.4 and lambda'(0)=30
247 task.setLambda(lambda_adaptive);
248
249 // Display task information
250 task.print();
251
252 // Initialise the velocity control of the robot
253 robot.setRobotState(vpRobot::STATE_VELOCITY_CONTROL);
254
255 std::cout << "\nHit CTRL-C to stop the loop...\n" << std::flush;
256
257 bool init_pose_from_linear_method = true;
258 bool start_integrator = false;
259 double norm_error = 1.;
260 vpColVector sum_dedt(task.getDimension());
261
262 bool quit = false;
263 while (!quit) {
264 // Acquire a new image from the camera
265 rs.acquire(I);
266
267 // Display this image
269
270 // For each point...
271 for (size_t i = 0; i < dot.size(); ++i) {
272 // Achieve the tracking of the dot in the image
273 dot[i].track(I);
274 }
275
276 // At first iteration, we initialise non linear pose estimation with a linear approach.
277 // For the other iterations, non linear pose estimation is initialized with the pose estimated at previous iteration of the loop
278 compute_pose(point, dot, cam, c_M_o, init_pose_from_linear_method);
279 if (init_pose_from_linear_method) {
280 init_pose_from_linear_method = false;
281 }
282
283 for (size_t i = 0; i < dot.size(); ++i) {
284 // Update the point feature from the dot location
285 vpFeatureBuilder::create(s[i], cam, dot[i]);
286 // Set the feature Z coordinate from the pose
287 vpColVector cP;
288 point[i].changeFrame(c_M_o, cP);
289
290 s[i].set_Z(cP[2]);
291 }
292
293 // Compute the visual servoing skew vector
294 vpColVector v = task.computeControlLaw();
295
296 // Get task error
297 norm_error = task.getError().sumSquare();
298 if (norm_error < opt_target_tracking_min_error) {
299 start_integrator = true;
300 }
301
302 if (start_integrator) {
303 sum_dedt += task.getError();
304 vpMatrix J1p = task.getTaskJacobianPseudoInverse();
305 v -= opt_mu * J1p * sum_dedt;
306 }
307 // Display the current and desired feature points in the image display
308 vpServoDisplay::display(task, cam, I);
309
310 // Apply the computed camera velocities to the robot
311 robot.setVelocity(vpRobot::CAMERA_FRAME, v);
312
313 // Save velocities applied to the robot in the log file
314 // v[0], v[1], v[2] correspond to camera translation velocities in m/s
315 // v[3], v[4], v[5] correspond to camera rotation velocities in rad/s
316 flog << v[0] << " " << v[1] << " " << v[2] << " " << v[3] << " " << v[4] << " " << v[5] << " ";
317
318 // Get the measured joint velocities of the robot
319 vpColVector qvel;
320 robot.getVelocity(vpRobot::ARTICULAR_FRAME, qvel);
321 // Save measured joint velocities of the robot in the log file:
322 // - qvel[0], qvel[1], qvel[2] correspond to measured joint translation
323 // velocities in m/s
324 // - qvel[3], qvel[4], qvel[5] correspond to measured joint rotation
325 // velocities in rad/s
326 flog << qvel[0] << " " << qvel[1] << " " << qvel[2] << " " << qvel[3] << " " << qvel[4] << " " << qvel[5] << " ";
327
328 // Get the measured joint positions of the robot
329 vpColVector q;
330 robot.getPosition(vpRobot::ARTICULAR_FRAME, q);
331 // Save measured joint positions of the robot in the log file
332 // - q[0], q[1], q[2] correspond to measured joint translation
333 // positions in m
334 // - q[3], q[4], q[5] correspond to measured joint rotation
335 // positions in rad
336 flog << q[0] << " " << q[1] << " " << q[2] << " " << q[3] << " " << q[4] << " " << q[5] << " ";
337
338 // Save feature error (s-s*) for the 4 feature points. For each feature
339 // point, we have 2 errors (along x and y axis). This error is
340 // expressed in meters in the camera frame
341 flog << (task.getError()).t() << " "; // s-s* for points
342
343 // Save the current c_M_o pose: translations in meters, rotations (rx, ry,
344 // rz) in radians
345 flog << c_t_o[0] << " " << c_t_o[1] << " " << c_t_o[2] << " " // translation
346 << c_r_o[0] << " " << c_r_o[1] << " " << c_r_o[2] << std::endl; // rotation
347
348 vpDisplay::displayText(I, 20, 20, "Click to quit...", vpColor::red);
349 if (start_integrator) {
350 vpDisplay::displayText(I, 35, 20, "Integrator enabled", vpColor::red);
351 }
352 if (vpDisplay::getClick(I, false)) {
353 quit = true;
354 }
355
356 // Flush the display
358 }
359
360 // Close the log file
361 flog.close();
362
363 // Display task information
364 task.print();
365
366 return EXIT_SUCCESS;
367 }
368 catch (const vpException &e) {
369 // Close the log file
370 flog.close();
371
372 std::cout << "Visual servo failed with exception: " << e << std::endl;
373 return EXIT_FAILURE;
374 }
375}
376
377#else
378int main()
379{
380 std::cout << "You do not have an afma6 robot connected to your computer..." << std::endl;
381 return EXIT_SUCCESS;
382}
383
384#endif
Adaptive gain computation.
void initStandard(double gain_at_zero, double gain_at_infinity, double slope_at_zero)
@ TOOL_INTEL_D435_CAMERA
Definition vpAfma6.h:129
Generic class defining intrinsic camera parameters.
@ perspectiveProjWithDistortion
Perspective projection with distortion model.
Implementation of column vector and the associated operations.
vpRowVector t() const
static const vpColor red
Definition vpColor.h:198
static const vpColor blue
Definition vpColor.h:204
static bool getClick(const vpImage< unsigned char > &I, bool blocking=true)
static void display(const vpImage< unsigned char > &I)
static void displayCross(const vpImage< unsigned char > &I, const vpImagePoint &ip, unsigned int size, const vpColor &color, unsigned int thickness=1)
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:60
static void create(vpFeaturePoint &s, const vpCameraParameters &cam, const vpDot &d)
Implementation of an homogeneous matrix and operations on such kind of matrices.
vpHomogeneousMatrix & buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
Class that defines a 2D point in an image. This class is useful for image processing and stores only ...
Definition of the vpImage class member functions.
Definition vpImage.h:131
static bool checkDirectory(const std::string &dirname)
static std::string getUserName()
static void makeDirectory(const std::string &dirname)
static double rad(double deg)
Definition vpMath.h:129
Implementation of a matrix and operations on matrices.
Definition vpMatrix.h:175
static void convertPoint(const vpCameraParameters &cam, const double &u, const double &v, double &x, double &y)
Class used for pose computation from N points (pose from point only). Some of the algorithms implemen...
Definition vpPose.h:82
void addPoint(const vpPoint &P)
Definition vpPose.cpp:96
@ DEMENTHON_LAGRANGE_VIRTUAL_VS
Definition vpPose.h:103
@ VIRTUAL_VS
Definition vpPose.h:97
bool computePose(vpPoseMethodType method, vpHomogeneousMatrix &cMo, FuncCheckValidityPose func=nullptr)
Definition vpPose.cpp:385
void acquire(vpImage< unsigned char > &grey, double *ts=nullptr)
bool open(const rs2::config &cfg=rs2::config())
Control of Irisa's gantry robot named Afma6.
@ ARTICULAR_FRAME
Definition vpRobot.h:77
@ CAMERA_FRAME
Definition vpRobot.h:81
@ STATE_VELOCITY_CONTROL
Initialize the velocity controller.
Definition vpRobot.h:64
Implementation of a rotation matrix and operations on such kind of matrices.
Implementation of a rotation vector as Euler angle minimal representation.
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)
@ EYEINHAND_CAMERA
Definition vpServo.h:176
@ PSEUDO_INVERSE
Definition vpServo.h:250
@ CURRENT
Definition vpServo.h:217
Class that consider the case of a translation vector.
std::shared_ptr< vpDisplay > createDisplay()
Return a smart pointer vpDisplay specialization if a GUI library is available or nullptr otherwise.