61 #include <visp3/core/vpCameraParameters.h>
62 #include <visp3/detection/vpDetectorAprilTag.h>
63 #include <visp3/gui/vpDisplayGDI.h>
64 #include <visp3/gui/vpDisplayX.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_X11) || defined(VISP_HAVE_GDI)) && defined(VISP_HAVE_FRANKA)
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++) {
97 int main(
int argc,
char **argv)
99 double opt_tagSize = 0.120;
100 std::string opt_robot_ip =
"192.168.1.1";
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 + 1]);
115 else if (std::string(argv[i]) ==
"--ip" && i + 1 < argc) {
116 opt_robot_ip = std::string(argv[i + 1]);
118 else if (std::string(argv[i]) ==
"--eMc" && i + 1 < argc) {
119 opt_eMc_filename = std::string(argv[i + 1]);
121 else if (std::string(argv[i]) ==
"--verbose") {
124 else if (std::string(argv[i]) ==
"--plot") {
127 else if (std::string(argv[i]) ==
"--adaptive_gain") {
128 opt_adaptive_gain =
true;
130 else if (std::string(argv[i]) ==
"--task_sequencing") {
131 opt_task_sequencing =
true;
133 else if (std::string(argv[i]) ==
"--quad_decimate" && i + 1 < argc) {
134 opt_quad_decimate = std::stoi(argv[i + 1]);
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 <<
"[--quad_decimate <decimation; default " << opt_quad_decimate
145 <<
">] [--adaptive_gain] [--plot] [--task_sequencing] [--no-convergence-threshold] [--verbose] [--help] [-h]"
154 robot.connect(opt_robot_ip);
158 unsigned int width = 640, height = 480;
159 config.enable_stream(RS2_STREAM_COLOR, 640, 480, RS2_FORMAT_RGBA8, 30);
160 config.enable_stream(RS2_STREAM_DEPTH, 640, 480, RS2_FORMAT_Z16, 30);
161 config.enable_stream(RS2_STREAM_INFRARED, 640, 480, RS2_FORMAT_Y8, 30);
168 ePc[1] = -0.00535012;
175 if (!opt_eMc_filename.empty()) {
176 ePc.
loadYAML(opt_eMc_filename, ePc);
179 std::cout <<
"Warning, opt_eMc_filename is empty! Use hard coded values."
183 std::cout <<
"eMc:\n" << eMc <<
"\n";
188 std::cout <<
"cam:\n" << cam <<
"\n";
192 #if defined(VISP_HAVE_X11)
194 #elif defined(VISP_HAVE_GDI)
202 detector.setAprilTagPoseEstimationMethod(poseEstimationMethod);
203 detector.setDisplayTag(display_tag);
204 detector.setAprilTagQuadDecimate(opt_quad_decimate);
228 if (opt_adaptive_gain) {
236 vpPlot *plotter =
nullptr;
240 plotter =
new vpPlot(2,
static_cast<int>(250 * 2), 500,
static_cast<int>(I.
getWidth()) + 80, 10,
241 "Real time curves plotter");
242 plotter->
setTitle(0,
"Visual features error");
243 plotter->
setTitle(1,
"Camera velocities");
246 plotter->
setLegend(0, 0,
"error_feat_tx");
247 plotter->
setLegend(0, 1,
"error_feat_ty");
248 plotter->
setLegend(0, 2,
"error_feat_tz");
249 plotter->
setLegend(0, 3,
"error_feat_theta_ux");
250 plotter->
setLegend(0, 4,
"error_feat_theta_uy");
251 plotter->
setLegend(0, 5,
"error_feat_theta_uz");
260 bool final_quit =
false;
261 bool has_converged =
false;
262 bool send_velocities =
false;
263 bool servo_started =
false;
264 std::vector<vpImagePoint> *traj_vip =
nullptr;
271 while (!has_converged && !final_quit) {
278 std::vector<vpHomogeneousMatrix> cMo_vec;
279 detector.detect(I, opt_tagSize, cam, cMo_vec);
281 std::stringstream ss;
282 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())) {
303 std::cout <<
"Desired frame modified to avoid PI rotation of the camera" << std::endl;
309 cdMc = cdMo * oMo * cMo.
inverse();
313 if (opt_task_sequencing) {
314 if (!servo_started) {
315 if (send_velocities) {
316 servo_started =
true;
330 std::vector<vpImagePoint> vip = detector.getPolygon(0);
332 vip.push_back(detector.getCog(0));
335 traj_vip =
new std::vector<vpImagePoint>[vip.size()];
337 display_point_trajectory(I, vip, traj_vip);
341 plotter->
plot(1, iter_plot, v_c);
346 std::cout <<
"v_c: " << v_c.t() << std::endl;
351 double error_tr = sqrt(cd_t_c.
sumSquare());
355 ss <<
"error_t: " << error_tr;
358 ss <<
"error_tu: " << error_tu;
362 std::cout <<
"error translation: " << error_tr <<
" ; error rotation: " << error_tu << std::endl;
364 if (error_tr < convergence_threshold_t && error_tu < convergence_threshold_tu) {
365 has_converged =
true;
366 std::cout <<
"Servo task has converged" << std::endl;
379 if (!send_velocities) {
395 send_velocities = !send_velocities;
408 std::cout <<
"Stop the robot " << std::endl;
411 if (opt_plot && plotter !=
nullptr) {
417 while (!final_quit) {
437 std::cout <<
"ViSP exception: " << e.
what() << std::endl;
438 std::cout <<
"Stop the robot " << std::endl;
442 catch (
const franka::NetworkException &e) {
443 std::cout <<
"Franka network exception: " << e.what() << std::endl;
444 std::cout <<
"Check if you are connected to the Franka robot"
445 <<
" or if you specified the right IP using --ip command line option set by default to 192.168.1.1. "
449 catch (
const std::exception &e) {
450 std::cout <<
"Franka exception: " << e.what() << std::endl;
459 #if !defined(VISP_HAVE_REALSENSE2)
460 std::cout <<
"Install librealsense-2.x" << std::endl;
462 #if !defined(VISP_HAVE_FRANKA)
463 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 none
static const vpColor yellow
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 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.
const char * what() const
Class that defines a 3D visual feature from a axis/angle parametrization that represent the rotatio...
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
void buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
static double distance(const vpImagePoint &iP1, const vpImagePoint &iP2)
unsigned int getWidth() const
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...
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.
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()
Implementation of a rotation vector as axis-angle minimal representation.
Class that consider the case of a translation vector.
VISP_EXPORT double measureTimeMs()