61 #include <visp3/core/vpCameraParameters.h> 62 #include <visp3/gui/vpDisplayGDI.h> 63 #include <visp3/gui/vpDisplayX.h> 64 #include <visp3/io/vpImageIo.h> 65 #include <visp3/sensor/vpRealSense2.h> 66 #include <visp3/robot/vpRobotFranka.h> 67 #include <visp3/detection/vpDetectorAprilTag.h> 68 #include <visp3/visual_features/vpFeatureThetaU.h> 69 #include <visp3/visual_features/vpFeatureTranslation.h> 70 #include <visp3/vs/vpServo.h> 71 #include <visp3/vs/vpServoDisplay.h> 72 #include <visp3/gui/vpPlot.h> 74 #if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && \ 75 (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && defined(VISP_HAVE_FRANKA) 78 std::vector<vpImagePoint> *traj_vip)
80 for (
size_t i = 0; i < vip.size(); i++) {
81 if (traj_vip[i].size()) {
84 traj_vip[i].push_back(vip[i]);
88 traj_vip[i].push_back(vip[i]);
91 for (
size_t i = 0; i < vip.size(); i++) {
92 for (
size_t j = 1; j < traj_vip[i].size(); j++) {
98 int main(
int argc,
char **argv)
100 double opt_tagSize = 0.120;
101 std::string opt_robot_ip =
"192.168.1.1";
102 std::string opt_eMc_filename =
"";
103 bool display_tag =
true;
104 int opt_quad_decimate = 2;
105 bool opt_verbose =
false;
106 bool opt_plot =
false;
107 bool opt_adaptive_gain =
false;
108 bool opt_task_sequencing =
false;
109 double convergence_threshold_t = 0.0005, convergence_threshold_tu =
vpMath::rad(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") {
141 std::cout << argv[0] <<
" [--ip <default " << opt_robot_ip <<
">] [--tag_size <marker size in meter; default " << opt_tagSize <<
">] [--eMc <eMc extrinsic file>] " 142 <<
"[--quad_decimate <decimation; default " << opt_quad_decimate <<
">] [--adaptive_gain] [--plot] [--task_sequencing] [--no-convergence-threshold] [--verbose] [--help] [-h]" 155 unsigned int width = 640, height = 480;
156 config.enable_stream(RS2_STREAM_COLOR, 640, 480, RS2_FORMAT_RGBA8, 30);
157 config.enable_stream(RS2_STREAM_DEPTH, 640, 480, RS2_FORMAT_Z16, 30);
158 config.enable_stream(RS2_STREAM_INFRARED, 640, 480, RS2_FORMAT_Y8, 30);
164 ePc[0] = 0.0337731; ePc[1] = -0.00535012; ePc[2] = -0.0523339;
165 ePc[3] = -0.247294; ePc[4] = -0.306729; ePc[5] = 1.53055;
168 if (!opt_eMc_filename.empty()) {
169 ePc.
loadYAML(opt_eMc_filename, ePc);
172 std::cout <<
"Warning, opt_eMc_filename is empty! Use hard coded values." <<
"\n";
175 std::cout <<
"eMc:\n" << eMc <<
"\n";
179 std::cout <<
"cam:\n" << cam <<
"\n";
183 #if defined(VISP_HAVE_X11) 185 #elif defined(VISP_HAVE_GDI) 219 if (opt_adaptive_gain) {
227 vpPlot *plotter =
nullptr;
231 plotter =
new vpPlot(2, static_cast<int>(250 * 2), 500, static_cast<int>(I.
getWidth()) + 80, 10,
"Real time curves plotter");
232 plotter->
setTitle(0,
"Visual features error");
233 plotter->
setTitle(1,
"Camera velocities");
236 plotter->
setLegend(0, 0,
"error_feat_tx");
237 plotter->
setLegend(0, 1,
"error_feat_ty");
238 plotter->
setLegend(0, 2,
"error_feat_tz");
239 plotter->
setLegend(0, 3,
"error_feat_theta_ux");
240 plotter->
setLegend(0, 4,
"error_feat_theta_uy");
241 plotter->
setLegend(0, 5,
"error_feat_theta_uz");
250 bool final_quit =
false;
251 bool has_converged =
false;
252 bool send_velocities =
false;
253 bool servo_started =
false;
254 std::vector<vpImagePoint> *traj_vip =
nullptr;
261 while (!has_converged && !final_quit) {
268 std::vector<vpHomogeneousMatrix> cMo_vec;
269 detector.
detect(I, opt_tagSize, cam, cMo_vec);
271 std::stringstream ss;
272 ss <<
"Left click to " << (send_velocities ?
"stop the robot" :
"servo the robot") <<
", right click to quit.";
278 if (cMo_vec.size() == 1) {
281 static bool first_time =
true;
284 std::vector<vpHomogeneousMatrix> v_oMo(2), v_cdMc(2);
285 v_oMo[1].buildFrom(0, 0, 0, 0, 0, M_PI);
286 for (
size_t i = 0; i < 2; i++) {
287 v_cdMc[i] = cdMo * v_oMo[i] * cMo.
inverse();
289 if (std::fabs(v_cdMc[0].getThetaUVector().getTheta()) < std::fabs(v_cdMc[1].getThetaUVector().getTheta())) {
293 std::cout <<
"Desired frame modified to avoid PI rotation of the camera" << std::endl;
299 cdMc = cdMo * oMo * cMo.
inverse();
303 if (opt_task_sequencing) {
304 if (! servo_started) {
305 if (send_velocities) {
306 servo_started =
true;
320 std::vector<vpImagePoint> vip = detector.
getPolygon(0);
322 vip.push_back(detector.
getCog(0));
325 traj_vip =
new std::vector<vpImagePoint> [vip.size()];
327 display_point_trajectory(I, vip, traj_vip);
331 plotter->
plot(1, iter_plot, v_c);
336 std::cout <<
"v_c: " << v_c.t() << std::endl;
341 double error_tr = sqrt(cd_t_c.
sumSquare());
345 ss <<
"error_t: " << error_tr;
348 ss <<
"error_tu: " << error_tu;
352 std::cout <<
"error translation: " << error_tr <<
" ; error rotation: " << error_tu << std::endl;
354 if (error_tr < convergence_threshold_t && error_tu < convergence_threshold_tu) {
355 has_converged =
true;
356 std::cout <<
"Servo task has converged" << std::endl;;
368 if (!send_velocities) {
384 send_velocities = !send_velocities;
397 std::cout <<
"Stop the robot " << std::endl;
400 if (opt_plot && plotter !=
nullptr) {
408 while (!final_quit) {
428 std::cout <<
"ViSP exception: " << e.
what() << std::endl;
429 std::cout <<
"Stop the robot " << std::endl;
433 catch(
const franka::NetworkException &e) {
434 std::cout <<
"Franka network exception: " << e.what() << std::endl;
435 std::cout <<
"Check if you are connected to the Franka robot" 436 <<
" or if you specified the right IP using --ip command line option set by default to 192.168.1.1. " << std::endl;
439 catch(
const std::exception &e) {
440 std::cout <<
"Franka exception: " << e.what() << std::endl;
449 #if !defined(VISP_HAVE_REALSENSE2) 450 std::cout <<
"Install librealsense-2.x" << std::endl;
452 #if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11) 453 std::cout <<
"Build ViSP with c++11 or higher compiler flag (cmake -DUSE_CXX_STANDARD=11)." << std::endl;
455 #if !defined(VISP_HAVE_FRANKA) 456 std::cout <<
"Install libfranka." << std::endl;
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel)
Adaptive gain computation.
Class that defines the translation visual feature .
static bool getClick(const vpImage< unsigned char > &I, bool blocking=true)
void setAprilTagPoseEstimationMethod(const vpPoseEstimationMethod &poseEstimationMethod)
static bool loadYAML(const std::string &filename, vpArray2D< Type > &A, char *header=NULL)
vpRobot::vpRobotStateType setRobotState(vpRobot::vpRobotStateType newState)
Implementation of an homogeneous matrix and operations on such kind of matrices.
AprilTag 36h11 pattern (recommended)
void addFeature(vpBasicFeature &s, vpBasicFeature &s_star, unsigned int select=vpBasicFeature::FEATURE_ALL)
Display for windows using GDI (available on any windows 32 platform).
static void displayText(const vpImage< unsigned char > &I, const vpImagePoint &ip, const std::string &s, const vpColor &color)
Use the X11 console to display images on unix-like OS. Thus to enable this class X11 should be instal...
static const vpColor none
error that can be emited by ViSP classes.
vpHomogeneousMatrix inverse() const
void open(const rs2::config &cfg=rs2::config())
static const vpColor green
void setLegend(unsigned int graphNum, unsigned int curveNum, const std::string &legend)
vpThetaUVector getThetaUVector() const
static void flush(const vpImage< unsigned char > &I)
VISP_EXPORT double measureTimeMs()
Implementation of a rotation matrix and operations on such kind of matrices.
void set_eMc(const vpHomogeneousMatrix &eMc)
void setAprilTagQuadDecimate(float quadDecimate)
Initialize the velocity controller.
vpColVector computeControlLaw()
static void display(const vpImage< unsigned char > &I)
Generic class defining intrinsic camera parameters.
void setTitle(unsigned int graphNum, const std::string &title)
void plot(unsigned int graphNum, unsigned int curveNum, double x, double y)
void acquire(vpImage< unsigned char > &grey)
vpImagePoint getCog(size_t i) const
void buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
void setInteractionMatrixType(const vpServoIteractionMatrixType &interactionMatrixType, const vpServoInversionType &interactionMatrixInversion=PSEUDO_INVERSE)
const char * what() const
static double rad(double deg)
Stops robot motion especially in velocity and acceleration control.
void initGraph(unsigned int graphNum, unsigned int curveNbr)
vpTranslationVector getTranslationVector() const
static double deg(double rad)
Implementation of column vector and the associated operations.
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))
void setDisplayTag(bool display, const vpColor &color=vpColor::none, unsigned int thickness=2)
vpCameraParameters getCameraParameters(const rs2_stream &stream, vpCameraParameters::vpCameraParametersProjType type=vpCameraParameters::perspectiveProjWithDistortion) const
Implementation of a pose vector and operations on poses.
Class that defines a 3D visual feature from a axis/angle parametrization that represent the rotatio...
void connect(const std::string &franka_address, franka::RealtimeConfig realtime_config=franka::RealtimeConfig::kEnforce)
This class enables real time drawing of 2D or 3D graphics. An instance of the class open a window whi...
vpColVector getError() const
static const vpColor yellow
unsigned int getWidth() const
void setServo(const vpServoType &servo_type)
static void displayLine(const vpImage< unsigned char > &I, const vpImagePoint &ip1, const vpImagePoint &ip2, const vpColor &color, unsigned int thickness=1, bool segment=true)
Class that consider the case of a translation vector.
Implementation of a rotation vector as axis-angle minimal representation.
static double distance(const vpImagePoint &iP1, const vpImagePoint &iP2)
std::vector< std::vector< vpImagePoint > > & getPolygon()
bool detect(const vpImage< unsigned char > &I)