64 #include <visp3/core/vpCameraParameters.h>
65 #include <visp3/core/vpConfig.h>
66 #include <visp3/detection/vpDetectorAprilTag.h>
67 #include <visp3/gui/vpDisplayGDI.h>
68 #include <visp3/gui/vpDisplayX.h>
69 #include <visp3/gui/vpPlot.h>
70 #include <visp3/io/vpImageIo.h>
71 #include <visp3/robot/vpRobotFranka.h>
72 #include <visp3/sensor/vpRealSense2.h>
73 #include <visp3/visual_features/vpFeatureBuilder.h>
74 #include <visp3/visual_features/vpFeaturePoint.h>
75 #include <visp3/vs/vpServo.h>
76 #include <visp3/vs/vpServoDisplay.h>
78 #if defined(VISP_HAVE_REALSENSE2) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && defined(VISP_HAVE_FRANKA)
80 #ifdef ENABLE_VISP_NAMESPACE
85 std::vector<vpImagePoint> *traj_vip)
87 for (
size_t i = 0; i < vip.size(); i++) {
88 if (traj_vip[i].size()) {
91 traj_vip[i].push_back(vip[i]);
95 traj_vip[i].push_back(vip[i]);
98 for (
size_t i = 0; i < vip.size(); i++) {
99 for (
size_t j = 1; j < traj_vip[i].size(); j++) {
105 int main(
int argc,
char **argv)
107 double opt_tagSize = 0.120;
108 std::string opt_robot_ip =
"192.168.1.1";
109 std::string opt_eMc_filename =
"";
110 bool display_tag =
true;
111 int opt_quad_decimate = 2;
112 bool opt_verbose =
false;
113 bool opt_plot =
false;
114 bool opt_adaptive_gain =
false;
115 bool opt_task_sequencing =
false;
116 double convergence_threshold = 0.00005;
118 for (
int i = 1; i < argc; i++) {
119 if (std::string(argv[i]) ==
"--tag_size" && i + 1 < argc) {
120 opt_tagSize = std::stod(argv[i + 1]);
122 else if (std::string(argv[i]) ==
"--ip" && i + 1 < argc) {
123 opt_robot_ip = std::string(argv[i + 1]);
125 else if (std::string(argv[i]) ==
"--eMc" && i + 1 < argc) {
126 opt_eMc_filename = std::string(argv[i + 1]);
128 else if (std::string(argv[i]) ==
"--verbose") {
131 else if (std::string(argv[i]) ==
"--plot") {
134 else if (std::string(argv[i]) ==
"--adaptive_gain") {
135 opt_adaptive_gain =
true;
137 else if (std::string(argv[i]) ==
"--task_sequencing") {
138 opt_task_sequencing =
true;
140 else if (std::string(argv[i]) ==
"--quad_decimate" && i + 1 < argc) {
141 opt_quad_decimate = std::stoi(argv[i + 1]);
143 else if (std::string(argv[i]) ==
"--no-convergence-threshold") {
144 convergence_threshold = 0.;
146 else if (std::string(argv[i]) ==
"--help" || std::string(argv[i]) ==
"-h") {
148 << argv[0] <<
" [--ip <default " << opt_robot_ip <<
">] [--tag_size <marker size in meter; default "
149 << opt_tagSize <<
">] [--eMc <eMc extrinsic file>] "
150 <<
"[--quad_decimate <decimation; default " << opt_quad_decimate
151 <<
">] [--adaptive_gain] [--plot] [--task_sequencing] [--no-convergence-threshold] [--verbose] [--help] [-h]"
160 robot.connect(opt_robot_ip);
164 unsigned int width = 640, height = 480;
165 config.enable_stream(RS2_STREAM_COLOR, 640, 480, RS2_FORMAT_RGBA8, 30);
166 config.enable_stream(RS2_STREAM_DEPTH, 640, 480, RS2_FORMAT_Z16, 30);
167 config.enable_stream(RS2_STREAM_INFRARED, 640, 480, RS2_FORMAT_Y8, 30);
174 ePc[1] = -0.00535012;
181 if (!opt_eMc_filename.empty()) {
182 ePc.
loadYAML(opt_eMc_filename, ePc);
185 std::cout <<
"Warning, opt_eMc_filename is empty! Use hard coded values."
189 std::cout <<
"eMc:\n" << eMc <<
"\n";
194 std::cout <<
"cam:\n" << cam <<
"\n";
198 #if defined(VISP_HAVE_X11)
199 vpDisplayX dc(I, 10, 10,
"Color image");
200 #elif defined(VISP_HAVE_GDI)
208 detector.setAprilTagPoseEstimationMethod(poseEstimationMethod);
209 detector.setDisplayTag(display_tag);
210 detector.setAprilTagQuadDecimate(opt_quad_decimate);
220 std::vector<vpFeaturePoint> p(4), pd(4);
223 std::vector<vpPoint> point(4);
224 point[0].setWorldCoordinates(-opt_tagSize / 2., -opt_tagSize / 2., 0);
225 point[1].setWorldCoordinates(opt_tagSize / 2., -opt_tagSize / 2., 0);
226 point[2].setWorldCoordinates(opt_tagSize / 2., opt_tagSize / 2., 0);
227 point[3].setWorldCoordinates(-opt_tagSize / 2., opt_tagSize / 2., 0);
231 for (
size_t i = 0; i < p.size(); i++) {
237 if (opt_adaptive_gain) {
245 vpPlot *plotter =
nullptr;
249 plotter =
new vpPlot(2,
static_cast<int>(250 * 2), 500,
static_cast<int>(I.
getWidth()) + 80, 10,
250 "Real time curves plotter");
251 plotter->
setTitle(0,
"Visual features error");
252 plotter->
setTitle(1,
"Camera velocities");
255 plotter->
setLegend(0, 0,
"error_feat_p1_x");
256 plotter->
setLegend(0, 1,
"error_feat_p1_y");
257 plotter->
setLegend(0, 2,
"error_feat_p2_x");
258 plotter->
setLegend(0, 3,
"error_feat_p2_y");
259 plotter->
setLegend(0, 4,
"error_feat_p3_x");
260 plotter->
setLegend(0, 5,
"error_feat_p3_y");
261 plotter->
setLegend(0, 6,
"error_feat_p4_x");
262 plotter->
setLegend(0, 7,
"error_feat_p4_y");
271 bool final_quit =
false;
272 bool has_converged =
false;
273 bool send_velocities =
false;
274 bool servo_started =
false;
275 std::vector<vpImagePoint> *traj_corners =
nullptr;
282 while (!has_converged && !final_quit) {
289 std::vector<vpHomogeneousMatrix> cMo_vec;
290 detector.detect(I, opt_tagSize, cam, cMo_vec);
293 std::stringstream ss;
294 ss <<
"Left click to " << (send_velocities ?
"stop the robot" :
"servo the robot") <<
", right click to quit.";
301 if (cMo_vec.size() == 1) {
304 static bool first_time =
true;
307 std::vector<vpHomogeneousMatrix> v_oMo(2), v_cdMc(2);
308 v_oMo[1].buildFrom(0, 0, 0, 0, 0, M_PI);
309 for (
size_t i = 0; i < 2; i++) {
310 v_cdMc[i] = cdMo * v_oMo[i] * cMo.
inverse();
312 if (std::fabs(v_cdMc[0].getThetaUVector().getTheta()) < std::fabs(v_cdMc[1].getThetaUVector().getTheta())) {
316 std::cout <<
"Desired frame modified to avoid PI rotation of the camera" << std::endl;
321 for (
size_t i = 0; i < point.size(); i++) {
323 point[i].changeFrame(cdMo * oMo, cP);
324 point[i].projection(cP, p_);
333 std::vector<vpImagePoint> corners = detector.getPolygon(0);
336 for (
size_t i = 0; i < corners.size(); i++) {
341 point[i].changeFrame(cMo, cP);
346 if (opt_task_sequencing) {
347 if (!servo_started) {
348 if (send_velocities) {
349 servo_started =
true;
361 for (
size_t i = 0; i < corners.size(); i++) {
362 std::stringstream ss;
372 traj_corners =
new std::vector<vpImagePoint>[corners.size()];
375 display_point_trajectory(I, corners, traj_corners);
379 plotter->
plot(1, iter_plot, v_c);
384 std::cout <<
"v_c: " << v_c.t() << std::endl;
388 std::stringstream ss;
389 ss <<
"error: " << error;
393 std::cout <<
"error: " << error << std::endl;
395 if (error < convergence_threshold) {
396 has_converged =
true;
397 std::cout <<
"Servo task has converged"
409 if (!send_velocities) {
417 std::stringstream ss;
427 send_velocities = !send_velocities;
440 std::cout <<
"Stop the robot " << std::endl;
443 if (opt_plot && plotter !=
nullptr) {
449 while (!final_quit) {
464 delete[] traj_corners;
468 std::cout <<
"ViSP exception: " << e.
what() << std::endl;
469 std::cout <<
"Stop the robot " << std::endl;
473 catch (
const franka::NetworkException &e) {
474 std::cout <<
"Franka network exception: " << e.what() << std::endl;
475 std::cout <<
"Check if you are connected to the Franka robot"
476 <<
" or if you specified the right IP using --ip command line option set by default to 192.168.1.1. "
480 catch (
const std::exception &e) {
481 std::cout <<
"Franka exception: " << e.what() << std::endl;
490 #if !defined(VISP_HAVE_REALSENSE2)
491 std::cout <<
"Install librealsense-2.x" << std::endl;
493 #if !defined(VISP_HAVE_FRANKA)
494 std::cout <<
"Install libfranka." << 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.
Implementation of column vector and the associated operations.
static const vpColor green
@ TAG_36h11
AprilTag 36h11 pattern (recommended)
Display for windows using GDI (available on any windows 32 platform).
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.
const char * what() const
static void create(vpFeaturePoint &s, const vpCameraParameters &cam, const vpImagePoint &t)
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)
unsigned int getWidth() const
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...
void initGraph(unsigned int graphNum, unsigned int curveNbr)
void setLegend(unsigned int graphNum, unsigned int curveNum, const std::string &legend)
void plot(unsigned int graphNum, unsigned int curveNum, double x, double y)
void setTitle(unsigned int graphNum, const std::string &title)
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())
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel) VP_OVERRIDE
@ STATE_VELOCITY_CONTROL
Initialize the velocity controller.
@ STATE_STOP
Stops robot motion especially in velocity and acceleration control.
virtual vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
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)
void setInteractionMatrixType(const vpServoIteractionMatrixType &interactionMatrixType, const vpServoInversionType &interactionMatrixInversion=PSEUDO_INVERSE)
void addFeature(vpBasicFeature &s_cur, vpBasicFeature &s_star, unsigned int select=vpBasicFeature::FEATURE_ALL)
void setServo(const vpServoType &servo_type)
vpColVector getError() const
vpColVector computeControlLaw()
Class that consider the case of a translation vector.
VISP_EXPORT double measureTimeMs()