67 #include <visp3/core/vpCameraParameters.h>
68 #include <visp3/detection/vpDetectorAprilTag.h>
69 #include <visp3/gui/vpDisplayGDI.h>
70 #include <visp3/gui/vpDisplayX.h>
71 #include <visp3/gui/vpPlot.h>
72 #include <visp3/io/vpImageIo.h>
73 #include <visp3/robot/vpRobotFranka.h>
74 #include <visp3/sensor/vpRealSense2.h>
75 #include <visp3/visual_features/vpFeatureBuilder.h>
76 #include <visp3/visual_features/vpFeaturePoint.h>
77 #include <visp3/vs/vpServo.h>
78 #include <visp3/vs/vpServoDisplay.h>
80 #if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && \
81 (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && defined(VISP_HAVE_FRANKA)
84 std::vector<vpImagePoint> *traj_vip)
86 for (
size_t i = 0; i < vip.size(); i++) {
87 if (traj_vip[i].size()) {
90 traj_vip[i].push_back(vip[i]);
93 traj_vip[i].push_back(vip[i]);
96 for (
size_t i = 0; i < vip.size(); i++) {
97 for (
size_t j = 1; j < traj_vip[i].size(); j++) {
103 int main(
int argc,
char **argv)
105 double opt_tagSize = 0.120;
106 std::string opt_robot_ip =
"192.168.1.1";
107 std::string opt_eMc_filename =
"";
108 bool display_tag =
true;
109 int opt_quad_decimate = 2;
110 bool opt_verbose =
false;
111 bool opt_plot =
false;
112 bool opt_adaptive_gain =
false;
113 bool opt_task_sequencing =
false;
114 double convergence_threshold = 0.00005;
116 for (
int i = 1; i < argc; i++) {
117 if (std::string(argv[i]) ==
"--tag_size" && i + 1 < argc) {
118 opt_tagSize = std::stod(argv[i + 1]);
119 }
else if (std::string(argv[i]) ==
"--ip" && i + 1 < argc) {
120 opt_robot_ip = std::string(argv[i + 1]);
121 }
else if (std::string(argv[i]) ==
"--eMc" && i + 1 < argc) {
122 opt_eMc_filename = std::string(argv[i + 1]);
123 }
else if (std::string(argv[i]) ==
"--verbose") {
125 }
else if (std::string(argv[i]) ==
"--plot") {
127 }
else if (std::string(argv[i]) ==
"--adaptive_gain") {
128 opt_adaptive_gain =
true;
129 }
else if (std::string(argv[i]) ==
"--task_sequencing") {
130 opt_task_sequencing =
true;
131 }
else if (std::string(argv[i]) ==
"--quad_decimate" && i + 1 < argc) {
132 opt_quad_decimate = std::stoi(argv[i + 1]);
133 }
else if (std::string(argv[i]) ==
"--no-convergence-threshold") {
134 convergence_threshold = 0.;
135 }
else if (std::string(argv[i]) ==
"--help" || std::string(argv[i]) ==
"-h") {
137 << argv[0] <<
" [--ip <default " << opt_robot_ip <<
">] [--tag_size <marker size in meter; default "
138 << opt_tagSize <<
">] [--eMc <eMc extrinsic file>] "
139 <<
"[--quad_decimate <decimation; default " << opt_quad_decimate
140 <<
">] [--adaptive_gain] [--plot] [--task_sequencing] [--no-convergence-threshold] [--verbose] [--help] [-h]"
149 robot.connect(opt_robot_ip);
153 unsigned int width = 640, height = 480;
154 config.enable_stream(RS2_STREAM_COLOR, 640, 480, RS2_FORMAT_RGBA8, 30);
155 config.enable_stream(RS2_STREAM_DEPTH, 640, 480, RS2_FORMAT_Z16, 30);
156 config.enable_stream(RS2_STREAM_INFRARED, 640, 480, RS2_FORMAT_Y8, 30);
163 ePc[1] = -0.00535012;
170 if (!opt_eMc_filename.empty()) {
171 ePc.
loadYAML(opt_eMc_filename, ePc);
173 std::cout <<
"Warning, opt_eMc_filename is empty! Use hard coded values."
177 std::cout <<
"eMc:\n" << eMc <<
"\n";
182 std::cout <<
"cam:\n" << cam <<
"\n";
186 #if defined(VISP_HAVE_X11)
188 #elif defined(VISP_HAVE_GDI)
196 detector.setAprilTagPoseEstimationMethod(poseEstimationMethod);
197 detector.setDisplayTag(display_tag);
198 detector.setAprilTagQuadDecimate(opt_quad_decimate);
208 std::vector<vpFeaturePoint> p(4), pd(4);
211 std::vector<vpPoint> point(4);
212 point[0].setWorldCoordinates(-opt_tagSize / 2., -opt_tagSize / 2., 0);
213 point[1].setWorldCoordinates(opt_tagSize / 2., -opt_tagSize / 2., 0);
214 point[2].setWorldCoordinates(opt_tagSize / 2., opt_tagSize / 2., 0);
215 point[3].setWorldCoordinates(-opt_tagSize / 2., opt_tagSize / 2., 0);
219 for (
size_t i = 0; i < p.size(); i++) {
225 if (opt_adaptive_gain) {
232 vpPlot *plotter =
nullptr;
236 plotter =
new vpPlot(2,
static_cast<int>(250 * 2), 500,
static_cast<int>(I.
getWidth()) + 80, 10,
237 "Real time curves plotter");
238 plotter->
setTitle(0,
"Visual features error");
239 plotter->
setTitle(1,
"Camera velocities");
242 plotter->
setLegend(0, 0,
"error_feat_p1_x");
243 plotter->
setLegend(0, 1,
"error_feat_p1_y");
244 plotter->
setLegend(0, 2,
"error_feat_p2_x");
245 plotter->
setLegend(0, 3,
"error_feat_p2_y");
246 plotter->
setLegend(0, 4,
"error_feat_p3_x");
247 plotter->
setLegend(0, 5,
"error_feat_p3_y");
248 plotter->
setLegend(0, 6,
"error_feat_p4_x");
249 plotter->
setLegend(0, 7,
"error_feat_p4_y");
258 bool final_quit =
false;
259 bool has_converged =
false;
260 bool send_velocities =
false;
261 bool servo_started =
false;
262 std::vector<vpImagePoint> *traj_corners =
nullptr;
269 while (!has_converged && !final_quit) {
276 std::vector<vpHomogeneousMatrix> cMo_vec;
277 detector.detect(I, opt_tagSize, cam, cMo_vec);
280 std::stringstream ss;
281 ss <<
"Left click to " << (send_velocities ?
"stop the robot" :
"servo the robot") <<
", right click to quit.";
288 if (cMo_vec.size() == 1) {
291 static bool first_time =
true;
294 std::vector<vpHomogeneousMatrix> v_oMo(2), v_cdMc(2);
295 v_oMo[1].buildFrom(0, 0, 0, 0, 0, M_PI);
296 for (
size_t i = 0; i < 2; i++) {
297 v_cdMc[i] = cdMo * v_oMo[i] * cMo.
inverse();
299 if (std::fabs(v_cdMc[0].getThetaUVector().getTheta()) < std::fabs(v_cdMc[1].getThetaUVector().getTheta())) {
302 std::cout <<
"Desired frame modified to avoid PI rotation of the camera" << std::endl;
307 for (
size_t i = 0; i < point.size(); i++) {
309 point[i].changeFrame(cdMo * oMo, cP);
310 point[i].projection(cP, p_);
319 std::vector<vpImagePoint> corners = detector.getPolygon(0);
322 for (
size_t i = 0; i < corners.size(); i++) {
327 point[i].changeFrame(cMo, cP);
332 if (opt_task_sequencing) {
333 if (!servo_started) {
334 if (send_velocities) {
335 servo_started =
true;
346 for (
size_t i = 0; i < corners.size(); i++) {
347 std::stringstream ss;
357 traj_corners =
new std::vector<vpImagePoint>[corners.size()];
360 display_point_trajectory(I, corners, traj_corners);
364 plotter->
plot(1, iter_plot, v_c);
369 std::cout <<
"v_c: " << v_c.t() << std::endl;
373 std::stringstream ss;
374 ss <<
"error: " << error;
378 std::cout <<
"error: " << error << std::endl;
380 if (error < convergence_threshold) {
381 has_converged =
true;
382 std::cout <<
"Servo task has converged"
394 if (!send_velocities) {
402 std::stringstream ss;
412 send_velocities = !send_velocities;
425 std::cout <<
"Stop the robot " << std::endl;
428 if (opt_plot && plotter !=
nullptr) {
434 while (!final_quit) {
449 delete[] traj_corners;
452 std::cout <<
"ViSP exception: " << e.
what() << std::endl;
453 std::cout <<
"Stop the robot " << std::endl;
456 }
catch (
const franka::NetworkException &e) {
457 std::cout <<
"Franka network exception: " << e.what() << std::endl;
458 std::cout <<
"Check if you are connected to the Franka robot"
459 <<
" or if you specified the right IP using --ip command line option set by default to 192.168.1.1. "
462 }
catch (
const std::exception &e) {
463 std::cout <<
"Franka exception: " << e.what() << std::endl;
472 #if !defined(VISP_HAVE_REALSENSE2)
473 std::cout <<
"Install librealsense-2.x" << std::endl;
475 #if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
476 std::cout <<
"Build ViSP with c++11 or higher compiler flag (cmake -DUSE_CXX_STANDARD=11)." << std::endl;
478 #if !defined(VISP_HAVE_FRANKA)
479 std::cout <<
"Install libfranka." << std::endl;
Adaptive gain computation.
static bool loadYAML(const std::string &filename, vpArray2D< Type > &A, char *header=NULL)
Generic class defining intrinsic camera parameters.
@ perspectiveProjWithDistortion
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).
Use the X11 console to display images on unix-like OS. Thus to enable this class X11 should be instal...
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 emited by ViSP classes.
const char * what() const
static void create(vpFeaturePoint &s, const vpCameraParameters &cam, const vpDot &d)
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.
void acquire(vpImage< unsigned char > &grey, double *ts=NULL)
vpCameraParameters getCameraParameters(const rs2_stream &stream, vpCameraParameters::vpCameraParametersProjType type=vpCameraParameters::perspectiveProjWithDistortion, int index=-1) const
bool open(const rs2::config &cfg=rs2::config())
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel)
@ 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 setServo(const vpServoType &servo_type)
vpColVector getError() const
vpColVector computeControlLaw()
void addFeature(vpBasicFeature &s, vpBasicFeature &s_star, unsigned int select=vpBasicFeature::FEATURE_ALL)
Class that consider the case of a translation vector.
VISP_EXPORT double measureTimeMs()