59#include <visp3/core/vpConfig.h>
60#include <visp3/core/vpCameraParameters.h>
61#include <visp3/core/vpIoTools.h>
62#include <visp3/core/vpXmlParserCamera.h>
63#include <visp3/detection/vpDetectorAprilTag.h>
64#include <visp3/gui/vpDisplayFactory.h>
65#include <visp3/gui/vpPlot.h>
66#include <visp3/io/vpImageIo.h>
67#include <visp3/robot/vpRobotFranka.h>
68#include <visp3/sensor/vpRealSense2.h>
69#include <visp3/visual_features/vpFeatureThetaU.h>
70#include <visp3/visual_features/vpFeatureTranslation.h>
71#include <visp3/vs/vpServo.h>
72#include <visp3/vs/vpServoDisplay.h>
74#if defined(VISP_HAVE_REALSENSE2) && defined(VISP_HAVE_DISPLAY) && defined(VISP_HAVE_FRANKA) && defined(VISP_HAVE_PUGIXML)
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_tag_size = 0.120;
104 bool opt_tag_z_aligned =
false;
105 std::string opt_robot_ip =
"192.168.1.1";
106 std::string opt_eMc_filename =
"";
107 std::string opt_intrinsic_filename =
"";
108 std::string opt_camera_name =
"Camera";
109 bool display_tag =
true;
110 int opt_quad_decimate = 2;
111 bool opt_verbose =
false;
112 bool opt_plot =
false;
113 bool opt_adaptive_gain =
false;
114 bool opt_task_sequencing =
false;
115 double convergence_threshold_t = 0.0005;
116 double convergence_threshold_tu = 0.5;
118 for (
int i = 1;
i < argc; ++
i) {
119 if ((std::string(argv[i]) ==
"--tag-size") && (i + 1 < argc)) {
120 opt_tag_size = std::stod(argv[++i]);
122 else if ((std::string(argv[i]) ==
"--tag-quad-decimate") && (i + 1 < argc)) {
123 opt_quad_decimate = std::stoi(argv[++i]);
125 else if (std::string(argv[i]) ==
"--tag-z-aligned") {
126 opt_tag_z_aligned =
true;
128 else if ((std::string(argv[i]) ==
"--ip") && (i + 1 < argc)) {
129 opt_robot_ip = std::string(argv[++i]);
131 else if (std::string(argv[i]) ==
"--intrinsic" && i + 1 < argc) {
132 opt_intrinsic_filename = std::string(argv[++i]);
134 else if (std::string(argv[i]) ==
"--camera-name" && i + 1 < argc) {
135 opt_camera_name = std::string(argv[++i]);
137 else if ((std::string(argv[i]) ==
"--eMc") && (i + 1 < argc)) {
138 opt_eMc_filename = std::string(argv[++i]);
140 else if (std::string(argv[i]) ==
"--verbose") {
143 else if (std::string(argv[i]) ==
"--plot") {
146 else if (std::string(argv[i]) ==
"--adaptive-gain") {
147 opt_adaptive_gain =
true;
149 else if (std::string(argv[i]) ==
"--task-sequencing") {
150 opt_task_sequencing =
true;
152 else if (std::string(argv[i]) ==
"--no-convergence-threshold") {
153 convergence_threshold_t = 0.;
154 convergence_threshold_tu = 0.;
156 else if ((std::string(argv[i]) ==
"--help") || (std::string(argv[i]) ==
"-h")) {
157 std::cout <<
"SYNOPSYS" << std::endl
159 <<
" [--ip <controller ip>]"
160 <<
" [--intrinsic <xml file>]"
161 <<
" [--camera-name <name>]"
162 <<
" [--tag-size <size>]"
163 <<
" [--tag-quad-decimate <decimation factor>]"
164 <<
" [--tag-z-aligned]"
165 <<
" [--eMc <extrinsic transformation file>]"
166 <<
" [--adaptive-gain]"
168 <<
" [--task-sequencing]"
169 <<
" [--no-convergence-threshold]"
171 <<
" [--help] [-h]\n"
173 std::cout <<
"DESCRIPTION" << std::endl
174 <<
" Use a position-based visual-servoing scheme to position the camera in front of an Apriltag." << std::endl
176 <<
" --ip <controller ip>" << std::endl
177 <<
" Franka controller ip address" << std::endl
178 <<
" Default: " << opt_robot_ip << std::endl
180 <<
" --intrinsic <xml file>" << std::endl
181 <<
" XML file that contains camera intrinsic parameters. " << std::endl
182 <<
" If no file is specified, use Realsense camera factory intrinsic parameters." << std::endl
184 <<
" --camera-name <name>" << std::endl
185 <<
" Camera name in the XML file that contains camera intrinsic parameters." << std::endl
186 <<
" Default: \"Camera\"" << std::endl
188 <<
" --tag-size <size>" << std::endl
189 <<
" Apriltag size in [m]." << std::endl
190 <<
" Default: " << opt_tag_size <<
" [m]" << std::endl
192 <<
" --tag-quad-decimate <decimation factor>" << std::endl
193 <<
" Decimation factor used during Apriltag detection." << std::endl
194 <<
" Default: " << opt_quad_decimate << std::endl
196 <<
" --tag-z-aligned" << std::endl
197 <<
" When enabled, tag z-axis and camera z-axis are aligned." << std::endl
198 <<
" Default: false" << std::endl
200 <<
" --eMc <extrinsic transformation file>" << std::endl
201 <<
" File containing the homogeneous transformation matrix between" << std::endl
202 <<
" robot end-effector and camera frame." << std::endl
204 <<
" --adaptive-gain" << std::endl
205 <<
" Flag to enable adaptive gain to speed up visual servo near convergence." << std::endl
207 <<
" --plot" << std::endl
208 <<
" Flag to enable curve plotter." << std::endl
210 <<
" --task-sequencing" << std::endl
211 <<
" Flag to enable task sequencing scheme." << std::endl
213 <<
" --no-convergence-threshold" << std::endl
214 <<
" Flag to disable convergence threshold used to stop the visual servo." << std::endl
216 <<
" --verbose" << std::endl
217 <<
" Flag to enable extra verbosity." << std::endl
219 <<
" --help, -h" << std::endl
220 <<
" Print this helper message." << std::endl
225 std::cout <<
"\nERROR" << std::endl
226 << std::string(argv[i]) <<
" command line option is not supported." << std::endl
227 <<
"Use " << std::string(argv[0]) <<
" --help" << std::endl
236 config.enable_stream(RS2_STREAM_COLOR, 640, 480, RS2_FORMAT_RGBA8, 30);
237 config.enable_stream(RS2_STREAM_DEPTH, 640, 480, RS2_FORMAT_Z16, 30);
238 config.enable_stream(RS2_STREAM_INFRARED, 640, 480, RS2_FORMAT_Y8, 30);
243#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
249 std::cout <<
"Parameters:" << std::endl;
250 std::cout <<
" Apriltag " << std::endl;
251 std::cout <<
" Size [m] : " << opt_tag_size << std::endl;
252 std::cout <<
" Z aligned : " << (opt_tag_z_aligned ?
"true" :
"false") << std::endl;
253 std::cout <<
" Camera intrinsics " << std::endl;
254 std::cout <<
" Factory parameters : " << (opt_intrinsic_filename.empty() ?
"yes" :
"no") << std::endl;
258 if (opt_intrinsic_filename.empty()) {
259 std::cout <<
"Use Realsense camera intrinsic factory parameters: " << std::endl;
261 std::cout <<
"cam:\n" <<
cam << std::endl;
264 std::cout <<
"Camera parameters file " << opt_intrinsic_filename <<
" doesn't exist." << std::endl;
269 if (!opt_camera_name.empty()) {
271 std::cout <<
" Param file name [.xml]: " << opt_intrinsic_filename << std::endl;
272 std::cout <<
" Camera name : " << opt_camera_name << std::endl;
276 std::cout <<
"Unable to parse parameters with distortion for camera \"" << opt_camera_name <<
"\" from "
277 << opt_intrinsic_filename <<
" file" << std::endl;
278 std::cout <<
"Attempt to find parameters without distortion" << std::endl;
280 if (
parser.parse(cam, opt_intrinsic_filename, opt_camera_name,
282 std::cout <<
"Unable to parse parameters without distortion for camera \"" << opt_camera_name <<
"\" from "
283 << opt_intrinsic_filename <<
" file" << std::endl;
290 std::cout <<
"Camera parameters used to compute the pose:\n" <<
cam << std::endl;
297 detector.setAprilTagPoseEstimationMethod(poseEstimationMethod);
298 detector.setDisplayTag(display_tag);
299 detector.setAprilTagQuadDecimate(opt_quad_decimate);
300 detector.setZAlignedWithCameraAxis(opt_tag_z_aligned);
305 e_P_c[0] = 0.0337731;
306 e_P_c[1] = -0.00535012;
307 e_P_c[2] = -0.0523339;
308 e_P_c[3] = -0.247294;
309 e_P_c[4] = -0.306729;
313 if (!opt_eMc_filename.empty()) {
314 e_P_c.
loadYAML(opt_eMc_filename, e_P_c);
317 std::cout <<
"Warning, opt_eMc_filename is empty! Use hard coded values." << std::endl;
320 std::cout <<
"e_M_c:\n" << e_M_c << std::endl;
329 robot.connect(opt_robot_ip);
340 task.addFeature(t, td);
341 task.addFeature(tu, tud);
345 if (opt_adaptive_gain) {
347 task.setLambda(lambda);
357 plotter =
new vpPlot(2,
static_cast<int>(250 * 2), 500,
static_cast<int>(I.getWidth()) + 80, 10,
358 "Real time curves plotter");
359 plotter->setTitle(0,
"Visual features error");
360 plotter->setTitle(1,
"Camera velocities");
363 plotter->setLegend(0, 0,
"error_feat_tx");
364 plotter->setLegend(0, 1,
"error_feat_ty");
365 plotter->setLegend(0, 2,
"error_feat_tz");
366 plotter->setLegend(0, 3,
"error_feat_theta_ux");
367 plotter->setLegend(0, 4,
"error_feat_theta_uy");
368 plotter->setLegend(0, 5,
"error_feat_theta_uz");
369 plotter->setLegend(1, 0,
"vc_x");
370 plotter->setLegend(1, 1,
"vc_y");
371 plotter->setLegend(1, 2,
"vc_z");
372 plotter->setLegend(1, 3,
"wc_x");
373 plotter->setLegend(1, 4,
"wc_y");
374 plotter->setLegend(1, 5,
"wc_z");
377 bool final_quit =
false;
378 bool has_converged =
false;
379 bool send_velocities =
false;
380 bool servo_started =
false;
381 std::vector<vpImagePoint> *traj_vip =
nullptr;
385 robot.set_eMc(e_M_c);
390 while (!has_converged && !final_quit) {
397 std::vector<vpHomogeneousMatrix> c_M_o_vec;
398 bool ret = detector.detect(I, opt_tag_size, cam, c_M_o_vec);
400 std::stringstream ss;
401 ss <<
"Left click to " << (send_velocities ?
"stop the robot" :
"servo the robot") <<
", right click to quit.";
407 if (ret && (c_M_o_vec.size() == 1)) {
408 c_M_o = c_M_o_vec[0];
410 static bool first_time =
true;
413 std::vector<vpHomogeneousMatrix> secure_o_M_o(2), secure_cd_M_c(2);
414 secure_o_M_o[1].buildFrom(0, 0, 0, 0, 0, M_PI);
415 for (
size_t i = 0;
i < 2; ++
i) {
416 secure_cd_M_c[
i] = cd_M_o * secure_o_M_o[
i] * c_M_o.
inverse();
418 if (std::fabs(secure_cd_M_c[0].getThetaUVector().getTheta()) < std::fabs(secure_cd_M_c[1].getThetaUVector().getTheta())) {
419 o_M_o = secure_o_M_o[0];
422 std::cout <<
"Desired frame modified to avoid PI rotation of the camera" << std::endl;
423 o_M_o = secure_o_M_o[1];
428 cd_M_c = cd_M_o * o_M_o * c_M_o.
inverse();
430 tu.buildFrom(cd_M_c);
432 if (opt_task_sequencing) {
433 if (!servo_started) {
434 if (send_velocities) {
435 servo_started =
true;
442 v_c =
task.computeControlLaw();
449 std::vector<vpImagePoint> vip = detector.getPolygon(0);
451 vip.push_back(detector.getCog(0));
454 traj_vip =
new std::vector<vpImagePoint>[vip.size()];
456 display_point_trajectory(I, vip, traj_vip);
460 plotter->plot(1, iter_plot, v_c);
465 std::cout <<
"v_c: " << v_c.t() << std::endl;
470 double error_tr = sqrt(cd_t_c.
sumSquare());
474 ss <<
"error_t: " << error_tr;
477 ss <<
"error_tu: " << error_tu;
481 std::cout <<
"error translation: " << error_tr <<
" ; error rotation: " << error_tu << std::endl;
483 if (error_tr < convergence_threshold_t && error_tu < convergence_threshold_tu) {
484 has_converged =
true;
485 std::cout <<
"Servo task has converged" << std::endl;
498 if (!send_velocities) {
514 send_velocities = !send_velocities;
527 std::cout <<
"Stop the robot " << std::endl;
530 if (opt_plot && plotter !=
nullptr) {
536 while (!final_quit) {
556 std::cout <<
"ViSP exception: " <<
e.what() << std::endl;
557 std::cout <<
"Stop the robot " << std::endl;
559#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
560 if (display !=
nullptr) {
566 catch (
const franka::NetworkException &e) {
567 std::cout <<
"Franka network exception: " <<
e.what() << std::endl;
568 std::cout <<
"Check if you are connected to the Franka robot"
569 <<
" or if you specified the right IP using --ip command line option set by default to 192.168.1.1. "
571#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
572 if (display !=
nullptr) {
578 catch (
const std::exception &e) {
579 std::cout <<
"Franka exception: " <<
e.what() << std::endl;
580#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
581 if (display !=
nullptr) {
588#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
589 if (display !=
nullptr) {
598#if !defined(VISP_HAVE_REALSENSE2)
599 std::cout <<
"Install librealsense-2.x and rebuild ViSP." << std::endl;
601#if !defined(VISP_HAVE_FRANKA)
602 std::cout <<
"Install libfranka and rebuild ViSP." << std::endl;
604#if !defined(VISP_HAVE_PUGIXML)
605 std::cout <<
"Build ViSP with pugixml support enabled." << std::endl;
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.
@ perspectiveProjWithoutDistortion
Perspective projection without 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.
vpThetaUVector getThetaUVector() const
vpHomogeneousMatrix inverse() const
vpTranslationVector getTranslationVector() const
static double distance(const vpImagePoint &iP1, const vpImagePoint &iP2)
Definition of the vpImage class member functions.
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_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.
XML parser to load and save intrinsic camera parameters.
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()