61 #include <visp3/core/vpCameraParameters.h>
62 #include <visp3/core/vpConfig.h>
63 #include <visp3/detection/vpDetectorAprilTag.h>
64 #include <visp3/gui/vpDisplayGDI.h>
65 #include <visp3/gui/vpDisplayX.h>
66 #include <visp3/gui/vpPlot.h>
67 #include <visp3/io/vpImageIo.h>
68 #include <visp3/robot/vpRobotFranka.h>
69 #include <visp3/sensor/vpRealSense2.h>
70 #include <visp3/visual_features/vpFeatureThetaU.h>
71 #include <visp3/visual_features/vpFeatureTranslation.h>
72 #include <visp3/vs/vpServo.h>
73 #include <visp3/vs/vpServoDisplay.h>
75 #if defined(VISP_HAVE_REALSENSE2) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && defined(VISP_HAVE_FRANKA)
77 #ifdef ENABLE_VISP_NAMESPACE
82 std::vector<vpImagePoint> *traj_vip)
84 for (
size_t i = 0; i < vip.size(); i++) {
85 if (traj_vip[i].size()) {
88 traj_vip[i].push_back(vip[i]);
92 traj_vip[i].push_back(vip[i]);
95 for (
size_t i = 0; i < vip.size(); i++) {
96 for (
size_t j = 1; j < traj_vip[i].size(); j++) {
102 int main(
int argc,
char **argv)
104 double opt_tagSize = 0.120;
105 std::string opt_robot_ip =
"192.168.1.1";
106 std::string opt_eMc_filename =
"";
107 bool display_tag =
true;
108 int opt_quad_decimate = 2;
109 bool opt_verbose =
false;
110 bool opt_plot =
false;
111 bool opt_adaptive_gain =
false;
112 bool opt_task_sequencing =
false;
113 double convergence_threshold_t = 0.0005;
114 double convergence_threshold_tu = 0.5;
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]);
120 else if (std::string(argv[i]) ==
"--ip" && i + 1 < argc) {
121 opt_robot_ip = std::string(argv[i + 1]);
123 else if (std::string(argv[i]) ==
"--eMc" && i + 1 < argc) {
124 opt_eMc_filename = std::string(argv[i + 1]);
126 else if (std::string(argv[i]) ==
"--verbose") {
129 else if (std::string(argv[i]) ==
"--plot") {
132 else if (std::string(argv[i]) ==
"--adaptive_gain") {
133 opt_adaptive_gain =
true;
135 else if (std::string(argv[i]) ==
"--task_sequencing") {
136 opt_task_sequencing =
true;
138 else if (std::string(argv[i]) ==
"--quad_decimate" && i + 1 < argc) {
139 opt_quad_decimate = std::stoi(argv[i + 1]);
141 else if (std::string(argv[i]) ==
"--no-convergence-threshold") {
142 convergence_threshold_t = 0.;
143 convergence_threshold_tu = 0.;
145 else if (std::string(argv[i]) ==
"--help" || std::string(argv[i]) ==
"-h") {
147 << argv[0] <<
" [--ip <default " << opt_robot_ip <<
">] [--tag_size <marker size in meter; default "
148 << opt_tagSize <<
">] [--eMc <eMc extrinsic file>] "
149 <<
"[--quad_decimate <decimation; default " << opt_quad_decimate
150 <<
">] [--adaptive_gain] [--plot] [--task_sequencing] [--no-convergence-threshold] [--verbose] [--help] [-h]"
159 robot.connect(opt_robot_ip);
163 unsigned int width = 640, height = 480;
164 config.enable_stream(RS2_STREAM_COLOR, 640, 480, RS2_FORMAT_RGBA8, 30);
165 config.enable_stream(RS2_STREAM_DEPTH, 640, 480, RS2_FORMAT_Z16, 30);
166 config.enable_stream(RS2_STREAM_INFRARED, 640, 480, RS2_FORMAT_Y8, 30);
173 ePc[1] = -0.00535012;
180 if (!opt_eMc_filename.empty()) {
181 ePc.
loadYAML(opt_eMc_filename, ePc);
184 std::cout <<
"Warning, opt_eMc_filename is empty! Use hard coded values."
188 std::cout <<
"eMc:\n" << eMc <<
"\n";
193 std::cout <<
"cam:\n" << cam <<
"\n";
197 #if defined(VISP_HAVE_X11)
198 vpDisplayX dc(I, 10, 10,
"Color image");
199 #elif defined(VISP_HAVE_GDI)
207 detector.setAprilTagPoseEstimationMethod(poseEstimationMethod);
208 detector.setDisplayTag(display_tag);
209 detector.setAprilTagQuadDecimate(opt_quad_decimate);
233 if (opt_adaptive_gain) {
241 vpPlot *plotter =
nullptr;
245 plotter =
new vpPlot(2,
static_cast<int>(250 * 2), 500,
static_cast<int>(I.
getWidth()) + 80, 10,
246 "Real time curves plotter");
247 plotter->
setTitle(0,
"Visual features error");
248 plotter->
setTitle(1,
"Camera velocities");
251 plotter->
setLegend(0, 0,
"error_feat_tx");
252 plotter->
setLegend(0, 1,
"error_feat_ty");
253 plotter->
setLegend(0, 2,
"error_feat_tz");
254 plotter->
setLegend(0, 3,
"error_feat_theta_ux");
255 plotter->
setLegend(0, 4,
"error_feat_theta_uy");
256 plotter->
setLegend(0, 5,
"error_feat_theta_uz");
265 bool final_quit =
false;
266 bool has_converged =
false;
267 bool send_velocities =
false;
268 bool servo_started =
false;
269 std::vector<vpImagePoint> *traj_vip =
nullptr;
276 while (!has_converged && !final_quit) {
283 std::vector<vpHomogeneousMatrix> cMo_vec;
284 detector.detect(I, opt_tagSize, cam, cMo_vec);
286 std::stringstream ss;
287 ss <<
"Left click to " << (send_velocities ?
"stop the robot" :
"servo the robot") <<
", right click to quit.";
293 if (cMo_vec.size() == 1) {
296 static bool first_time =
true;
299 std::vector<vpHomogeneousMatrix> v_oMo(2), v_cdMc(2);
300 v_oMo[1].buildFrom(0, 0, 0, 0, 0, M_PI);
301 for (
size_t i = 0; i < 2; i++) {
302 v_cdMc[i] = cdMo * v_oMo[i] * cMo.
inverse();
304 if (std::fabs(v_cdMc[0].getThetaUVector().getTheta()) < std::fabs(v_cdMc[1].getThetaUVector().getTheta())) {
308 std::cout <<
"Desired frame modified to avoid PI rotation of the camera" << std::endl;
314 cdMc = cdMo * oMo * cMo.
inverse();
318 if (opt_task_sequencing) {
319 if (!servo_started) {
320 if (send_velocities) {
321 servo_started =
true;
335 std::vector<vpImagePoint> vip = detector.getPolygon(0);
337 vip.push_back(detector.getCog(0));
340 traj_vip =
new std::vector<vpImagePoint>[vip.size()];
342 display_point_trajectory(I, vip, traj_vip);
346 plotter->
plot(1, iter_plot, v_c);
351 std::cout <<
"v_c: " << v_c.t() << std::endl;
356 double error_tr = sqrt(cd_t_c.
sumSquare());
360 ss <<
"error_t: " << error_tr;
363 ss <<
"error_tu: " << error_tu;
367 std::cout <<
"error translation: " << error_tr <<
" ; error rotation: " << error_tu << std::endl;
369 if (error_tr < convergence_threshold_t && error_tu < convergence_threshold_tu) {
370 has_converged =
true;
371 std::cout <<
"Servo task has converged" << std::endl;
384 if (!send_velocities) {
400 send_velocities = !send_velocities;
413 std::cout <<
"Stop the robot " << std::endl;
416 if (opt_plot && plotter !=
nullptr) {
422 while (!final_quit) {
442 std::cout <<
"ViSP exception: " << e.
what() << std::endl;
443 std::cout <<
"Stop the robot " << std::endl;
447 catch (
const franka::NetworkException &e) {
448 std::cout <<
"Franka network exception: " << e.what() << std::endl;
449 std::cout <<
"Check if you are connected to the Franka robot"
450 <<
" or if you specified the right IP using --ip command line option set by default to 192.168.1.1. "
454 catch (
const std::exception &e) {
455 std::cout <<
"Franka exception: " << e.what() << std::endl;
464 #if !defined(VISP_HAVE_REALSENSE2)
465 std::cout <<
"Install librealsense-2.x" << std::endl;
467 #if !defined(VISP_HAVE_FRANKA)
468 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).
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 & buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
vpHomogeneousMatrix inverse() const
vpTranslationVector getTranslationVector() const
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()