51#include <visp3/core/vpConfig.h>
53#if defined(VISP_HAVE_REALSENSE2) && defined(VISP_HAVE_DISPLAY) && defined(VISP_HAVE_AFMA6)
55#include <visp3/core/vpCameraParameters.h>
56#include <visp3/detection/vpDetectorAprilTag.h>
57#include <visp3/gui/vpDisplayFactory.h>
58#include <visp3/gui/vpPlot.h>
59#include <visp3/io/vpImageIo.h>
60#include <visp3/robot/vpRobotAfma6.h>
61#include <visp3/sensor/vpRealSense2.h>
62#include <visp3/visual_features/vpFeatureThetaU.h>
63#include <visp3/visual_features/vpFeatureTranslation.h>
64#include <visp3/vs/vpServo.h>
65#include <visp3/vs/vpServoDisplay.h>
67#ifdef ENABLE_VISP_NAMESPACE
72 const std::vector<vpImagePoint> &vip,
73 std::vector<vpImagePoint> *traj_vip)
75 for (
size_t i = 0;
i < vip.size(); ++
i) {
76 if (traj_vip[i].size()) {
79 traj_vip[
i].push_back(vip[i]);
83 traj_vip[
i].push_back(vip[i]);
86 for (
size_t i = 0;
i < vip.size(); ++
i) {
87 for (
size_t j = 1;
j < traj_vip[
i].size(); ++
j) {
93int main(
int argc,
char **argv)
95 double opt_tagSize = 0.120;
96 int opt_quad_decimate = 2;
97 bool opt_verbose =
false;
98 bool opt_plot =
false;
99 bool opt_adaptive_gain =
false;
100 bool opt_task_sequencing =
false;
101 double opt_convergence_threshold_t = 0.0005;
102 double opt_convergence_threshold_tu = 0.5;
104 bool display_tag =
true;
106 for (
int i = 1;
i < argc; ++
i) {
107 if ((std::string(argv[i]) ==
"--tag-size") && (i + 1 < argc)) {
108 opt_tagSize = std::stod(argv[++i]);
110 else if ((std::string(argv[i]) ==
"--tag-quad-decimate") && (i + 1 < argc)) {
111 opt_quad_decimate = std::stoi(argv[++i]);
113 else if (std::string(argv[i]) ==
"--verbose") {
116 else if (std::string(argv[i]) ==
"--plot") {
119 else if (std::string(argv[i]) ==
"--adaptive-gain") {
120 opt_adaptive_gain =
true;
122 else if (std::string(argv[i]) ==
"--task-sequencing") {
123 opt_task_sequencing =
true;
125 else if (std::string(argv[i]) ==
"--no-convergence-threshold") {
126 opt_convergence_threshold_t = 0.;
127 opt_convergence_threshold_tu = 0.;
129 else if ((std::string(argv[i]) ==
"--help") || (std::string(argv[i]) ==
"-h")) {
132 <<
" [--tag-size <marker size in meter; default " << opt_tagSize <<
">]"
133 <<
" [--tag-quad-decimate <decimation; default " << opt_quad_decimate <<
">]"
134 <<
" [--adaptive-gain]"
136 <<
" [--task-sequencing]"
137 <<
" [--no-convergence-threshold]"
153 std::cout <<
"WARNING: This example will move the robot! "
154 <<
"Please make sure to have the user stop button at hand!" << std::endl
155 <<
"Press Enter to continue..." << std::endl;
161 config.enable_stream(RS2_STREAM_COLOR, width, height, RS2_FORMAT_RGBA8, fps);
162 config.enable_stream(RS2_STREAM_DEPTH, width, height, RS2_FORMAT_Z16, fps);
163 config.enable_stream(RS2_STREAM_INFRARED, width, height, RS2_FORMAT_Y8, fps);
168 for (
size_t i = 0;
i < 10; ++
i) {
174 robot.getCameraParameters(cam, I);
175 std::cout <<
"cam:\n" <<
cam << std::endl;
183 detector.setAprilTagPoseEstimationMethod(poseEstimationMethod);
184 detector.setDisplayTag(display_tag);
185 detector.setAprilTagQuadDecimate(opt_quad_decimate);
186 detector.setZAlignedWithCameraAxis(
true);
237 if (!detector.isZAlignedWithCameraAxis()) {
245 cd_M_c = cd_M_o * c_M_o.
inverse();
250 s_t.buildFrom(cd_M_c);
251 s_tu.buildFrom(cd_M_c);
258 task.addFeature(s_t, s_t_d);
259 task.addFeature(s_tu, s_tu_d);
264 if (opt_adaptive_gain) {
266 task.setLambda(lambda);
276 plotter =
new vpPlot(2,
static_cast<int>(250 * 2), 500,
static_cast<int>(I.getWidth()) + 80, 10,
277 "Real time curves plotter");
278 plotter->setTitle(0,
"Visual features error");
279 plotter->setTitle(1,
"Camera velocities");
282 plotter->setLegend(0, 0,
"error_feat_tx");
283 plotter->setLegend(0, 1,
"error_feat_ty");
284 plotter->setLegend(0, 2,
"error_feat_tz");
285 plotter->setLegend(0, 3,
"error_feat_theta_ux");
286 plotter->setLegend(0, 4,
"error_feat_theta_uy");
287 plotter->setLegend(0, 5,
"error_feat_theta_uz");
288 plotter->setLegend(1, 0,
"vc_x");
289 plotter->setLegend(1, 1,
"vc_y");
290 plotter->setLegend(1, 2,
"vc_z");
291 plotter->setLegend(1, 3,
"wc_x");
292 plotter->setLegend(1, 4,
"wc_y");
293 plotter->setLegend(1, 5,
"wc_z");
296 bool final_quit =
false;
297 bool has_converged =
false;
298 bool send_velocities =
false;
299 bool servo_started =
false;
300 std::vector<vpImagePoint> *traj_vip =
nullptr;
306 while (!has_converged && !final_quit) {
313 std::vector<vpHomogeneousMatrix> c_M_o_vec;
314 detector.detect(I, opt_tagSize, cam, c_M_o_vec);
316 std::stringstream ss;
317 ss <<
"Left click to " << (send_velocities ?
"stop the robot" :
"servo the robot") <<
", right click to quit.";
323 if (c_M_o_vec.size() == 1) {
324 c_M_o = c_M_o_vec[0];
326 static bool first_time =
true;
329 std::vector<vpHomogeneousMatrix> v_o_M_o(2), v_cd_M_c(2);
330 v_o_M_o[1].buildFrom(0, 0, 0, 0, 0, M_PI);
331 for (
size_t i = 0;
i < 2; ++
i) {
332 v_cd_M_c[
i] = cd_M_o * v_o_M_o[
i] * c_M_o.
inverse();
334 if (std::fabs(v_cd_M_c[0].getThetaUVector().getTheta()) < std::fabs(v_cd_M_c[1].getThetaUVector().getTheta())) {
338 std::cout <<
"Desired frame modified to avoid PI rotation of the camera" << std::endl;
344 cd_M_c = cd_M_o * o_M_o * c_M_o.
inverse();
348 if (opt_task_sequencing) {
349 if (!servo_started) {
350 if (send_velocities) {
351 servo_started =
true;
358 v_c =
task.computeControlLaw();
365 std::vector<vpImagePoint> vip = detector.getPolygon(0);
367 vip.push_back(detector.getCog(0));
370 traj_vip =
new std::vector<vpImagePoint>[vip.size()];
372 display_point_trajectory(I, vip, traj_vip);
376 plotter->plot(1, iter_plot, v_c);
381 std::cout <<
"v_c: " << v_c.t() << std::endl;
386 double error_tr = sqrt(cd_t_c.
sumSquare());
390 ss <<
"error_t: " << error_tr;
393 ss <<
"error_tu: " << error_tu;
397 std::cout <<
"error translation: " << error_tr <<
" ; error rotation: " << error_tu << std::endl;
399 if ((error_tr < opt_convergence_threshold_t) && (error_tu < opt_convergence_threshold_tu)) {
400 has_converged =
true;
401 std::cout <<
"Servo task has converged" << std::endl;
414 if (!send_velocities) {
430 send_velocities = !send_velocities;
442 std::cout <<
"Stop the robot " << std::endl;
445 if (opt_plot && plotter !=
nullptr) {
451 while (!final_quit) {
471 std::cout <<
"ViSP exception: " <<
e.what() << std::endl;
472 std::cout <<
"Stop the robot " << std::endl;
482#if !defined(VISP_HAVE_REALSENSE2)
483 std::cout <<
"Install librealsense-2.x" << std::endl;
485#if !defined(VISP_HAVE_AFMA6)
486 std::cout <<
"ViSP is not build with Afma-6 robot support..." << std::endl;
Adaptive gain computation.
Generic class defining intrinsic camera parameters.
vpCameraParametersProjType
@ perspectiveProjWithDistortion
Perspective projection with distortion model.
Implementation of column vector and the associated operations.
static const vpColor none
static const vpColor yellow
static const vpColor green
@ TAG_36h11
AprilTag 36h11 pattern (recommended).
static bool getClick(const vpImage< unsigned char > &I, bool blocking=true)
static void display(const vpImage< unsigned char > &I)
static void displayLine(const vpImage< unsigned char > &I, const vpImagePoint &ip1, const vpImagePoint &ip2, const vpColor &color, unsigned int thickness=1, bool segment=true)
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 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.
Class that defines a 3D visual feature from a axis/angle parametrization that represent the rotati...
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
static double distance(const vpImagePoint &iP1, const vpImagePoint &iP2)
Definition of the vpImage class member functions.
static double rad(double deg)
static double deg(double rad)
This class enables real time drawing of 2D or 3D graphics. An instance of the class open a window whi...
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.
@ STATE_VELOCITY_CONTROL
Initialize the velocity controller.
@ STATE_STOP
Stops robot motion especially in velocity and acceleration control.
Implementation of a rotation vector as axis-angle minimal representation.
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.
VISP_EXPORT double measureTimeMs()