Visual Servoing Platform  version 3.6.1 under development (2024-12-13)
servoAfma6MegaposePBVS.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  * Pose-based visual servoing using MegaPose, on an Afma6 platform.
32  */
33 
61 #include <iostream>
62 
63 #include <visp3/core/vpCameraParameters.h>
64 #include <visp3/core/vpConfig.h>
65 #include <visp3/detection/vpDetectorAprilTag.h>
66 #include <visp3/gui/vpDisplayGDI.h>
67 #include <visp3/gui/vpDisplayX.h>
68 #include <visp3/gui/vpPlot.h>
69 #include <visp3/io/vpImageIo.h>
70 #include <visp3/robot/vpRobotAfma6.h>
71 #include <visp3/sensor/vpRealSense2.h>
72 #include <visp3/visual_features/vpFeatureThetaU.h>
73 #include <visp3/visual_features/vpFeatureTranslation.h>
74 #include <visp3/vs/vpServo.h>
75 #include <visp3/vs/vpServoDisplay.h>
76 #include <visp3/core/vpImageFilter.h>
77 #include <visp3/io/vpVideoWriter.h>
78 
79 // Check if std:c++17 or higher
80 #if defined(VISP_HAVE_REALSENSE2) && ((__cplusplus >= 201703L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201703L))) && \
81  (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && defined(VISP_HAVE_AFMA6) && defined(VISP_HAVE_MODULE_DNN_TRACKER)
82 
83 #include <optional>
84 #include <visp3/io/vpJsonArgumentParser.h>
85 #include <visp3/dnn_tracker/vpMegaPoseTracker.h>
86 
87 #ifdef VISP_HAVE_NLOHMANN_JSON
88 using json = nlohmann::json;
89 #endif
90 
91 #ifdef ENABLE_VISP_NAMESPACE
92 using namespace VISP_NAMESPACE_NAME;
93 #endif
94 
95 std::optional<vpRect> detectObjectForInitMegaposeClick(const vpImage<vpRGBa> &I)
96 {
97  const bool startLabelling = vpDisplay::getClick(I, false);
98 
99  const vpImagePoint textPosition(10.0, 20.0);
100 
101  if (startLabelling) {
102  vpImagePoint topLeft, bottomRight;
103  vpDisplay::displayText(I, textPosition, "Click the upper left corner of the bounding box", vpColor::red);
104  vpDisplay::flush(I);
105  vpDisplay::getClick(I, topLeft, true);
107  vpDisplay::displayCross(I, topLeft, 5, vpColor::red, 2);
108  vpDisplay::displayText(I, textPosition, "Click the bottom right corner of the bounding box", vpColor::red);
109  vpDisplay::flush(I);
110  vpDisplay::getClick(I, bottomRight, true);
111  vpRect bb(topLeft, bottomRight);
112  return bb;
113  }
114  else {
116  vpDisplay::displayText(I, textPosition, "Click when the object is visible and static to start reinitializing megapose.", vpColor::red);
117  vpDisplay::flush(I);
118  return std::nullopt;
119  }
120 }
121 
122 int main(int argc, const char *argv[])
123 {
124  bool opt_verbose = true;
125  bool opt_plot = true;
126  double convergence_threshold_t = 0.0005; // Value in [m]
127  double convergence_threshold_tu = 0.5; // Value in [deg]
128 
129  unsigned width = 640, height = 480;
130  std::string megaposeAddress = "127.0.0.1";
131  unsigned megaposePort = 5555;
132  int refinerIterations = 1, coarseNumSamples = 1024;
133  std::string objectName = "";
134 
135  std::string desiredPosFile = "desired.pos";
136  std::string initialPosFile = "init.pos";
137 
138 #ifdef VISP_HAVE_NLOHMANN_JSON
139  vpJsonArgumentParser parser("Pose-based visual servoing with Megapose on an Afma6, with a Realsense D435.", "--config", "/");
140  parser
141  .addArgument("initialPose", initialPosFile, true, "Path to the file that contains that the desired pose. Can be acquired with Afma6_office.")
142  .addArgument("desiredPose", desiredPosFile, true, "Path to the file that contains that the desired pose. Can be acquired with Afma6_office.")
143  .addArgument("object", objectName, true, "Name of the object to track with megapose.")
144  .addArgument("megapose/address", megaposeAddress, true, "IP address of the Megapose server.")
145  .addArgument("megapose/port", megaposePort, true, "Port on which the Megapose server listens for connections.")
146  .addArgument("megapose/refinerIterations", refinerIterations, false, "Number of Megapose refiner model iterations."
147  "A higher count may lead to better accuracy, at the cost of more processing time")
148  .addArgument("megapose/initialisationNumSamples", coarseNumSamples, false, "Number of Megapose renderings used for the initial pose estimation.");
149  parser.parse(argc, argv);
150 #endif
151 
152  vpRobotAfma6 robot;
153 
154  try {
155  std::cout << "WARNING: This example will move the robot! "
156  << "Please make sure to have the user stop button at hand!" << std::endl
157  << "Press Enter to continue..." << std::endl;
158  std::cin.ignore();
159  std::vector<vpColVector> velocities;
160  std::vector<vpPoseVector> error;
161  /*
162  * Move to a safe position
163  */
164  vpColVector q(6, 0);
165 
166  vpVideoWriter writer;
167 
168  // Go to desired pose, save true camera pose wrt world frame
169  robot.setPositioningVelocity(10.0); // In %
170  robot.readPosFile(desiredPosFile, q);
172  robot.setPosition(vpRobot::ARTICULAR_FRAME, q); // Move to the joint position
173  std::cout << "Move to joint position: " << q.t() << std::endl;
174  vpHomogeneousMatrix cdTw = robot.get_fMc(q).inverse();
175 
176  // Setup camera
177  vpRealSense2 rs;
178  rs2::config config;
179  config.enable_stream(RS2_STREAM_COLOR, width, height, RS2_FORMAT_RGBA8, 30);
180  rs.open(config);
181 
182  // Get camera intrinsics
183  vpCameraParameters cam =
185  std::cout << "cam:\n" << cam << std::endl;
186  // Initialize Megapose
187  std::shared_ptr<vpMegaPose> megapose;
188  try {
189  megapose = std::make_shared<vpMegaPose>(megaposeAddress, megaposePort, cam, height, width);
190  }
191  catch (...) {
192  throw vpException(vpException::ioError, "Could not connect to Megapose server at " + megaposeAddress + " on port " + std::to_string(megaposePort));
193  }
194 
195  vpMegaPoseTracker megaposeTracker(megapose, objectName, refinerIterations);
196  megapose->setCoarseNumSamples(coarseNumSamples);
197  const std::vector<std::string> allObjects = megapose->getObjectNames();
198  if (std::find(allObjects.begin(), allObjects.end(), objectName) == allObjects.end()) {
199  throw vpException(vpException::badValue, "Object " + objectName + " is not known by the Megapose server!");
200  }
201  std::future<vpMegaPoseEstimate> trackerFuture;
202 
203  vpImage<vpRGBa> I(height, width);
204 
205 #if defined(VISP_HAVE_X11)
206  vpDisplayX dc(I, 10, 10, "Color image");
207 #elif defined(VISP_HAVE_GDI)
208  vpDisplayGDI dc(I, 10, 10, "Color image");
209 #endif
210 
211  std::optional<vpRect> detection;
212  while (!detection) {
213  rs.acquire(I);
215  detection = detectObjectForInitMegaposeClick(I);
216  vpDisplay::flush(I);
217  }
218 
219  vpHomogeneousMatrix cdTo = megaposeTracker.init(I, *detection).get().cTo; //get camera pose relative to object, not world
220 
221  // Go to starting pose, save true starting pose in world frame
222  robot.readPosFile(initialPosFile, q);
224  robot.setPosition(vpRobot::ARTICULAR_FRAME, q); // Move to the joint position
225  std::cout << "Move to joint position: " << q.t() << std::endl;
226  vpHomogeneousMatrix cTw = robot.get_fMc(q).inverse();
227  vpHomogeneousMatrix cdTc_true = cdTw * cTw.inverse(); // ground truth error
228 
229  detection = std::nullopt;
230  while (!detection) {
231  rs.acquire(I);
233  detection = detectObjectForInitMegaposeClick(I);
234  vpDisplay::flush(I);
235  }
236  auto est = megaposeTracker.init(I, *detection).get();
237  vpHomogeneousMatrix cTo = est.cTo;
238  std::cout << "Estimate score = " << est.score << std::endl;
239  writer.setFileName("video/I%05d.png");
240  //writer.setFramerate(60.0);
241  writer.open(I);
242 
243  //vpHomogeneousMatrix oTw = cTo.inverse() * cTw;
244  vpHomogeneousMatrix cdTc = cdTo * cTo.inverse();
247  t.buildFrom(cdTc);
248  tu.buildFrom(cdTc);
249 
252 
253  vpServo task;
254  task.addFeature(t, td);
255  task.addFeature(tu, tud);
258  task.setLambda(0.2);
259 
260  vpPlot *plotter = nullptr;
261  int iter_plot = 0;
262 
263  if (opt_plot) {
264  plotter = new vpPlot(2, static_cast<int>(250 * 2), 500, static_cast<int>(I.getWidth()) + 80, 10,
265  "Real time curves plotter");
266  plotter->setTitle(0, "Visual features error");
267  plotter->setTitle(1, "Camera velocities");
268  plotter->initGraph(0, 6);
269  plotter->initGraph(1, 6);
270  plotter->setLegend(0, 0, "error_feat_tx");
271  plotter->setLegend(0, 1, "error_feat_ty");
272  plotter->setLegend(0, 2, "error_feat_tz");
273  plotter->setLegend(0, 3, "error_feat_theta_ux");
274  plotter->setLegend(0, 4, "error_feat_theta_uy");
275  plotter->setLegend(0, 5, "error_feat_theta_uz");
276  plotter->setLegend(1, 0, "vc_x");
277  plotter->setLegend(1, 1, "vc_y");
278  plotter->setLegend(1, 2, "vc_z");
279  plotter->setLegend(1, 3, "wc_x");
280  plotter->setLegend(1, 4, "wc_y");
281  plotter->setLegend(1, 5, "wc_z");
282  }
283 
284  bool final_quit = false;
285  bool has_converged = false;
286  bool send_velocities = false;
287 
289  vpColVector vLastUpdate(6);
290 
291  vpHomogeneousMatrix prev_cTo = cTo;
292 
293  vpColVector v(6);
294 
295  bool callMegapose = true;
296  vpMegaPoseEstimate megaposeEstimate;
297 
298  while (!has_converged && !final_quit) {
299  double t_start = vpTime::measureTimeMs();
300 
301  rs.acquire(I);
303  if (!callMegapose && trackerFuture.wait_for(std::chrono::milliseconds(0)) == std::future_status::ready) {
304  megaposeEstimate = trackerFuture.get();
305 
306  cTo = megaposeEstimate.cTo;
307  callMegapose = true;
308  if (megaposeEstimate.score < 0.2) { // If confidence is low, exit
309  final_quit = true;
310  std::cout << "Low confidence, exiting" << std::endl;
311  }
312  }
313 
314  if (callMegapose) {
315  std::cout << "Calling megapose" << std::endl;
316  trackerFuture = megaposeTracker.track(I);
317  callMegapose = false;
318  }
319 
320  std::stringstream ss;
321  ss << "Left click to " << (send_velocities ? "stop the robot" : "servo the robot") << ", right click to quit.";
322  vpDisplay::displayText(I, 20, 20, ss.str(), vpColor::red);
323 
324  // Update visual features
325  cdTc = cdTo * cTo.inverse();
326  t.buildFrom(cdTc);
327  tu.buildFrom(cdTc);
328  v = task.computeControlLaw();
329  velocities.push_back(v);
330 
331  // Update true pose
332  vpPoseVector p;
333  robot.getPosition(vpRobot::ARTICULAR_FRAME, q);
334  cTw = robot.get_fMc(q).inverse();
335  cdTc_true = cdTw * cTw.inverse();
336  vpPoseVector cdrc(cdTc_true);
337  error.push_back(cdrc);
338 
339  // Display desired and current pose features
340  vpDisplay::displayFrame(I, cdTo, cam, 0.05, vpColor::yellow, 2);
341  vpDisplay::displayFrame(I, cTo, cam, 0.05, vpColor::none, 3);
342 
343  if (opt_plot) {
344  plotter->plot(0, iter_plot, task.getError());
345  plotter->plot(1, iter_plot, v);
346  iter_plot++;
347  }
348 
349  if (opt_verbose) {
350  std::cout << "v: " << v.t() << std::endl;
351  }
352 
354  vpThetaUVector cd_tu_c = cdTc.getThetaUVector();
355  double error_tr = sqrt(cd_t_c.sumSquare());
356  double error_tu = vpMath::deg(sqrt(cd_tu_c.sumSquare()));
357  vpTranslationVector cd_t_c_true = cdTc_true.getTranslationVector();
358  vpThetaUVector cd_tu_c_true = cdTc_true.getThetaUVector();
359  double error_tr_true = sqrt(cd_t_c_true.sumSquare());
360  double error_tu_true = vpMath::deg(sqrt(cd_tu_c_true.sumSquare()));
361 
362  ss.str("");
363  ss << "Predicted error_t: " << error_tr << ", True error_t:" << error_tr_true;
364  vpDisplay::displayText(I, 20, static_cast<int>(I.getWidth()) - 300, ss.str(), vpColor::red);
365  ss.str("");
366  ss << "Predicted error_tu: " << error_tu << ", True error_tu:" << error_tu_true;
367  vpDisplay::displayText(I, 40, static_cast<int>(I.getWidth()) - 300, ss.str(), vpColor::red);
368 
369  if (opt_verbose)
370  std::cout << "error translation: " << error_tr << " ; error rotation: " << error_tu << std::endl;
371 
372  if (error_tr < convergence_threshold_t && error_tu < convergence_threshold_tu) {
373  has_converged = true;
374  std::cout << "Servo task has converged" << std::endl;
375  vpDisplay::displayText(I, 100, 20, "Servo task has converged", vpColor::red);
376  }
377 
378  // Send to the robot
380 
381  ss.str("");
382  ss << "Loop time: " << vpTime::measureTimeMs() - t_start << " ms";
383  vpDisplay::displayText(I, 40, 20, ss.str(), vpColor::red);
384  vpDisplay::flush(I);
385  vpImage<vpRGBa> displayImage;
386  vpDisplay::getImage(I, displayImage);
387  writer.saveFrame(displayImage);
388 
390  if (vpDisplay::getClick(I, button, false)) {
391  switch (button) {
393  send_velocities = !send_velocities;
394  break;
395 
397  final_quit = true;
398  v = 0;
399  break;
400 
401  default:
402  break;
403  }
404  }
405  }
406  std::cout << "Stop the robot " << std::endl;
408 
409 #ifdef VISP_HAVE_NLOHMANN_JSON
410  // Save results to JSON
411  json j = json {
412  {"velocities", velocities},
413  {"error", error}
414  };
415  std::ofstream jsonFile;
416  jsonFile.open("results.json");
417  jsonFile << j.dump(4);
418  jsonFile.close();
419 #endif
420 
421  if (opt_plot && plotter != nullptr) {
422  delete plotter;
423  plotter = nullptr;
424  }
425 
426  if (!final_quit) {
427  while (!final_quit) {
428  rs.acquire(I);
430 
431  vpDisplay::displayText(I, 20, 20, "Click to quit the program.", vpColor::red);
432  vpDisplay::displayText(I, 40, 20, "Visual servo converged.", vpColor::red);
433 
434  if (vpDisplay::getClick(I, false)) {
435  final_quit = true;
436  }
437 
438  vpDisplay::flush(I);
439  }
440  }
441  }
442  catch (const vpException &e) {
443  std::cout << "ViSP exception: " << e.what() << std::endl;
444  std::cout << "Stop the robot " << std::endl;
446  return EXIT_FAILURE;
447  }
448  catch (const std::exception &e) {
449  std::cout << "ur_rtde exception: " << e.what() << std::endl;
450  return EXIT_FAILURE;
451  }
452 
453  return EXIT_SUCCESS;
454 }
455 #else
456 int main()
457 {
458 #if !defined(VISP_HAVE_REALSENSE2)
459  std::cout << "Install librealsense-2.x" << std::endl;
460 #endif
461 #if !((__cplusplus >= 201703L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201703L)))
462  std::cout << "Build ViSP with c++17 or higher compiler flag (cmake -DUSE_CXX_STANDARD=17)." << std::endl;
463 #endif
464 #if !defined(VISP_HAVE_AFMA6)
465  std::cout << "ViSP is not built with Afma-6 robot support..." << std::endl;
466 #endif
467  return EXIT_SUCCESS;
468 }
469 #endif
Generic class defining intrinsic camera parameters.
@ perspectiveProjWithoutDistortion
Perspective projection without distortion model.
Implementation of column vector and the associated operations.
Definition: vpColVector.h:191
static const vpColor red
Definition: vpColor.h:217
static const vpColor none
Definition: vpColor.h:229
static const vpColor yellow
Definition: vpColor.h:225
Display for windows using GDI (available on any windows 32 platform).
Definition: vpDisplayGDI.h:130
static bool getClick(const vpImage< unsigned char > &I, bool blocking=true)
static void display(const vpImage< unsigned char > &I)
static void displayFrame(const vpImage< unsigned char > &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, double size, const vpColor &color=vpColor::none, unsigned int thickness=1, const vpImagePoint &offset=vpImagePoint(0, 0), const std::string &frameName="", const vpColor &textColor=vpColor::black, const vpImagePoint &textOffset=vpImagePoint(15, 15))
static void getImage(const vpImage< unsigned char > &Is, vpImage< vpRGBa > &Id)
Definition: vpDisplay.cpp:140
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
@ ioError
I/O error.
Definition: vpException.h:67
@ badValue
Used to indicate that a value is not in the allowed range.
Definition: vpException.h:73
const char * what() const
Definition: vpException.cpp:71
Class that defines a 3D visual feature from a axis/angle parametrization that represent the rotatio...
Class that defines the translation visual feature .
Implementation of an homogeneous matrix and operations on such kind of matrices.
vpThetaUVector getThetaUVector() const
vpHomogeneousMatrix & buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
vpHomogeneousMatrix inverse() const
vpTranslationVector getTranslationVector() const
Class that defines a 2D point in an image. This class is useful for image processing and stores only ...
Definition: vpImagePoint.h:82
unsigned int getWidth() const
Definition: vpImage.h:242
Command line argument parsing with support for JSON files. If a JSON file is supplied,...
static double deg(double rad)
Definition: vpMath.h:119
vpHomogeneousMatrix cTo
Definition: vpMegaPose.h:70
A simplified interface to track a single object with MegaPose. This tracker works asynchronously: A c...
This class enables real time drawing of 2D or 3D graphics. An instance of the class open a window whi...
Definition: vpPlot.h:112
void initGraph(unsigned int graphNum, unsigned int curveNbr)
Definition: vpPlot.cpp:203
void setLegend(unsigned int graphNum, unsigned int curveNum, const std::string &legend)
Definition: vpPlot.cpp:552
void plot(unsigned int graphNum, unsigned int curveNum, double x, double y)
Definition: vpPlot.cpp:270
void setTitle(unsigned int graphNum, const std::string &title)
Definition: vpPlot.cpp:510
Implementation of a pose vector and operations on poses.
Definition: vpPoseVector.h:203
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())
Defines a rectangle in the plane.
Definition: vpRect.h:79
Control of Irisa's gantry robot named Afma6.
Definition: vpRobotAfma6.h:212
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel) VP_OVERRIDE
@ ARTICULAR_FRAME
Definition: vpRobot.h:80
@ CAMERA_FRAME
Definition: vpRobot.h:84
@ STATE_POSITION_CONTROL
Initialize the position controller.
Definition: vpRobot.h:68
@ 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
double sumSquare() const
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 setLambda(double c)
Definition: vpServo.h:986
void setServo(const vpServoType &servo_type)
Definition: vpServo.cpp:134
vpColVector getError() const
Definition: vpServo.h:510
vpColVector computeControlLaw()
Definition: vpServo.cpp:705
@ CURRENT
Definition: vpServo.h:202
Implementation of a rotation vector as axis-angle minimal representation.
Class that consider the case of a translation vector.
Class that enables to write easily a video file or a sequence of images.
void saveFrame(vpImage< vpRGBa > &I)
void setFileName(const std::string &filename)
void open(vpImage< vpRGBa > &I)
VISP_EXPORT double measureTimeMs()