70#include <visp3/core/vpConfig.h>
71#include <visp3/core/vpCameraParameters.h>
72#include <visp3/core/vpIoTools.h>
73#include <visp3/core/vpXmlParserCamera.h>
74#include <visp3/detection/vpDetectorAprilTag.h>
75#include <visp3/gui/vpDisplayFactory.h>
76#include <visp3/gui/vpPlot.h>
77#include <visp3/io/vpImageIo.h>
78#include <visp3/robot/vpRobotFranka.h>
79#include <visp3/sensor/vpRealSense2.h>
80#include <visp3/visual_features/vpFeatureBuilder.h>
81#include <visp3/visual_features/vpFeaturePoint.h>
82#include <visp3/vs/vpServo.h>
83#include <visp3/vs/vpServoDisplay.h>
85#if defined(VISP_HAVE_REALSENSE2) && defined(VISP_HAVE_DISPLAY) && defined(VISP_HAVE_FRANKA) && defined(VISP_HAVE_PUGIXML)
87#ifdef ENABLE_VISP_NAMESPACE
91bool save_desired_features(
const std::string &filename,
const std::vector<vpFeaturePoint> &desired_features)
93 std::ofstream file(filename);
95 for (
size_t i = 0;
i < desired_features.size(); ++
i) {
96 file << desired_features[
i].get_x() <<
" " << desired_features[
i].get_y() <<
" " << desired_features[
i].get_Z() << std::endl;
107bool read_desired_features(
const std::string &filename, std::vector<vpFeaturePoint> &desired_features)
109 desired_features.clear();
110 std::ifstream file(filename);
111 if (file.is_open()) {
113 while (std::getline(file, line)) {
114 std::istringstream iss(line);
116 if (!(iss >> x >> y >> Z)) {
121 desired_features.push_back(s_d);
133 std::vector<vpImagePoint> *traj_vip)
135 for (
size_t i = 0;
i < vip.size(); ++
i) {
136 if (traj_vip[i].size()) {
139 traj_vip[
i].push_back(vip[i]);
143 traj_vip[
i].push_back(vip[i]);
146 for (
size_t i = 0;
i < vip.size(); ++
i) {
147 for (
size_t j = 1;
j < traj_vip[
i].size();
j++) {
153int main(
int argc,
char **argv)
155 double opt_tag_size = 0.120;
156 bool opt_tag_z_aligned =
false;
157 std::string opt_robot_ip =
"192.168.1.1";
158 std::string opt_eMo_filename =
"";
159 std::string opt_intrinsic_filename =
"";
160 std::string opt_camera_name =
"Camera";
161 bool display_tag =
true;
162 int opt_quad_decimate = 2;
163 bool opt_verbose =
false;
164 bool opt_plot =
false;
165 bool opt_adaptive_gain =
false;
166 bool opt_task_sequencing =
false;
167 bool opt_learn_desired_features =
false;
168 std::string desired_features_filename =
"learned_desired_features.txt";
169 double convergence_threshold = 0.00005;
171 for (
int i = 1;
i < argc; ++
i) {
172 if ((std::string(argv[i]) ==
"--tag-size") && (i + 1 < argc)) {
173 opt_tag_size = std::stod(argv[++i]);
175 else if ((std::string(argv[i]) ==
"--tag-quad-decimate") && (i + 1 < argc)) {
176 opt_quad_decimate = std::stoi(argv[++i]);
178 else if (std::string(argv[i]) ==
"--tag-z-aligned") {
179 opt_tag_z_aligned =
true;
181 else if ((std::string(argv[i]) ==
"--ip") && (i + 1 < argc)) {
182 opt_robot_ip = std::string(argv[++i]);
184 else if (std::string(argv[i]) ==
"--intrinsic" && i + 1 < argc) {
185 opt_intrinsic_filename = std::string(argv[++i]);
187 else if (std::string(argv[i]) ==
"--camera-name" && i + 1 < argc) {
188 opt_camera_name = std::string(argv[++i]);
190 else if ((std::string(argv[i]) ==
"--eMo") && (i + 1 < argc)) {
191 opt_eMo_filename = std::string(argv[++i]);
193 else if ((std::string(argv[i]) ==
"--verbose") || (std::string(argv[i]) ==
"-v")) {
196 else if (std::string(argv[i]) ==
"--plot") {
199 else if (std::string(argv[i]) ==
"--adaptive-gain") {
200 opt_adaptive_gain =
true;
202 else if (std::string(argv[i]) ==
"--task-sequencing") {
203 opt_task_sequencing =
true;
205 else if (std::string(argv[i]) ==
"--no-convergence-threshold") {
206 convergence_threshold = 0.;
208 else if (std::string(argv[i]) ==
"--learn-desired-features") {
209 opt_learn_desired_features =
true;
211 else if ((std::string(argv[i]) ==
"--help") || (std::string(argv[i]) ==
"-h")) {
212 std::cout <<
"SYNOPSYS" << std::endl
214 <<
" [--ip <controller ip>]"
215 <<
" [--intrinsic <xml file>]"
216 <<
" [--camera-name <name>]"
217 <<
" [--tag-size <size>]"
218 <<
" [--tag-quad-decimate <decimation factor>]"
219 <<
" [--tag-z-aligned]"
220 <<
" [--learn-desired-pose]"
221 <<
" [--eMo <file.yaml>]"
222 <<
" [--adaptive-gain]"
224 <<
" [--task-sequencing]"
225 <<
" [--no-convergence-threshold]"
226 <<
" [--verbose, -v]"
229 std::cout <<
"DESCRIPTION" << std::endl
230 <<
" Use an image-based visual-servoing scheme to position the camera in front of an Apriltag." << std::endl
232 <<
" --ip <controller ip>" << std::endl
233 <<
" Franka controller ip address" << std::endl
234 <<
" Default: " << opt_robot_ip << std::endl
236 <<
" --intrinsic <xml file>" << std::endl
237 <<
" XML file that contains camera intrinsic parameters. " << std::endl
238 <<
" If no file is specified, use Realsense camera factory intrinsic parameters." << std::endl
240 <<
" --camera-name <name>" << std::endl
241 <<
" Camera name in the XML file that contains camera intrinsic parameters." << std::endl
242 <<
" Default: \"Camera\"" << std::endl
244 <<
" --tag-size <size>" << std::endl
245 <<
" Apriltag size in [m]." << std::endl
246 <<
" Default: " << opt_tag_size <<
" [m]" << std::endl
248 <<
" --tag-quad-decimate <decimation factor>" << std::endl
249 <<
" Decimation factor used during Apriltag detection." << std::endl
250 <<
" Default: " << opt_quad_decimate << std::endl
252 <<
" --tag-z-aligned" << std::endl
253 <<
" When enabled, tag z-axis and camera z-axis are aligned." << std::endl
254 <<
" Default: false" << std::endl
256 <<
" --eMo <file.yaml>" << std::endl
257 <<
" Yaml file containing the extrinsic transformation between" << std::endl
258 <<
" robot end-effector frame and object (Apriltag) frames." << std::endl
260 <<
" --adaptive-gain" << std::endl
261 <<
" Flag to enable adaptive gain to speed up visual servo near convergence." << std::endl
263 <<
" --plot" << std::endl
264 <<
" Flag to enable curve plotter." << std::endl
266 <<
" --task-sequencing" << std::endl
267 <<
" Flag to enable task sequencing scheme." << std::endl
269 <<
" --no-convergence-threshold" << std::endl
270 <<
" Flag to disable convergence threshold used to stop the visual servo." << std::endl
272 <<
" --learn-desired-pose" << std::endl
273 <<
" Flag to enable desired pose learning." << std::endl
274 <<
" Data are saved in learned-desired-pose.yaml file." << std::endl
276 <<
" --verbose, -v" << std::endl
277 <<
" Flag to enable extra verbosity." << std::endl
279 <<
" --help, -h" << std::endl
280 <<
" Print this helper message." << std::endl
286 std::cout <<
"\nERROR" << std::endl
287 << std::string(argv[i]) <<
" command line option is not supported." << std::endl
288 <<
"Use " << std::string(argv[0]) <<
" --help" << std::endl
297 config.enable_stream(RS2_STREAM_COLOR, 640, 480, RS2_FORMAT_RGBA8, 30);
298 config.enable_stream(RS2_STREAM_DEPTH, 640, 480, RS2_FORMAT_Z16, 30);
299 config.enable_stream(RS2_STREAM_INFRARED, 640, 480, RS2_FORMAT_Y8, 30);
304#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
310 std::cout <<
"Parameters:" << std::endl;
311 std::cout <<
" Apriltag " << std::endl;
312 std::cout <<
" Size [m] : " << opt_tag_size << std::endl;
313 std::cout <<
" Z aligned : " << (opt_tag_z_aligned ?
"true" :
"false") << std::endl;
314 std::cout <<
" Camera intrinsics " << std::endl;
315 std::cout <<
" Factory parameters : " << (opt_intrinsic_filename.empty() ?
"yes" :
"no") << std::endl;
319 if (opt_intrinsic_filename.empty()) {
320 std::cout <<
"Use Realsense camera intrinsic factory parameters: " << std::endl;
322 std::cout <<
"cam:\n" <<
cam << std::endl;
325 std::cout <<
"Camera parameters file " << opt_intrinsic_filename <<
" doesn't exist." << std::endl;
330 if (!opt_camera_name.empty()) {
332 std::cout <<
" Param file name [.xml]: " << opt_intrinsic_filename << std::endl;
333 std::cout <<
" Camera name : " << opt_camera_name << std::endl;
337 std::cout <<
"Unable to parse parameters with distortion for camera \"" << opt_camera_name <<
"\" from "
338 << opt_intrinsic_filename <<
" file" << std::endl;
339 std::cout <<
"Attempt to find parameters without distortion" << std::endl;
341 if (
parser.parse(cam, opt_intrinsic_filename, opt_camera_name,
343 std::cout <<
"Unable to parse parameters without distortion for camera \"" << opt_camera_name <<
"\" from "
344 << opt_intrinsic_filename <<
" file" << std::endl;
351 std::cout <<
"Camera parameters used to compute the pose:\n" <<
cam << std::endl;
358 detector.setAprilTagPoseEstimationMethod(poseEstimationMethod);
359 detector.setDisplayTag(display_tag);
360 detector.setAprilTagQuadDecimate(opt_quad_decimate);
361 detector.setZAlignedWithCameraAxis(opt_tag_z_aligned);
364 std::vector<vpPoint> point(4);
365 point[0].setWorldCoordinates(-opt_tag_size / 2., -opt_tag_size / 2., 0);
366 point[1].setWorldCoordinates(+opt_tag_size / 2., -opt_tag_size / 2., 0);
367 point[2].setWorldCoordinates(+opt_tag_size / 2., +opt_tag_size / 2., 0);
368 point[3].setWorldCoordinates(-opt_tag_size / 2., +opt_tag_size / 2., 0);
370 if (opt_learn_desired_features) {
378 std::vector<vpHomogeneousMatrix> c_M_o_vec;
380 bool ret = detector.detect(I, opt_tag_size, cam, c_M_o_vec);
385 std::vector< std::vector<vpImagePoint> > tags_corners;
387 if (detector.getNbObjects() == 1) {
388 tags_corners = detector.getTagsCorners();
389 for (
size_t i = 0;
i < 4; ++
i) {
390 std::stringstream ss;
403 if (detector.getNbObjects() == 1) {
404 tags_corners = detector.getTagsCorners();
406 std::vector<vpFeaturePoint> p_d(4);
409 for (
size_t i = 0;
i < 4; ++
i) {
417 for (
size_t i = 0;
i < point.size(); ++
i) {
419 point[
i].changeFrame(cd_M_o, c_P);
420 p_d[
i].set_Z(c_P[2]);
422 if (save_desired_features(desired_features_filename, p_d)) {
423 std::cout <<
"Desired visual features saved in: " << desired_features_filename << std::endl;
426 std::cout <<
"Error: Unable to save desired features in " << desired_features_filename << std::endl;
431 std::cout <<
"Cannot save desired features. More than 1 tag is visible in the image..." << std::endl;
435 std::cout <<
"Cannot save desired features. Tag is not visible in the image..." << std::endl;
454 std::vector<vpFeaturePoint> p_d;
457 std::cout <<
"Cannot start eye-to-hand visual-servoing. Desired features are not available." << std::endl;
458 std::cout <<
"use --learn-desired-features flag to learn the desired features." << std::endl;
462 if (!read_desired_features(desired_features_filename, p_d)) {
463 std::cout <<
"Error: Unable to read desired features from: " << desired_features_filename << std::endl;
473 if (!opt_eMo_filename.empty()) {
474 e_P_o.
loadYAML(opt_eMo_filename, e_P_o);
477 std::cout <<
"Warning, eMo transformation is not specified using --eMo parameter." << std::endl;
481 std::cout <<
"e_M_o:\n" << e_M_o << std::endl;
486 robot.connect(opt_robot_ip);
492 std::vector<vpFeaturePoint>
p(4);
495 for (
size_t i = 0;
i <
p.size(); ++
i) {
496 task.addFeature(p[i], p_d[i]);
507 if (opt_adaptive_gain) {
509 task.setLambda(lambda);
519 plotter =
new vpPlot(2,
static_cast<int>(250 * 2), 500,
static_cast<int>(I.getWidth()) + 80, 10,
520 "Real time curves plotter");
521 plotter->setTitle(0,
"Visual features error");
522 plotter->setTitle(1,
"Joint velocities");
525 plotter->setLegend(0, 0,
"error_feat_p1_x");
526 plotter->setLegend(0, 1,
"error_feat_p1_y");
527 plotter->setLegend(0, 2,
"error_feat_p2_x");
528 plotter->setLegend(0, 3,
"error_feat_p2_y");
529 plotter->setLegend(0, 4,
"error_feat_p3_x");
530 plotter->setLegend(0, 5,
"error_feat_p3_y");
531 plotter->setLegend(0, 6,
"error_feat_p4_x");
532 plotter->setLegend(0, 7,
"error_feat_p4_y");
533 plotter->setLegend(1, 0,
"q_1");
534 plotter->setLegend(1, 1,
"q_2");
535 plotter->setLegend(1, 2,
"q_3");
536 plotter->setLegend(1, 3,
"q_4");
537 plotter->setLegend(1, 4,
"q_5");
538 plotter->setLegend(1, 5,
"q_6");
539 plotter->setLegend(1, 6,
"q_7");
542 bool final_quit =
false;
543 bool has_converged =
false;
544 bool send_velocities =
false;
545 bool servo_started =
false;
546 std::vector<vpImagePoint> *traj_corners =
nullptr;
553 while (!has_converged && !final_quit) {
560 std::vector<vpHomogeneousMatrix> c_M_o_vec;
563 bool ret = detector.detect(I, opt_tag_size, cam, c_M_o_vec);
567 std::stringstream ss;
568 ss <<
"Left click to " << (send_velocities ?
"stop the robot" :
"servo the robot") <<
", right click to quit.";
575 if (ret && (c_M_o_vec.size() == 1)) {
580 static bool first_time =
true;
584 std::vector<vpImagePoint> corners = detector.getPolygon(0);
587 for (
size_t i = 0;
i < corners.size(); ++
i) {
592 point[
i].changeFrame(c_M_o, c_P);
600 c_M_e = c_M_o * e_M_o.
inverse();
607 robot.get_eJe(e_J_e);
611 if (opt_task_sequencing) {
612 if (!servo_started) {
613 if (send_velocities) {
614 servo_started =
true;
622 qdot =
task.computeControlLaw();
628 for (
size_t i = 0;
i < corners.size(); ++
i) {
629 std::stringstream ss;
639 traj_corners =
new std::vector<vpImagePoint>[corners.size()];
642 display_point_trajectory(I, corners, traj_corners);
646 plotter->plot(1, iter_plot, qdot);
651 std::cout <<
"qdot: " << qdot.t() << std::endl;
654 double error =
task.getError().sumSquare();
655 std::stringstream ss;
656 ss <<
"error: " <<
error;
660 std::cout <<
"error: " <<
error << std::endl;
662 if (error < convergence_threshold) {
663 has_converged =
true;
664 std::cout <<
"Servo task has converged" << std::endl;
675 if (!send_velocities) {
683 std::stringstream ss;
693 send_velocities = !send_velocities;
706 std::cout <<
"Stop the robot " << std::endl;
709 if (opt_plot && plotter !=
nullptr) {
715 while (!final_quit) {
730 delete[] traj_corners;
734 std::cout <<
"ViSP exception: " <<
e.what() << std::endl;
735 std::cout <<
"Stop the robot " << std::endl;
737#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
738 if (display !=
nullptr) {
744 catch (
const franka::NetworkException &e) {
745 std::cout <<
"Franka network exception: " <<
e.what() << std::endl;
746 std::cout <<
"Check if you are connected to the Franka robot"
747 <<
" or if you specified the right IP using --ip command line option set by default to 192.168.1.1. "
749#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
750 if (display !=
nullptr) {
756 catch (
const std::exception &e) {
757 std::cout <<
"Franka exception: " <<
e.what() << std::endl;
758#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
759 if (display !=
nullptr) {
766#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
767 if (display !=
nullptr) {
777#if !defined(VISP_HAVE_REALSENSE2)
778 std::cout <<
"Install librealsense-2.x and rebuild ViSP." << std::endl;
780#if !defined(VISP_HAVE_FRANKA)
781 std::cout <<
"Install libfranka and rebuild ViSP." << std::endl;
783#if !defined(VISP_HAVE_PUGIXML)
784 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 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 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.
static void create(vpFeaturePoint &s, const vpCameraParameters &cam, const vpDot &d)
Class that defines a 2D point visual feature which is composed by two parameters that are the cartes...
vpFeaturePoint & buildFrom(const double &x, const double &y, const double &Z)
Implementation of an homogeneous matrix and operations on such kind of matrices.
vpHomogeneousMatrix inverse() const
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.
Implementation of a matrix and operations on matrices.
static void convertPoint(const vpCameraParameters &cam, const double &x, const double &y, double &u, double &v)
static void convertPoint(const vpCameraParameters &cam, const double &u, const double &v, double &x, double &y)
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.
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)
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()