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