56#include <visp3/core/vpConfig.h>
58#if defined(VISP_HAVE_REALSENSE2) && defined(VISP_HAVE_DISPLAY) && defined(VISP_HAVE_UR_RTDE)
60#include <visp3/core/vpCameraParameters.h>
61#include <visp3/detection/vpDetectorAprilTag.h>
62#include <visp3/gui/vpDisplayFactory.h>
63#include <visp3/gui/vpPlot.h>
64#include <visp3/io/vpImageIo.h>
65#include <visp3/robot/vpRobotUniversalRobots.h>
66#include <visp3/sensor/vpRealSense2.h>
67#include <visp3/visual_features/vpFeatureThetaU.h>
68#include <visp3/visual_features/vpFeatureTranslation.h>
69#include <visp3/vs/vpServo.h>
70#include <visp3/vs/vpServoDisplay.h>
72#ifdef ENABLE_VISP_NAMESPACE
77 std::vector<vpImagePoint> *traj_vip)
79 for (
size_t i = 0;
i < vip.size();
i++) {
80 if (traj_vip[i].size()) {
83 traj_vip[
i].push_back(vip[i]);
87 traj_vip[
i].push_back(vip[i]);
90 for (
size_t i = 0;
i < vip.size();
i++) {
91 for (
size_t j = 1;
j < traj_vip[
i].size();
j++) {
97int main(
int argc,
char **argv)
99 double opt_tagSize = 0.120;
100 std::string opt_robot_ip =
"192.168.0.100";
101 std::string opt_eMc_filename =
"";
102 bool display_tag =
true;
103 int opt_quad_decimate = 2;
104 bool opt_verbose =
false;
105 bool opt_plot =
false;
106 bool opt_adaptive_gain =
false;
107 bool opt_task_sequencing =
false;
108 double convergence_threshold_t = 0.0005;
109 double convergence_threshold_tu = 0.5;
111 for (
int i = 1;
i < argc;
i++) {
112 if (std::string(argv[i]) ==
"--tag-size" && i + 1 < argc) {
113 opt_tagSize = std::stod(argv[++i]);
115 else if (std::string(argv[i]) ==
"--tag-quad-decimate" && i + 1 < argc) {
116 opt_quad_decimate = std::stoi(argv[++i]);
118 else if (std::string(argv[i]) ==
"--ip" && i + 1 < argc) {
119 opt_robot_ip = std::string(argv[++i]);
121 else if (std::string(argv[i]) ==
"--eMc" && i + 1 < argc) {
122 opt_eMc_filename = std::string(argv[++i]);
124 else if (std::string(argv[i]) ==
"--verbose") {
127 else if (std::string(argv[i]) ==
"--plot") {
130 else if (std::string(argv[i]) ==
"--adpative-gain") {
131 opt_adaptive_gain =
true;
133 else if (std::string(argv[i]) ==
"--task-sequencing") {
134 opt_task_sequencing =
true;
136 else if (std::string(argv[i]) ==
"--no-convergence-threshold") {
137 convergence_threshold_t = 0.;
138 convergence_threshold_tu = 0.;
140 else if (std::string(argv[i]) ==
"--help" || std::string(argv[i]) ==
"-h") {
142 << argv[0] <<
" [--ip <default " << opt_robot_ip <<
">] [--tag-size <marker size in meter; default "
143 << opt_tagSize <<
">] [--eMc <eMc extrinsic file>] "
144 <<
"[--tag-quad-decimate <decimation; default " << opt_quad_decimate
145 <<
">] [--adpative-gain] [--plot] [--task-sequencing] [--no-convergence-threshold] [--verbose] [--help] [-h]"
153#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
154 std::shared_ptr<vpDisplay> display;
160 robot.connect(opt_robot_ip);
162 std::cout <<
"WARNING: This example will move the robot! "
163 <<
"Please make sure to have the user stop button at hand!" << std::endl
164 <<
"Press Enter to continue..." << std::endl;
177 std::cout <<
"Move to joint position: " << q.t() << std::endl;
184 config.enable_stream(RS2_STREAM_COLOR, 640, 480, RS2_FORMAT_RGBA8, 30);
185 config.enable_stream(RS2_STREAM_DEPTH, 640, 480, RS2_FORMAT_Z16, 30);
186 config.enable_stream(RS2_STREAM_INFRARED, 640, 480, RS2_FORMAT_Y8, 30);
195 ePc[3] = -0.00506562;
196 ePc[4] = -0.00293325;
200 if (!opt_eMc_filename.empty()) {
201 ePc.
loadYAML(opt_eMc_filename, ePc);
204 std::cout <<
"Warning, opt_eMc_filename is empty! Use hard coded values."
208 std::cout <<
"eMc:\n" << eMc <<
"\n";
213 std::cout <<
"cam:\n" <<
cam <<
"\n";
217#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
227 detector.setAprilTagPoseEstimationMethod(poseEstimationMethod);
228 detector.setDisplayTag(display_tag);
229 detector.setAprilTagQuadDecimate(opt_quad_decimate);
238 cdMc = cdMo *
cMo.inverse();
248 task.addFeature(t, td);
249 task.addFeature(tu, tud);
253 if (opt_adaptive_gain) {
255 task.setLambda(lambda);
265 plotter =
new vpPlot(2,
static_cast<int>(250 * 2), 500,
static_cast<int>(I.getWidth()) + 80, 10,
266 "Real time curves plotter");
267 plotter->setTitle(0,
"Visual features error");
268 plotter->setTitle(1,
"Camera velocities");
271 plotter->setLegend(0, 0,
"error_feat_tx");
272 plotter->setLegend(0, 1,
"error_feat_ty");
273 plotter->setLegend(0, 2,
"error_feat_tz");
274 plotter->setLegend(0, 3,
"error_feat_theta_ux");
275 plotter->setLegend(0, 4,
"error_feat_theta_uy");
276 plotter->setLegend(0, 5,
"error_feat_theta_uz");
277 plotter->setLegend(1, 0,
"vc_x");
278 plotter->setLegend(1, 1,
"vc_y");
279 plotter->setLegend(1, 2,
"vc_z");
280 plotter->setLegend(1, 3,
"wc_x");
281 plotter->setLegend(1, 4,
"wc_y");
282 plotter->setLegend(1, 5,
"wc_z");
285 bool final_quit =
false;
286 bool has_converged =
false;
287 bool send_velocities =
false;
288 bool servo_started =
false;
289 std::vector<vpImagePoint> *traj_vip =
nullptr;
296 while (!has_converged && !final_quit) {
303 std::vector<vpHomogeneousMatrix> cMo_vec;
304 detector.detect(I, opt_tagSize, cam, cMo_vec);
306 std::stringstream ss;
307 ss <<
"Left click to " << (send_velocities ?
"stop the robot" :
"servo the robot") <<
", right click to quit.";
313 if (cMo_vec.size() == 1) {
316 static bool first_time =
true;
319 std::vector<vpHomogeneousMatrix> v_oMo(2), v_cdMc(2);
320 v_oMo[1].buildFrom(0, 0, 0, 0, 0, M_PI);
321 for (
size_t i = 0;
i < 2;
i++) {
322 v_cdMc[
i] = cdMo * v_oMo[
i] *
cMo.inverse();
324 if (std::fabs(v_cdMc[0].getThetaUVector().getTheta()) < std::fabs(v_cdMc[1].getThetaUVector().getTheta())) {
328 std::cout <<
"Desired frame modified to avoid PI rotation of the camera" << std::endl;
334 cdMc = cdMo * oMo *
cMo.inverse();
338 if (opt_task_sequencing) {
339 if (!servo_started) {
340 if (send_velocities) {
341 servo_started =
true;
348 v_c =
task.computeControlLaw();
355 std::vector<vpImagePoint> vip = detector.getPolygon(0);
357 vip.push_back(detector.getCog(0));
360 traj_vip =
new std::vector<vpImagePoint>[vip.size()];
362 display_point_trajectory(I, vip, traj_vip);
366 plotter->plot(1, iter_plot, v_c);
371 std::cout <<
"v_c: " << v_c.t() << std::endl;
376 double error_tr = sqrt(cd_t_c.
sumSquare());
380 ss <<
"error_t: " << error_tr;
383 ss <<
"error_tu: " << error_tu;
387 std::cout <<
"error translation: " << error_tr <<
" ; error rotation: " << error_tu << std::endl;
389 if (error_tr < convergence_threshold_t && error_tu < convergence_threshold_tu) {
390 has_converged =
true;
391 std::cout <<
"Servo task has converged" << std::endl;
403 if (!send_velocities) {
419 send_velocities = !send_velocities;
432 std::cout <<
"Stop the robot " << std::endl;
435 if (opt_plot && plotter !=
nullptr) {
441 while (!final_quit) {
461 std::cout <<
"ViSP exception: " <<
e.what() << std::endl;
462 std::cout <<
"Stop the robot " << std::endl;
464#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
465 if (display !=
nullptr) {
471 catch (
const std::exception &e) {
472 std::cout <<
"ur_rtde exception: " <<
e.what() << std::endl;
473#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
474 if (display !=
nullptr) {
481#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
482 if (display !=
nullptr) {
491#if !defined(VISP_HAVE_REALSENSE2)
492 std::cout <<
"Install librealsense-2.x" << std::endl;
494#if !defined(VISP_HAVE_UR_RTDE)
495 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 none
static const vpColor yellow
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 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.
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...
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.
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.
vpDisplay * allocateDisplay()
Return a newly allocated vpDisplay specialization if a GUI library is available or nullptr otherwise.
VISP_EXPORT double measureTimeMs()