60#include <visp3/core/vpConfig.h>
62#if defined(VISP_HAVE_REALSENSE2) && defined(VISP_HAVE_DISPLAY) && defined(VISP_HAVE_UR_RTDE)
64#include <visp3/core/vpCameraParameters.h>
65#include <visp3/detection/vpDetectorAprilTag.h>
66#include <visp3/gui/vpDisplayFactory.h>
67#include <visp3/gui/vpPlot.h>
68#include <visp3/io/vpImageIo.h>
69#include <visp3/robot/vpRobotUniversalRobots.h>
70#include <visp3/sensor/vpRealSense2.h>
71#include <visp3/visual_features/vpFeatureBuilder.h>
72#include <visp3/visual_features/vpFeaturePoint.h>
73#include <visp3/vs/vpServo.h>
74#include <visp3/vs/vpServoDisplay.h>
76#ifdef ENABLE_VISP_NAMESPACE
81 std::vector<vpImagePoint> *traj_vip)
83 for (
size_t i = 0;
i < vip.size();
i++) {
84 if (traj_vip[i].size()) {
87 traj_vip[
i].push_back(vip[i]);
91 traj_vip[
i].push_back(vip[i]);
94 for (
size_t i = 0;
i < vip.size();
i++) {
95 for (
size_t j = 1;
j < traj_vip[
i].size();
j++) {
101int main(
int argc,
char **argv)
103 double opt_tagSize = 0.120;
104 std::string opt_robot_ip =
"192.168.0.100";
105 std::string opt_eMc_filename =
"";
106 bool display_tag =
true;
107 int opt_quad_decimate = 2;
108 bool opt_verbose =
false;
109 bool opt_plot =
false;
110 bool opt_adaptive_gain =
false;
111 bool opt_task_sequencing =
false;
112 double convergence_threshold = 0.00005;
114 for (
int i = 1;
i < argc;
i++) {
115 if (std::string(argv[i]) ==
"--tag-size" && i + 1 < argc) {
116 opt_tagSize = std::stod(argv[++i]);
118 else if (std::string(argv[i]) ==
"--tag-quad-decimate" && i + 1 < argc) {
119 opt_quad_decimate = std::stoi(argv[++i]);
121 else if (std::string(argv[i]) ==
"--ip" && i + 1 < argc) {
122 opt_robot_ip = std::string(argv[++i]);
124 else if (std::string(argv[i]) ==
"--eMc" && i + 1 < argc) {
125 opt_eMc_filename = std::string(argv[++i]);
127 else if (std::string(argv[i]) ==
"--verbose") {
130 else if (std::string(argv[i]) ==
"--plot") {
133 else if (std::string(argv[i]) ==
"--adpative-gain") {
134 opt_adaptive_gain =
true;
136 else if (std::string(argv[i]) ==
"--task-sequencing") {
137 opt_task_sequencing =
true;
139 else if (std::string(argv[i]) ==
"--no-convergence-threshold") {
140 convergence_threshold = 0.;
142 else if (std::string(argv[i]) ==
"--help" || std::string(argv[i]) ==
"-h") {
144 << argv[0] <<
" [--ip <default " << opt_robot_ip <<
">] [--tag-size <marker size in meter; default "
145 << opt_tagSize <<
">] [--eMc <eMc extrinsic file>] "
146 <<
"[--tag-quad-decimate <decimation; default " << opt_quad_decimate
147 <<
">] [--adpative-gain] [--plot] [--task-sequencing] [--no-convergence-threshold] [--verbose] [--help] [-h]"
155#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
156 std::shared_ptr<vpDisplay> display;
161 robot.connect(opt_robot_ip);
163 std::cout <<
"WARNING: This example will move the robot! "
164 <<
"Please make sure to have the user stop button at hand!" << std::endl
165 <<
"Press Enter to continue..." << std::endl;
178 std::cout <<
"Move to joint position: " << q.t() << std::endl;
185 config.enable_stream(RS2_STREAM_COLOR, 640, 480, RS2_FORMAT_RGBA8, 30);
186 config.enable_stream(RS2_STREAM_DEPTH, 640, 480, RS2_FORMAT_Z16, 30);
187 config.enable_stream(RS2_STREAM_INFRARED, 640, 480, RS2_FORMAT_Y8, 30);
196 ePc[3] = -0.00506562;
197 ePc[4] = -0.00293325;
201 if (!opt_eMc_filename.empty()) {
202 ePc.
loadYAML(opt_eMc_filename, ePc);
205 std::cout <<
"Warning, opt_eMc_filename is empty! Use hard coded values."
209 std::cout <<
"eMc:\n" << eMc <<
"\n";
214 std::cout <<
"cam:\n" <<
cam <<
"\n";
218#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
228 detector.setAprilTagPoseEstimationMethod(poseEstimationMethod);
229 detector.setDisplayTag(display_tag);
230 detector.setAprilTagQuadDecimate(opt_quad_decimate);
240 std::vector<vpFeaturePoint>
p(4), pd(4);
243 std::vector<vpPoint> point(4);
244 point[0].setWorldCoordinates(-opt_tagSize / 2., -opt_tagSize / 2., 0);
245 point[1].setWorldCoordinates(opt_tagSize / 2., -opt_tagSize / 2., 0);
246 point[2].setWorldCoordinates(opt_tagSize / 2., opt_tagSize / 2., 0);
247 point[3].setWorldCoordinates(-opt_tagSize / 2., opt_tagSize / 2., 0);
251 for (
size_t i = 0;
i <
p.size();
i++) {
252 task.addFeature(p[i], pd[i]);
257 if (opt_adaptive_gain) {
259 task.setLambda(lambda);
269 plotter =
new vpPlot(2,
static_cast<int>(250 * 2), 500,
static_cast<int>(I.getWidth()) + 80, 10,
270 "Real time curves plotter");
271 plotter->setTitle(0,
"Visual features error");
272 plotter->setTitle(1,
"Camera velocities");
275 plotter->setLegend(0, 0,
"error_feat_p1_x");
276 plotter->setLegend(0, 1,
"error_feat_p1_y");
277 plotter->setLegend(0, 2,
"error_feat_p2_x");
278 plotter->setLegend(0, 3,
"error_feat_p2_y");
279 plotter->setLegend(0, 4,
"error_feat_p3_x");
280 plotter->setLegend(0, 5,
"error_feat_p3_y");
281 plotter->setLegend(0, 6,
"error_feat_p4_x");
282 plotter->setLegend(0, 7,
"error_feat_p4_y");
283 plotter->setLegend(1, 0,
"vc_x");
284 plotter->setLegend(1, 1,
"vc_y");
285 plotter->setLegend(1, 2,
"vc_z");
286 plotter->setLegend(1, 3,
"wc_x");
287 plotter->setLegend(1, 4,
"wc_y");
288 plotter->setLegend(1, 5,
"wc_z");
291 bool final_quit =
false;
292 bool has_converged =
false;
293 bool send_velocities =
false;
294 bool servo_started =
false;
295 std::vector<vpImagePoint> *traj_corners =
nullptr;
302 while (!has_converged && !final_quit) {
309 std::vector<vpHomogeneousMatrix> cMo_vec;
310 detector.detect(I, opt_tagSize, cam, cMo_vec);
313 std::stringstream ss;
314 ss <<
"Left click to " << (send_velocities ?
"stop the robot" :
"servo the robot") <<
", right click to quit.";
321 if (cMo_vec.size() == 1) {
324 static bool first_time =
true;
327 std::vector<vpHomogeneousMatrix> v_oMo(2), v_cdMc(2);
328 v_oMo[1].buildFrom(0, 0, 0, 0, 0, M_PI);
329 for (
size_t i = 0;
i < 2;
i++) {
330 v_cdMc[
i] = cdMo * v_oMo[
i] *
cMo.inverse();
332 if (std::fabs(v_cdMc[0].getThetaUVector().getTheta()) < std::fabs(v_cdMc[1].getThetaUVector().getTheta())) {
336 std::cout <<
"Desired frame modified to avoid PI rotation of the camera" << std::endl;
341 for (
size_t i = 0;
i < point.size();
i++) {
343 point[
i].changeFrame(cdMo * oMo, cP);
344 point[
i].projection(cP, p_);
353 std::vector<vpImagePoint> corners = detector.getPolygon(0);
356 for (
size_t i = 0;
i < corners.size();
i++) {
361 point[
i].changeFrame(cMo, cP);
366 if (opt_task_sequencing) {
367 if (!servo_started) {
368 if (send_velocities) {
369 servo_started =
true;
376 v_c =
task.computeControlLaw();
381 for (
size_t i = 0;
i < corners.size();
i++) {
382 std::stringstream ss;
392 traj_corners =
new std::vector<vpImagePoint>[corners.size()];
395 display_point_trajectory(I, corners, traj_corners);
399 plotter->plot(1, iter_plot, v_c);
404 std::cout <<
"v_c: " << v_c.t() << std::endl;
407 double error =
task.getError().sumSquare();
408 std::stringstream ss;
409 ss <<
"error: " <<
error;
413 std::cout <<
"error: " <<
error << std::endl;
415 if (error < convergence_threshold) {
416 has_converged =
true;
417 std::cout <<
"Servo task has converged"
429 if (!send_velocities) {
437 std::stringstream ss;
447 send_velocities = !send_velocities;
460 std::cout <<
"Stop the robot " << std::endl;
463 if (opt_plot && plotter !=
nullptr) {
469 while (!final_quit) {
484 delete[] traj_corners;
488 std::cout <<
"ViSP exception: " <<
e.what() << std::endl;
489 std::cout <<
"Stop the robot " << std::endl;
491#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
492 if (display !=
nullptr) {
498 catch (
const std::exception &e) {
499 std::cout <<
"ur_rtde exception: " <<
e.what() << std::endl;
500#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
501 if (display !=
nullptr) {
508#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
509 if (display !=
nullptr) {
518#if !defined(VISP_HAVE_REALSENSE2)
519 std::cout <<
"Install librealsense-2.x" << std::endl;
521#if !defined(VISP_HAVE_UR_RTDE)
522 std::cout <<
"ViSP is not build with libur_rtde 3rd party used to control a robot from Universal Robots..."
Adaptive gain computation.
static bool loadYAML(const std::string &filename, vpArray2D< Type > &A, char *header=nullptr)
Generic class defining intrinsic camera parameters.
@ perspectiveProjWithDistortion
Perspective projection with distortion model.
Implementation of column vector and the associated operations.
static const vpColor green
@ TAG_36h11
AprilTag 36h11 pattern (recommended).
Class that defines generic functionalities for display.
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 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.
static void create(vpFeaturePoint &s, const vpCameraParameters &cam, const vpDot &d)
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 ...
static double distance(const vpImagePoint &iP1, const vpImagePoint &iP2)
Definition of the vpImage class member functions.
static double rad(double deg)
static void convertPoint(const vpCameraParameters &cam, const double &x, const double &y, double &u, double &v)
This class enables real time drawing of 2D or 3D graphics. An instance of the class open a window whi...
Implementation of a pose vector and operations on poses.
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())
@ STATE_POSITION_CONTROL
Initialize the position controller.
@ STATE_VELOCITY_CONTROL
Initialize the velocity controller.
@ STATE_STOP
Stops robot motion especially in velocity and acceleration control.
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)
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.
vpDisplay * allocateDisplay()
Return a newly allocated vpDisplay specialization if a GUI library is available or nullptr otherwise.
VISP_EXPORT double measureTimeMs()