58 #include <visp3/core/vpCameraParameters.h>
59 #include <visp3/core/vpConfig.h>
60 #include <visp3/detection/vpDetectorAprilTag.h>
61 #include <visp3/gui/vpDisplayGDI.h>
62 #include <visp3/gui/vpDisplayX.h>
63 #include <visp3/gui/vpPlot.h>
64 #include <visp3/io/vpImageIo.h>
65 #include <visp3/robot/vpRobotUniversalRobots.h>
66 #include <visp3/sensor/vpRealSense2.h>
67 #include <visp3/visual_features/vpFeatureThetaU.h>
68 #include <visp3/visual_features/vpFeatureTranslation.h>
69 #include <visp3/vs/vpServo.h>
70 #include <visp3/vs/vpServoDisplay.h>
72 #if defined(VISP_HAVE_REALSENSE2) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && defined(VISP_HAVE_UR_RTDE)
74 #ifdef ENABLE_VISP_NAMESPACE
79 std::vector<vpImagePoint> *traj_vip)
81 for (
size_t i = 0; i < vip.size(); i++) {
82 if (traj_vip[i].size()) {
85 traj_vip[i].push_back(vip[i]);
89 traj_vip[i].push_back(vip[i]);
92 for (
size_t i = 0; i < vip.size(); i++) {
93 for (
size_t j = 1; j < traj_vip[i].size(); j++) {
99 int main(
int argc,
char **argv)
101 double opt_tagSize = 0.120;
102 std::string opt_robot_ip =
"192.168.0.100";
103 std::string opt_eMc_filename =
"";
104 bool display_tag =
true;
105 int opt_quad_decimate = 2;
106 bool opt_verbose =
false;
107 bool opt_plot =
false;
108 bool opt_adaptive_gain =
false;
109 bool opt_task_sequencing =
false;
110 double convergence_threshold_t = 0.0005;
111 double convergence_threshold_tu = 0.5;
113 for (
int i = 1; i < argc; i++) {
114 if (std::string(argv[i]) ==
"--tag_size" && i + 1 < argc) {
115 opt_tagSize = std::stod(argv[i + 1]);
117 else if (std::string(argv[i]) ==
"--ip" && i + 1 < argc) {
118 opt_robot_ip = std::string(argv[i + 1]);
120 else if (std::string(argv[i]) ==
"--eMc" && i + 1 < argc) {
121 opt_eMc_filename = std::string(argv[i + 1]);
123 else if (std::string(argv[i]) ==
"--verbose") {
126 else if (std::string(argv[i]) ==
"--plot") {
129 else if (std::string(argv[i]) ==
"--adaptive_gain") {
130 opt_adaptive_gain =
true;
132 else if (std::string(argv[i]) ==
"--task_sequencing") {
133 opt_task_sequencing =
true;
135 else if (std::string(argv[i]) ==
"--quad_decimate" && i + 1 < argc) {
136 opt_quad_decimate = std::stoi(argv[i + 1]);
138 else if (std::string(argv[i]) ==
"--no-convergence-threshold") {
139 convergence_threshold_t = 0.;
140 convergence_threshold_tu = 0.;
142 else if (std::string(argv[i]) ==
"--help" || std::string(argv[i]) ==
"-h") {
144 << argv[0] <<
" [--ip <default " << opt_robot_ip <<
">] [--tag_size <marker size in meter; default "
145 << opt_tagSize <<
">] [--eMc <eMc extrinsic file>] "
146 <<
"[--quad_decimate <decimation; default " << opt_quad_decimate
147 <<
">] [--adaptive_gain] [--plot] [--task_sequencing] [--no-convergence-threshold] [--verbose] [--help] [-h]"
156 robot.connect(opt_robot_ip);
158 std::cout <<
"WARNING: This example will move the robot! "
159 <<
"Please make sure to have the user stop button at hand!" << std::endl
160 <<
"Press Enter to continue..." << std::endl;
173 std::cout <<
"Move to joint position: " << q.t() << std::endl;
179 unsigned int width = 640, height = 480;
180 config.enable_stream(RS2_STREAM_COLOR, 640, 480, RS2_FORMAT_RGBA8, 30);
181 config.enable_stream(RS2_STREAM_DEPTH, 640, 480, RS2_FORMAT_Z16, 30);
182 config.enable_stream(RS2_STREAM_INFRARED, 640, 480, RS2_FORMAT_Y8, 30);
191 ePc[3] = -0.00506562;
192 ePc[4] = -0.00293325;
196 if (!opt_eMc_filename.empty()) {
197 ePc.
loadYAML(opt_eMc_filename, ePc);
200 std::cout <<
"Warning, opt_eMc_filename is empty! Use hard coded values."
204 std::cout <<
"eMc:\n" << eMc <<
"\n";
209 std::cout <<
"cam:\n" << cam <<
"\n";
213 #if defined(VISP_HAVE_X11)
214 vpDisplayX dc(I, 10, 10,
"Color image");
215 #elif defined(VISP_HAVE_GDI)
223 detector.setAprilTagPoseEstimationMethod(poseEstimationMethod);
224 detector.setDisplayTag(display_tag);
225 detector.setAprilTagQuadDecimate(opt_quad_decimate);
238 tu.buibuildFromld(cdMc);
249 if (opt_adaptive_gain) {
257 vpPlot *plotter =
nullptr;
261 plotter =
new vpPlot(2,
static_cast<int>(250 * 2), 500,
static_cast<int>(I.
getWidth()) + 80, 10,
262 "Real time curves plotter");
263 plotter->
setTitle(0,
"Visual features error");
264 plotter->
setTitle(1,
"Camera velocities");
267 plotter->
setLegend(0, 0,
"error_feat_tx");
268 plotter->
setLegend(0, 1,
"error_feat_ty");
269 plotter->
setLegend(0, 2,
"error_feat_tz");
270 plotter->
setLegend(0, 3,
"error_feat_theta_ux");
271 plotter->
setLegend(0, 4,
"error_feat_theta_uy");
272 plotter->
setLegend(0, 5,
"error_feat_theta_uz");
281 bool final_quit =
false;
282 bool has_converged =
false;
283 bool send_velocities =
false;
284 bool servo_started =
false;
285 std::vector<vpImagePoint> *traj_vip =
nullptr;
292 while (!has_converged && !final_quit) {
299 std::vector<vpHomogeneousMatrix> cMo_vec;
300 detector.detect(I, opt_tagSize, cam, cMo_vec);
302 std::stringstream ss;
303 ss <<
"Left click to " << (send_velocities ?
"stop the robot" :
"servo the robot") <<
", right click to quit.";
309 if (cMo_vec.size() == 1) {
312 static bool first_time =
true;
315 std::vector<vpHomogeneousMatrix> v_oMo(2), v_cdMc(2);
316 v_oMo[1].buildFrom(0, 0, 0, 0, 0, M_PI);
317 for (
size_t i = 0; i < 2; i++) {
318 v_cdMc[i] = cdMo * v_oMo[i] * cMo.
inverse();
320 if (std::fabs(v_cdMc[0].getThetaUVector().getTheta()) < std::fabs(v_cdMc[1].getThetaUVector().getTheta())) {
324 std::cout <<
"Desired frame modified to avoid PI rotation of the camera" << std::endl;
330 cdMc = cdMo * oMo * cMo.
inverse();
334 if (opt_task_sequencing) {
335 if (!servo_started) {
336 if (send_velocities) {
337 servo_started =
true;
351 std::vector<vpImagePoint> vip = detector.getPolygon(0);
353 vip.push_back(detector.getCog(0));
356 traj_vip =
new std::vector<vpImagePoint>[vip.size()];
358 display_point_trajectory(I, vip, traj_vip);
362 plotter->
plot(1, iter_plot, v_c);
367 std::cout <<
"v_c: " << v_c.t() << std::endl;
372 double error_tr = sqrt(cd_t_c.
sumSquare());
376 ss <<
"error_t: " << error_tr;
379 ss <<
"error_tu: " << error_tu;
383 std::cout <<
"error translation: " << error_tr <<
" ; error rotation: " << error_tu << std::endl;
385 if (error_tr < convergence_threshold_t && error_tu < convergence_threshold_tu) {
386 has_converged =
true;
387 std::cout <<
"Servo task has converged" << std::endl;
400 if (!send_velocities) {
416 send_velocities = !send_velocities;
429 std::cout <<
"Stop the robot " << std::endl;
432 if (opt_plot && plotter !=
nullptr) {
438 while (!final_quit) {
458 std::cout <<
"ViSP exception: " << e.
what() << std::endl;
459 std::cout <<
"Stop the robot " << std::endl;
463 catch (
const std::exception &e) {
464 std::cout <<
"ur_rtde exception: " << e.what() << std::endl;
473 #if !defined(VISP_HAVE_REALSENSE2)
474 std::cout <<
"Install librealsense-2.x" << std::endl;
476 #if !defined(VISP_HAVE_UR_RTDE)
477 std::cout <<
"ViSP is not build with libur_rtde 3rd party used to control a robot from Universal Robots..."
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 rad(double deg)
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_POSITION_CONTROL
Initialize the position controller.
@ 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()