Visual Servoing Platform  version 3.6.1 under development (2024-05-09)
servoBiclopsPoint2DArtVelocity.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 articular
34  */
35 
45 #include <iostream>
46 
47 #include <visp3/core/vpConfig.h>
48 
49 #if defined(VISP_HAVE_BICLOPS) && defined(VISP_HAVE_APRILTAG) && defined(VISP_HAVE_REALSENSE2)
50 
51 #include <visp3/core/vpDisplay.h>
52 #include <visp3/core/vpException.h>
53 #include <visp3/core/vpHomogeneousMatrix.h>
54 #include <visp3/core/vpImage.h>
55 #include <visp3/detection/vpDetectorAprilTag.h>
56 #include <visp3/gui/vpDisplayGDI.h>
57 #include <visp3/gui/vpDisplayGTK.h>
58 #include <visp3/gui/vpDisplayX.h>
59 #include <visp3/io/vpParseArgv.h>
60 #include <visp3/robot/vpRobotBiclops.h>
61 #include <visp3/sensor/vpRealSense2.h>
62 #include <visp3/visual_features/vpFeatureBuilder.h>
63 #include <visp3/visual_features/vpFeaturePoint.h>
64 #include <visp3/vs/vpServo.h>
65 #include <visp3/vs/vpServoDisplay.h>
66 
67 // List of allowed command line options
68 #define GETOPTARGS "c:d:h"
69 
77 void usage(const char *name, const char *badparam, std::string &conf)
78 {
79  fprintf(stdout, "\n\
80  Example of eye-in-hand control law. We control here a real robot, the biclops\n\
81  robot (pan-tilt head provided by Traclabs) equipped with a Realsense camera\n\
82  mounted on its end-effector. The velocity to apply to the PT head is joint\n\
83  velocity. The visual feature is a point corresponding to the center of\n\
84  gravity of an AprilTag. \n\
85 \n\
86 SYNOPSIS\n\
87  %s [-c <Biclops configuration file>] [-h]\n",
88  name);
89 
90  fprintf(stdout, "\n\
91 OPTIONS: Default\n\
92  -c <Biclops configuration file> %s\n\
93  Sets the Biclops robot configuration file.\n",
94  conf.c_str());
95 
96  if (badparam) {
97  fprintf(stderr, "ERROR: \n");
98  fprintf(stderr, "\nBad parameter [%s]\n", badparam);
99  }
100 }
101 
112 bool getOptions(int argc, const char **argv, std::string &conf)
113 {
114  const char *optarg_;
115  int c;
116  while ((c = vpParseArgv::parse(argc, argv, GETOPTARGS, &optarg_)) > 1) {
117 
118  switch (c) {
119  case 'c':
120  conf = optarg_;
121  break;
122  case 'h':
123  usage(argv[0], nullptr, conf);
124  return false;
125  break;
126 
127  default:
128  usage(argv[0], optarg_, conf);
129  return false;
130  break;
131  }
132  }
133 
134  if ((c == 1) || (c == -1)) {
135  // standalone param or error
136  usage(argv[0], nullptr, conf);
137  std::cerr << "ERROR: " << std::endl;
138  std::cerr << " Bad argument " << optarg_ << std::endl << std::endl;
139  return false;
140  }
141 
142  return true;
143 }
144 
145 int main(int argc, const char **argv)
146 {
147  try {
148  // Default unix configuration file path
149  std::string opt_conf = "/usr/share/BiclopsDefault.cfg";
150 
151  // Read the command line options
152  if (getOptions(argc, argv, opt_conf) == false) {
153  return EXIT_FAILURE;
154  }
155 
156  // Initialize PTU
157  vpRobotBiclops robot(opt_conf);
158 
159  /*
160  * Biclops DH2 has the following axis orientation
161  *
162  * tilt + <---- (end-effector-frame)
163  * |
164  * \/ pan +
165  *
166  * The end-effector-frame from PT unit rear view is the following
167  *
168  * /\ x
169  * |
170  * (e) ----> y
171  *
172  *
173  *
174  * The camera frame attached to the PT unit is the following (rear view)
175  *
176  * (c) ----> x
177  * |
178  * \/ y
179  *
180  * The corresponding cRe (camera to end-effector rotation matrix) is then the following
181  *
182  * ( 0 1 0)
183  * cRe = (-1 0 0)
184  * ( 0 0 1)
185  *
186  * Translation cte (camera to end-effector) can be neglected
187  *
188  * (0)
189  * cte = (0)
190  * (0)
191  */
192 
193  robot.setDenavitHartenbergModel(vpBiclops::DH2);
194  vpRotationMatrix cRe;
195  cRe[0][0] = 0; cRe[0][1] = 1; cRe[0][2] = 0;
196  cRe[1][0] = -1; cRe[1][1] = 0; cRe[1][2] = 0;
197  cRe[2][0] = 0; cRe[2][1] = 0; cRe[2][2] = 1;
198  vpTranslationVector cte; // By default set to 0
199 
200  // Robot Jacobian (expressed in the end-effector frame)
201  vpMatrix eJe;
202  // Camera to end-effector frame transformation
203  vpHomogeneousMatrix cMe(cte, cRe);
204  // Velocity twist transformation to express a velocity from end-effector to camera frame
205  vpVelocityTwistMatrix cVe(cMe);
206 
207  // Initialize grabber
208  vpRealSense2 g;
209  rs2::config config;
210  config.disable_stream(RS2_STREAM_DEPTH);
211  config.disable_stream(RS2_STREAM_INFRARED);
212  config.enable_stream(RS2_STREAM_COLOR, 640, 480, RS2_FORMAT_RGBA8, 30);
213  g.open(config);
214 
215  std::cout << "Read camera parameters from Realsense device" << std::endl;
216  vpCameraParameters cam;
218 
220  q = 0;
221  std::cout << "Move PT to initial position: " << q.t() << std::endl;
223  robot.setPosition(vpRobot::JOINT_STATE, q);
224 
226  g.acquire(I);
227 
228  // We open a window using either X11 or GTK or GDI.
229  // Its size is automatically defined by the image (I) size
230 #if defined(VISP_HAVE_X11)
231  vpDisplayX display(I, 100, 100, "Display X...");
232 #elif defined(VISP_HAVE_GTK)
233  vpDisplayGTK display(I, 100, 100, "Display GTK...");
234 #elif defined(VISP_HAVE_GDI)
235  vpDisplayGDI display(I, 100, 100, "Display GDI...");
236 #endif
237 
239  vpDisplay::flush(I);
240 
241  vpDetectorAprilTag detector;
242 
243  vpServo task;
244 
245  // Create current and desired point visual feature
246  vpFeaturePoint p, pd;
247  // Sets the desired position of the visual feature
248  // Here we set Z desired to 1 meter, and (x,y)=(0,0) to center the tag in the image
249  pd.buildFrom(0, 0, 1);
250 
251  // Define the task
252  // - we want an eye-in-hand control law
253  // - joint velocities are computed
254  // - interaction matrix is the one at desired position
257  task.set_cVe(cVe);
258  // We want to see a point on a point
259  task.addFeature(p, pd);
260  // Set the gain
261  task.setLambda(0.2);
262 
264 
265  bool quit = false;
266  bool send_velocities = false;
267  vpColVector q_dot;
268 
269  while (!quit) {
270  g.acquire(I);
272 
273  {
274  std::stringstream ss;
275  ss << "Left click to " << (send_velocities ? "stop the robot" : "servo the robot") << ", right click to quit.";
276  vpDisplay::displayText(I, 20, 20, ss.str(), vpColor::red);
277  }
278 
279  if (detector.detect(I)) {
280  // We consider the first tag only
281  vpImagePoint cog = detector.getCog(0); // 0 is the id of the first tag
282 
283  vpFeatureBuilder::create(p, cam, cog);
284 
285  // Get the jacobian
286  robot.get_eJe(eJe);
287  task.set_eJe(eJe);
288 
289  q_dot = task.computeControlLaw();
290 
291  vpServoDisplay::display(task, cam, I);
292  vpDisplay::flush(I);
293 
294  std::cout << "q_dot: " << q_dot.t() << std::endl;
295 
296  std::cout << "|| s - s* || = " << (task.getError()).sumSquare() << std::endl;
297  }
298  else {
299  q_dot = 0;
300  }
301  if (!send_velocities) {
302  q_dot = 0;
303  }
304 
305  robot.setVelocity(vpRobot::JOINT_STATE, q_dot);
306 
307  vpDisplay::flush(I);
308 
310  if (vpDisplay::getClick(I, button, false)) {
311  switch (button) {
313  send_velocities = !send_velocities;
314  break;
315 
317  quit = true;
318  q_dot = 0;
319  break;
320 
321  default:
322  break;
323  }
324  }
325  }
326 
327  std::cout << "Stop the robot " << std::endl;
329 
330  return EXIT_SUCCESS;
331  }
332  catch (const vpException &e) {
333  std::cout << "Catch an exception: " << e.getMessage() << std::endl;
334  return EXIT_FAILURE;
335  }
336 }
337 
338 #else
339 int main()
340 {
341  std::cout << "You do not have an Biclops PT robot connected to your computer..." << std::endl;
342  return EXIT_SUCCESS;
343 }
344 #endif
@ DH2
Second Denavit-Hartenberg representation.
Definition: vpBiclops.h:95
static const unsigned int ndof
Number of dof.
Definition: vpBiclops.h:99
Generic class defining intrinsic camera parameters.
@ perspectiveProjWithoutDistortion
Perspective projection without distortion model.
Implementation of column vector and the associated operations.
Definition: vpColVector.h:163
vpRowVector t() const
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
Implementation of a matrix and operations on matrices.
Definition: vpMatrix.h:146
static bool parse(int *argcPtr, const char **argv, vpArgvInfo *argTable, int flags)
Definition: vpParseArgv.cpp:69
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 Biclops, pan, tilt head control.
void get_eJe(vpMatrix &eJe) vp_override
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel) vp_override
@ 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
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.