Visual Servoing Platform version 3.7.0
Loading...
Searching...
No Matches
servoPololuPtuPoint2DJointVelocity.cpp
1/*
2 * ViSP, open source Visual Servoing Platform software.
3 * Copyright (C) 2005 - 2025 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 joint
34 */
35
45
46#include <iostream>
47
48#include <visp3/core/vpConfig.h>
49
50#if defined(VISP_HAVE_POLOLU) && defined(VISP_HAVE_APRILTAG) && defined(VISP_HAVE_REALSENSE2)
51
52#include <visp3/core/vpDisplay.h>
53#include <visp3/core/vpException.h>
54#include <visp3/core/vpHomogeneousMatrix.h>
55#include <visp3/core/vpImage.h>
56#include <visp3/core/vpTime.h>
57#include <visp3/detection/vpDetectorAprilTag.h>
58#include <visp3/gui/vpDisplayFactory.h>
59#include <visp3/robot/vpRobotPololuPtu.h>
60#include <visp3/sensor/vpRealSense2.h>
61#include <visp3/visual_features/vpFeatureBuilder.h>
62#include <visp3/visual_features/vpFeaturePoint.h>
63#include <visp3/vs/vpServo.h>
64#include <visp3/vs/vpAdaptiveGain.h>
65#include <visp3/vs/vpServoDisplay.h>
66
67void usage(const char **argv, int error, const std::string &device, int baudrate)
68{
69 std::cout << "Name" << std::endl
70 << " Example of eye-in-hand control law. We control here a real robot, a pan-tilt unit" << std::endl
71 << " controlled using a Pololu Maestro board equipped.The PTU is equipped with a Realsense" << std::endl
72 << " camera mounted on its end-effector.The velocity to apply to the PT head is a joint" << std::endl
73 << " velocity.The visual feature is a point corresponding to the center of gravity" << std::endl
74 << " of an AprilTag." << std::endl
75 << std::endl;
76 std::cout << "Synopsis" << std::endl
77 << " " << argv[0] << " [--device <name>] [--baud <rate>] [--verbose, -v] [--help, -h]" << std::endl
78 << std::endl;
79 std::cout << "Description" << std::endl
80 << " --device <name> Device name." << std::endl
81 << " Default: " << device << std::endl
82 << std::endl
83 << " --baud <rate> Serial link baud rate." << std::endl
84 << " Default: " << baudrate << std::endl
85 << std::endl
86 << " --verbose, -v Enable verbosity." << std::endl
87 << std::endl
88 << " --help, -h Print this helper message." << std::endl
89 << std::endl;
90 if (error) {
91 std::cout << "Error" << std::endl
92 << " "
93 << "Unsupported parameter " << argv[error] << std::endl;
94 }
95}
96
97int main(int argc, const char **argv)
98{
99#ifdef ENABLE_VISP_NAMESPACE
100 using namespace VISP_NAMESPACE_NAME;
101#endif
102
103#ifdef _WIN32
104 std::string opt_device = "COM4";
105#else
106 std::string opt_device = "/dev/ttyACM0";
107 // Example for Mac OS, the Maestro creates two devices, use the one with the lowest number (the command port)
108 //std::string opt_device = "/dev/cu.usbmodem00031501";
109#endif
110 int opt_baudrate = 38400;
111 bool opt_verbose = false;
112
113 for (int i = 1; i < argc; i++) {
114 if (std::string(argv[i]) == "--device" && i + 1 < argc) {
115 opt_device = std::string(argv[i + 1]);
116 i++;
117 }
118 else if (std::string(argv[i]) == "--verbose" || std::string(argv[i]) == "-v") {
119 opt_verbose = true;
120 }
121 else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") {
122 usage(argv, 0, opt_device, opt_baudrate);
123 return EXIT_SUCCESS;
124 }
125 else {
126 usage(argv, i, opt_device, opt_baudrate);
127 return EXIT_FAILURE;
128 }
129 }
130
131#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
132 std::shared_ptr<vpDisplay> display;
133#else
134 vpDisplay *display = nullptr;
135#endif
136 try {
137 // Creating the servo object on channel 0
138 vpRobotPololuPtu robot(opt_device, opt_baudrate, opt_verbose);
139
140 /*
141 * Pololu PTU has the following axis orientation (rear view)
142 *
143 * tilt + <---- (end-effector-frame)
144 * |
145 * \/ pan +
146 *
147 * The PTU end-effector-frame is the following (rear view)
148 *
149 * /\ x
150 * |
151 * (e) ----> y
152 *
153 * The camera frame attached to the PT unit is the following (rear view)
154 *
155 * (c) ----> x
156 * |
157 * \/ y
158 *
159 * The corresponding cRe (camera to end-effector rotation matrix) is then the following
160 *
161 * ( 0 1 0)
162 * cRe = (-1 0 0)
163 * ( 0 0 1)
164 *
165 * Translation cte (camera to end-effector) can be neglected
166 *
167 * (0)
168 * cte = (0)
169 * (0)
170 */
171
172 vpRotationMatrix cRe({ 0, 1, 0, -1, 0, 0, 0, 0, 1 });
173 vpTranslationVector cte; // By default set to 0
174
175 // Robot Jacobian (expressed in the end-effector frame)
176 vpMatrix eJe;
177 // Camera to end-effector frame transformation
178 vpHomogeneousMatrix cMe(cte, cRe);
179 // Velocity twist transformation to express a velocity from end-effector to camera frame
180 vpVelocityTwistMatrix cVe(cMe);
181
182 vpColVector q(robot.getNDof());
183 q = 0;
184 std::cout << "Move PT to initial position: " << q.t() << std::endl;
185 robot.setRobotState(vpRobot::STATE_POSITION_CONTROL);
186 robot.setPositioningVelocityPercentage(10.f);
187 robot.setPosition(vpRobot::JOINT_STATE, q);
188
189 vpTime::wait(1500); // TODO make setPosition() blocking
190
191 std::cout << "Min velocity resolution: " << vpMath::deg(robot.getAngularVelocityResolution()) << " deg/s" << std::endl;
192
193 // Initialize grabber
194 vpRealSense2 g;
195 rs2::config config;
196 config.disable_stream(RS2_STREAM_DEPTH);
197 config.disable_stream(RS2_STREAM_INFRARED);
198 config.enable_stream(RS2_STREAM_COLOR, 640, 480, RS2_FORMAT_RGBA8, 30);
199 g.open(config);
200
201 std::cout << "Read camera parameters from Realsense device" << std::endl;
204
206 g.acquire(I);
207
208 // We open a window
209 // Its size is automatically defined by the image (I) size
210#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
211 display = vpDisplayFactory::createDisplay(I, 100, 100, "Display");
212#else
213 display = vpDisplayFactory::allocateDisplay(I, 100, 100, "Display");
214#endif
215
218
219 vpDetectorAprilTag detector;
220
222
223 // Create current and desired point visual feature
224 vpFeaturePoint p, pd;
225 // Sets the desired position of the visual feature
226 // Here we set Z desired to 1 meter, and (x,y)=(0,0) to center the tag in the image
227 pd.buildFrom(0, 0, 1);
228
229 // Define the task
230 // - we want an eye-in-hand control law
231 // - joint velocities are computed
232 // - interaction matrix is the one at desired position
234 task.setInteractionMatrixType(vpServo::DESIRED, vpServo::PSEUDO_INVERSE);
235 task.set_cVe(cVe);
236 // We want to see a point on a point
237 task.addFeature(p, pd);
238 // Set the gain
239 //task.setLambda(2.0);
240 //vpAdaptiveGain lambda(2, 0.7, 30);
241 vpAdaptiveGain lambda(3.5, 2, 50);
242 task.setLambda(lambda);
243
244 robot.setRobotState(vpRobot::STATE_VELOCITY_CONTROL);
245
246 // {
247 // vpColVector ve(6);
248 // ve = 0;
249 // ve[5] = vpMath::rad(5);
250 // double t_start = vpTime::measureTimeMs();
251 // while (vpTime::measureTimeMs() - t_start < 3000) {
252 // robot.get_eJe(eJe);
253 // vpColVector q_dot = (cVe * eJe).pseudoInverse() * ve;
254 // robot.setVelocity(vpRobot::JOINT_STATE, q_dot);
255 // vpTime::wait(40);
256 // }
257
258 // return EXIT_SUCCESS;
259 // }
260
261
262 bool quit = false;
263 bool send_velocities = false;
264 vpColVector q_dot(robot.getNDof());
265 double min_pix_error = 10; // In pixels
266 double min_error = vpMath::sqr(min_pix_error / cam.get_px());
267
268 while (!quit) {
269 g.acquire(I);
271
272 {
273 std::stringstream ss;
274 ss << "Left click to " << (send_velocities ? "stop the robot" : "servo the robot") << ", right click to quit.";
275 vpDisplay::displayText(I, 20, 20, ss.str(), vpColor::red);
276 }
277
278 if (detector.detect(I)) {
279 // We consider the first tag only
280 vpImagePoint cog = detector.getCog(0); // 0 is the id of the first tag
281
282 vpFeatureBuilder::create(p, cam, cog);
283
284 // Get the jacobian
285 robot.get_eJe(eJe);
286 task.set_eJe(eJe);
287
288 q_dot = task.computeControlLaw();
289
290 vpServoDisplay::display(task, cam, I);
292
293 double error = (task.getError()).sumSquare();
294 if (opt_verbose) {
295 std::cout << "|| s - s* || = " << error << std::endl;
296 }
297 if (error < min_error) {
298 if (opt_verbose) {
299 std::cout << "Stop the robot" << std::endl;
300 }
301 q_dot = 0;
302 }
303 }
304 else {
305 q_dot = 0;
306 }
307 if (!send_velocities) {
308 q_dot = 0;
309 }
310
311 robot.setVelocity(vpRobot::JOINT_STATE, q_dot);
312
314
316 if (vpDisplay::getClick(I, button, false)) {
317 switch (button) {
319 send_velocities = !send_velocities;
320 break;
321
323 quit = true;
324 q_dot = 0;
325 break;
326
327 default:
328 break;
329 }
330 }
331 }
332
333 std::cout << "Stop the robot " << std::endl;
334 robot.setRobotState(vpRobot::STATE_STOP);
335
336#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
337 if (display != nullptr) {
338 delete display;
339 }
340#endif
341 return EXIT_SUCCESS;
342 }
343 catch (const vpException &e) {
344 std::cout << "Catch an exception: " << e.getMessage() << std::endl;
345#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
346 if (display != nullptr) {
347 delete display;
348 }
349#endif
350 return EXIT_FAILURE;
351 }
352}
353
354#else
355int main()
356{
357 std::cout << "You do not have a Pololu PTU connected to your computer..." << std::endl;
358 return EXIT_SUCCESS;
359}
360#endif
Adaptive gain computation.
Generic class defining intrinsic camera parameters.
@ perspectiveProjWithoutDistortion
Perspective projection without distortion model.
Implementation of column vector and the associated operations.
static const vpColor red
Definition vpColor.h:198
bool detect(const vpImage< unsigned char > &I) VP_OVERRIDE
vpImagePoint getCog(size_t i) const
Class that defines generic functionalities for display.
Definition vpDisplay.h:171
static bool getClick(const vpImage< unsigned char > &I, bool blocking=true)
static void display(const vpImage< unsigned char > &I)
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)
Class that defines a 2D point visual feature which is composed by two parameters that are the cartes...
vpFeaturePoint & buildFrom(const double &x, const double &y, const double &Z)
Implementation of an homogeneous matrix and operations on such kind of matrices.
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 double sqr(double x)
Definition vpMath.h:203
static double deg(double rad)
Definition vpMath.h:119
Implementation of a matrix and operations on matrices.
Definition vpMatrix.h:175
vpCameraParameters getCameraParameters(const rs2_stream &stream, vpCameraParameters::vpCameraParametersProjType type=vpCameraParameters::perspectiveProjWithDistortion, int index=-1) const
void acquire(vpImage< unsigned char > &grey, double *ts=nullptr)
bool open(const rs2::config &cfg=rs2::config())
Interface for the Pololu Maestro pan-tilt unit using two servo motors.
@ JOINT_STATE
Definition vpRobot.h:79
@ 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
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)
@ EYEINHAND_L_cVe_eJe
Definition vpServo.h:183
@ PSEUDO_INVERSE
Definition vpServo.h:250
@ DESIRED
Definition vpServo.h:223
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.
vpDisplay * allocateDisplay()
Return a newly allocated vpDisplay specialization if a GUI library is available or nullptr otherwise.
VISP_EXPORT int wait(double t0, double t)