Visual Servoing Platform  version 3.6.1 under development (2024-12-13)
servoAfma6Cylinder2DCamVelocity.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  */
35 
46 #include <iostream>
47 
48 #include <visp3/core/vpConfig.h>
49 
50 #if defined(VISP_HAVE_REALSENSE2) && defined(VISP_HAVE_AFMA6)
51 
52 #include <visp3/core/vpImage.h>
53 #include <visp3/gui/vpDisplayGTK.h>
54 #include <visp3/gui/vpDisplayOpenCV.h>
55 #include <visp3/gui/vpDisplayX.h>
56 #include <visp3/io/vpImageIo.h>
57 #include <visp3/sensor/vpRealSense2.h>
58 #include <visp3/core/vpCylinder.h>
59 #include <visp3/core/vpHomogeneousMatrix.h>
60 #include <visp3/core/vpMath.h>
61 #include <visp3/me/vpMeLine.h>
62 #include <visp3/visual_features/vpFeatureBuilder.h>
63 #include <visp3/visual_features/vpFeatureLine.h>
64 #include <visp3/robot/vpRobotAfma6.h>
65 #include <visp3/vs/vpServoDisplay.h>
66 #include <visp3/vs/vpServo.h>
67 
68 #ifdef ENABLE_VISP_NAMESPACE
69 using namespace VISP_NAMESPACE_NAME;
70 #endif
71 
80 int main(int argc, char **argv)
81 {
82  bool opt_verbose = false;
83  bool opt_adaptive_gain = false;
84 
85  for (int i = 1; i < argc; ++i) {
86  if (std::string(argv[i]) == "--verbose") {
87  opt_verbose = true;
88  }
89  else if (std::string(argv[i]) == "--adaptive-gain") {
90  opt_adaptive_gain = true;
91  }
92  else if ((std::string(argv[i]) == "--help") || (std::string(argv[i]) == "-h")) {
93  std::cout
94  << argv[0]
95  << " [--adaptive-gain]"
96  << " [--verbose]"
97  << " [--help] [-h]"
98  << std::endl;;
99  return EXIT_SUCCESS;
100  }
101  }
102 
103  vpRobotAfma6 robot;
105 
106  // Load the end-effector to camera frame transformation obtained
107  // using a camera intrinsic model with distortion
108  robot.init(vpAfma6::TOOL_INTEL_D435_CAMERA, projModel);
109 
110  try {
111  std::cout << "WARNING: This example will move the robot! "
112  << "Please make sure to have the user stop button at hand!" << std::endl
113  << "Press Enter to continue..." << std::endl;
114  std::cin.ignore();
115 
116  vpRealSense2 rs;
117  rs2::config config;
118  unsigned int width = 640, height = 480, fps = 60;
119  config.enable_stream(RS2_STREAM_COLOR, width, height, RS2_FORMAT_RGBA8, fps);
120  config.enable_stream(RS2_STREAM_DEPTH, width, height, RS2_FORMAT_Z16, fps);
121  config.enable_stream(RS2_STREAM_INFRARED, width, height, RS2_FORMAT_Y8, fps);
122  rs.open(config);
123 
124  // Warm up camera
126  for (size_t i = 0; i < 10; ++i) {
127  rs.acquire(I);
128  }
129 
130 #ifdef VISP_HAVE_X11
131  vpDisplayX display(I, 100, 100, "Current image");
132 #elif defined(HAVE_OPENCV_HIGHGUI)
133  vpDisplayOpenCV display(I, 100, 100, "Current image");
134 #elif defined(VISP_HAVE_GTK)
135  vpDisplayGTK display(I, 100, 100, "Current image");
136 #endif
138  vpDisplay::flush(I);
139 
140  int nblines = 2;
141  std::vector<vpMeLine> line(nblines);
142 
143  vpMe me;
144  me.setRange(10);
145  me.setPointsToTrack(100);
147  me.setThreshold(15);
148  me.setSampleStep(10);
149 
150  // Initialize the tracking of the two edges of the cylinder
151  for (int i = 0; i < nblines; ++i) {
152  line[i].setDisplay(vpMeSite::RANGE_RESULT);
153  line[i].setMe(&me);
154 
155  line[i].initTracking(I);
156  line[i].track(I);
157  vpDisplay::flush(I);
158  }
159 
160  // Get camera intrinsics
161  vpCameraParameters cam;
162  robot.getCameraParameters(cam, I);
163  std::cout << "cam:\n" << cam << std::endl;
164 
165  // Sets the current position of the visual feature ");
166  std::vector<vpFeatureLine> s_line(nblines);
167  for (int i = 0; i < nblines; ++i) {
168  vpFeatureBuilder::create(s_line[i], cam, line[i]);
169  }
170 
171  // Sets the desired position of the visual feature ");
172  vpCylinder cylinder(0, 1, 0, 0, 0, 0, 0.04);
173 
174  vpHomogeneousMatrix c_M_o(0, 0, 0.4, vpMath::rad(0), vpMath::rad(0), vpMath::rad(0));
175 
176  cylinder.project(c_M_o);
177 
178  std::vector<vpFeatureLine> s_line_d(nblines);
179  vpFeatureBuilder::create(s_line_d[0], cylinder, vpCylinder::line1);
180  vpFeatureBuilder::create(s_line_d[1], cylinder, vpCylinder::line2);
181 
182  // {
183  // std::cout << "Desired features: " << std::endl;
184  // std::cout << " - line 1: rho: " << s_line_d[0].getRho() << " theta: " << vpMath::deg(s_line_d[0].getTheta()) << "deg" << std::endl;
185  // std::cout << " - line 2: rho: " << s_line_d[1].getRho() << " theta: " << vpMath::deg(ss_line_d_d[1].getTheta()) << "deg" << std::endl;
186  // }
187 
188  // Next 2 lines are needed to keep the conventions defined in vpMeLine
189  s_line_d[0].setRhoTheta(+fabs(s_line_d[0].getRho()), 0);
190  s_line_d[1].setRhoTheta(+fabs(s_line_d[1].getRho()), M_PI);
191  // {
192  // std::cout << "Modified desired features: " << std::endl;
193  // std::cout << " - line 1: rho: " << s_line_d[0].getRho() << " theta: " << vpMath::deg(s_line_d[0].getTheta()) << "deg" << std::endl;
194  // std::cout << " - line 2: rho: " << s_s_line_dd[1].getRho() << " theta: " << vpMath::deg(s_line_d[1].getTheta()) << "deg" << std::endl;
195  // }
196 
197  // Define the task
198  vpServo task;
199  // - we want an eye-in-hand control law
200  // - robot is controlled in the camera frame
203  // - we want to see a two lines on two lines
204  for (int i = 0; i < nblines; ++i) {
205  task.addFeature(s_line[i], s_line_d[i]);
206  }
207 
208  // Set the gain
209  if (opt_adaptive_gain) {
210  vpAdaptiveGain lambda(1.5, 0.4, 30); // lambda(0)=4, lambda(oo)=0.4 and lambda'(0)=30
211  task.setLambda(lambda);
212  }
213  else {
214  task.setLambda(0.5);
215  }
216 
217  // Display task information
218  task.print();
220 
221  vpColVector v_c(6);
222  bool final_quit = false;
223  bool send_velocities = false;
224 
225  while (!final_quit) {
226  double t_start = vpTime::measureTimeMs();
227 
228  rs.acquire(I);
230 
231  std::stringstream ss;
232  ss << "Left click to " << (send_velocities ? "stop the robot" : "servo the robot") << ", right click to quit.";
233  vpDisplay::displayText(I, 20, 20, ss.str(), vpColor::red);
234 
235  // Track the two edges and update the features
236  for (int i = 0; i < nblines; ++i) {
237  line[i].track(I);
238  line[i].display(I, vpColor::red);
239 
240  vpFeatureBuilder::create(s_line[i], cam, line[i]);
241  //std::cout << "line " << i << " rho: " << s[i].getRho() << " theta: " << vpMath::deg(s[i].getTheta()) << " deg" << std::endl;
242 
243  s_line[i].display(cam, I, vpColor::red);
244  s_line_d[i].display(cam, I, vpColor::green);
245  }
246 
247  v_c = task.computeControlLaw();
248 
249  if (opt_verbose) {
250  std::cout << "v: " << v_c.t() << std::endl;
251  std::cout << "\t\t || s - s* || = " << task.getError().sumSquare() << std::endl;;
252  }
253 
254  if (!send_velocities) {
255  v_c = 0;
256  }
257 
259 
260  ss.str("");
261  ss << "Loop time: " << vpTime::measureTimeMs() - t_start << " ms";
262  vpDisplay::displayText(I, 40, 20, ss.str(), vpColor::red);
263  vpDisplay::flush(I);
264 
266  if (vpDisplay::getClick(I, button, false)) {
267  switch (button) {
269  send_velocities = !send_velocities;
270  break;
271 
273  final_quit = true;
274  break;
275 
276  default:
277  break;
278  }
279  }
280  }
281 
282  std::cout << "Stop the robot " << std::endl;
284 
285  if (!final_quit) {
286  while (!final_quit) {
287  rs.acquire(I);
289 
290  vpDisplay::displayText(I, 20, 20, "Click to quit the program.", vpColor::red);
291  vpDisplay::displayText(I, 40, 20, "Visual servo converged.", vpColor::red);
292 
293  if (vpDisplay::getClick(I, false)) {
294  final_quit = true;
295  }
296 
297  vpDisplay::flush(I);
298  }
299  }
300  task.print();
301  }
302  catch (const vpException &e) {
303  std::cout << "ViSP exception: " << e.what() << std::endl;
304  std::cout << "Stop the robot " << std::endl;
306  return EXIT_FAILURE;
307  }
308 
309  return EXIT_SUCCESS;
310 }
311 
312 #else
313 int main()
314 {
315  std::cout << "You do not have an afma6 robot connected to your computer..." << std::endl;
316  return EXIT_SUCCESS;
317 }
318 
319 #endif
Adaptive gain computation.
@ TOOL_INTEL_D435_CAMERA
Definition: vpAfma6.h:131
Generic class defining intrinsic camera parameters.
@ perspectiveProjWithDistortion
Perspective projection with distortion model.
Implementation of column vector and the associated operations.
Definition: vpColVector.h:191
double sumSquare() const
vpRowVector t() const
static const vpColor red
Definition: vpColor.h:217
static const vpColor green
Definition: vpColor.h:220
Class that defines a 3D cylinder in the object frame and allows forward projection of a 3D cylinder i...
Definition: vpCylinder.h:101
The vpDisplayGTK allows to display image using the GTK 3rd party library. Thus to enable this class G...
Definition: vpDisplayGTK.h:133
The vpDisplayOpenCV allows to display image using the OpenCV library. Thus to enable this class OpenC...
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
const char * what() const
Definition: vpException.cpp:71
static void create(vpFeaturePoint &s, const vpCameraParameters &cam, const vpImagePoint &t)
Implementation of an homogeneous matrix and operations on such kind of matrices.
static double rad(double deg)
Definition: vpMath.h:129
@ RANGE_RESULT
Definition: vpMeSite.h:78
Definition: vpMe.h:134
void setPointsToTrack(const int &points_to_track)
Definition: vpMe.h:408
void setRange(const unsigned int &range)
Definition: vpMe.h:415
void setLikelihoodThresholdType(const vpLikelihoodThresholdType likelihood_threshold_type)
Definition: vpMe.h:505
void setThreshold(const double &threshold)
Definition: vpMe.h:466
void setSampleStep(const double &sample_step)
Definition: vpMe.h:422
@ NORMALIZED_THRESHOLD
Definition: vpMe.h:145
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.
Definition: vpRobotAfma6.h:212
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel) VP_OVERRIDE
@ CAMERA_FRAME
Definition: vpRobot.h:84
@ STATE_VELOCITY_CONTROL
Initialize the velocity controller.
Definition: vpRobot.h:67
@ STATE_STOP
Stops robot motion especially in velocity and acceleration control.
Definition: vpRobot.h:66
virtual vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
Definition: vpRobot.cpp:202
void setInteractionMatrixType(const vpServoIteractionMatrixType &interactionMatrixType, const vpServoInversionType &interactionMatrixInversion=PSEUDO_INVERSE)
Definition: vpServo.cpp:380
@ EYEINHAND_CAMERA
Definition: vpServo.h:161
void addFeature(vpBasicFeature &s_cur, vpBasicFeature &s_star, unsigned int select=vpBasicFeature::FEATURE_ALL)
Definition: vpServo.cpp:331
void print(const vpServo::vpServoPrintType display_level=ALL, std::ostream &os=std::cout)
Definition: vpServo.cpp:171
void setLambda(double c)
Definition: vpServo.h:986
void setServo(const vpServoType &servo_type)
Definition: vpServo.cpp:134
vpColVector getError() const
Definition: vpServo.h:510
@ PSEUDO_INVERSE
Definition: vpServo.h:235
vpColVector computeControlLaw()
Definition: vpServo.cpp:705
@ DESIRED
Definition: vpServo.h:208
VISP_EXPORT double measureTimeMs()