36 #include <visp3/core/vpConfig.h>
37 #include <visp3/core/vpMomentAreaNormalized.h>
38 #include <visp3/core/vpMomentBasic.h>
39 #include <visp3/core/vpMomentCentered.h>
40 #include <visp3/core/vpMomentDatabase.h>
41 #include <visp3/core/vpMomentGravityCenter.h>
42 #include <visp3/core/vpMomentGravityCenterNormalized.h>
43 #include <visp3/core/vpMomentObject.h>
44 #include <visp3/core/vpPixelMeterConversion.h>
45 #include <visp3/core/vpPoint.h>
46 #include <visp3/core/vpTime.h>
47 #include <visp3/core/vpXmlParserCamera.h>
48 #include <visp3/detection/vpDetectorAprilTag.h>
49 #include <visp3/gui/vpDisplayFactory.h>
50 #include <visp3/gui/vpPlot.h>
51 #include <visp3/robot/vpRobotBebop2.h>
52 #include <visp3/visual_features/vpFeatureBuilder.h>
53 #include <visp3/visual_features/vpFeatureMomentAreaNormalized.h>
54 #include <visp3/visual_features/vpFeatureMomentGravityCenterNormalized.h>
55 #include <visp3/visual_features/vpFeatureVanishingPoint.h>
56 #include <visp3/vs/vpServo.h>
57 #include <visp3/vs/vpServoDisplay.h>
59 #if !defined(VISP_HAVE_ARSDK)
62 std::cout <<
"\nThis example requires Parrot ARSDK3 library. You should install it.\n" << std::endl;
65 #elif !defined(VISP_HAVE_FFMPEG)
68 std::cout <<
"\nThis example requires ffmpeg library. You should install it.\n" << std::endl;
71 #elif !defined(VISP_HAVE_PUGIXML)
74 std::cout <<
"\nThis example requires pugixml built-in 3rdparty library. You should enable it.\n" << std::endl;
80 #ifdef ENABLE_VISP_NAMESPACE
84 bool compareImagePoint(std::pair<size_t, vpImagePoint> p1, std::pair<size_t, vpImagePoint> p2)
86 return (p1.second.get_v() < p2.second.get_v());
99 int main(
int argc,
char **argv)
101 #if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
102 std::shared_ptr<vpDisplay> display;
108 std::string ip_address =
"192.168.42.1";
109 std::string opt_cam_parameters;
110 bool opt_has_cam_parameters =
false;
114 double opt_distance_to_tag = -1;
115 bool opt_has_distance_to_tag =
false;
119 bool verbose =
false;
121 if (argc >= 3 && std::string(argv[1]) ==
"--tag-size") {
122 tagSize = std::atof(argv[2]);
124 std::cout <<
"Error : invalid tag size." << std::endl <<
"See " << argv[0] <<
" --help" << std::endl;
127 for (
int i = 3; i < argc; i++) {
128 if (std::string(argv[i]) ==
"--ip" && i + 1 < argc) {
129 ip_address = std::string(argv[i + 1]);
132 else if (std::string(argv[i]) ==
"--distance-to-tag" && i + 1 < argc) {
133 opt_distance_to_tag = std::atof(argv[i + 1]);
134 if (opt_distance_to_tag <= 0) {
135 std::cout <<
"Error : invalid distance to tag." << std::endl <<
"See " << argv[0] <<
" --help" << std::endl;
138 opt_has_distance_to_tag =
true;
141 else if (std::string(argv[i]) ==
"--intrinsic") {
143 opt_cam_parameters = std::string(argv[i + 1]);
144 opt_has_cam_parameters =
true;
147 else if (std::string(argv[i]) ==
"--hd_stream") {
150 else if (std::string(argv[i]) ==
"--verbose" || std::string(argv[i]) ==
"-v") {
154 std::cout <<
"Error : unknown parameter " << argv[i] << std::endl
155 <<
"See " << argv[0] <<
" --help" << std::endl;
160 else if (argc >= 2 && (std::string(argv[1]) ==
"--help" || std::string(argv[1]) ==
"-h")) {
161 std::cout <<
"\nUsage:\n"
163 <<
" [--tag-size <size>] [--ip <drone ip>] [--distance-to-tag <distance>] [--intrinsic <xml file>] "
164 <<
"[--hd_stream] [--verbose] [-v] [--help] [-h]\n"
167 <<
" --tag-size <size>\n"
168 <<
" The size of the tag to detect in meters, required.\n\n"
169 <<
" --ip <drone ip>\n"
170 <<
" Ip address of the drone to which you want to connect (default : 192.168.42.1).\n\n"
171 <<
" --distance-to-tag <distance>\n"
172 <<
" The desired distance to the tag in meters (default: 1 meter).\n\n"
173 <<
" --intrinsic <xml file>\n"
174 <<
" XML file containing computed intrinsic camera parameters (default: empty).\n\n"
176 <<
" Enables HD 720p streaming instead of default 480p.\n"
177 <<
" Allows to increase range and accuracy of the tag detection,\n"
178 <<
" but increases latency and computation time.\n"
179 <<
" Caution: camera calibration settings are different for the two resolutions.\n"
180 <<
" Make sure that if you pass custom intrinsic camera parameters,\n"
181 <<
" they were obtained with the correct resolution.\n\n"
182 <<
" --verbose, -v\n"
183 <<
" Enables verbose (drone information messages and velocity commands\n"
184 <<
" are then displayed).\n\n"
186 <<
" Print help message.\n"
191 std::cout <<
"Error : tag size parameter required." << std::endl <<
"See " << argv[0] <<
" --help" << std::endl;
196 <<
"\nWARNING: \n - This program does no sensing or avoiding of "
198 "the drone WILL collide with any objects in the way! Make sure "
200 "drone has approximately 3 meters of free space on all sides.\n"
201 " - The drone uses a downward-facing camera for horizontal speed estimation,\n make sure the drone flies "
202 "above a non-uniform flooring,\n or its movement will be inacurate and dangerous !\n"
207 verbose,
true, ip_address);
209 if (drone.isRunning()) {
211 drone.setVideoResolution(stream_res);
213 drone.setStreamingMode(0);
214 drone.setVideoStabilisationMode(0);
218 drone.startStreaming();
220 drone.setExposure(1.5f);
222 drone.setCameraOrientation(-5., 0.,
228 drone.getGrayscaleImage(I);
230 int orig_displayX = 100;
231 int orig_displayY = 100;
232 #if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
240 vpPlot plotter(1, 700, 700, orig_displayX +
static_cast<int>(I.
getWidth()) + 20, orig_displayY,
241 "Visual servoing tasks");
242 unsigned int iter = 0;
246 detector.setAprilTagQuadDecimate(4.0);
247 detector.setAprilTagNbThreads(4);
248 detector.setDisplayTag(
true);
252 if (opt_has_cam_parameters) {
259 std::cout <<
"Cannot find parameters in XML file " << opt_cam_parameters << std::endl;
260 if (drone.getVideoHeight() == 720) {
269 std::cout <<
"Setting default camera parameters ... " << std::endl;
270 if (drone.getVideoHeight() == 720) {
319 double Z_d = (opt_has_distance_to_tag ? opt_distance_to_tag : 1.);
322 double X[4] = { tagSize / 2., tagSize / 2., -tagSize / 2., -tagSize / 2. };
323 double Y[4] = { tagSize / 2., -tagSize / 2., -tagSize / 2., tagSize / 2. };
324 std::vector<vpPoint> vec_P, vec_P_d;
326 for (
int i = 0; i < 4; i++) {
330 vec_P_d.push_back(P_d);
342 m_obj_d.fromVector(vec_P_d);
355 area = mb_d.
get(2, 0) + mb_d.
get(0, 2);
357 area = mb_d.
get(0, 0);
359 man_d.setDesiredArea(area);
367 double C = 1.0 / Z_d;
379 plotter.initGraph(0, 4);
380 plotter.setLegend(0, 0,
"Xn");
381 plotter.setLegend(0, 1,
"Yn");
382 plotter.setLegend(0, 2,
"an");
383 plotter.setLegend(0, 3,
"atan(1/rho)");
386 s_mgn_d.update(A, B, C);
387 s_mgn_d.compute_interaction();
389 s_man_d.update(A, B, C);
390 s_man_d.compute_interaction();
397 bool vec_ip_has_been_sorted =
false;
398 std::vector<std::pair<size_t, vpImagePoint> > vec_ip_sorted;
401 while (drone.isRunning() && drone.isStreaming() && runLoop) {
405 drone.getGrayscaleImage(I);
408 std::vector<vpHomogeneousMatrix> cMo_vec;
409 detector.detect(I, tagSize, cam, cMo_vec);
413 std::stringstream ss;
414 ss <<
"Detection time: " << t <<
" ms";
418 if (detector.getNbObjects() == 1) {
421 std::vector<vpImagePoint> vec_ip = detector.getPolygon(0);
423 for (
size_t i = 0; i < vec_ip.size(); i++) {
434 m_obj.fromVector(vec_P);
443 man.setDesiredArea(area);
447 s_mgn.update(A, B, C);
448 s_mgn.compute_interaction();
449 s_man.update(A, B, C);
450 s_man.compute_interaction();
455 if (!vec_ip_has_been_sorted) {
456 for (
size_t i = 0; i < vec_ip.size(); i++) {
459 std::pair<size_t, vpImagePoint> index_pair = std::pair<size_t, vpImagePoint>(i, vec_ip[i]);
460 vec_ip_sorted.push_back(index_pair);
464 std::sort(vec_ip_sorted.begin(), vec_ip_sorted.end(), compareImagePoint);
466 vec_ip_has_been_sorted =
true;
471 vec_ip[vec_ip_sorted[2].first], vec_ip[vec_ip_sorted[3].first],
482 std::cout <<
"ve: " << ve.
t() << std::endl;
484 drone.setVelocity(ve, 1.0);
486 for (
size_t i = 0; i < 4; i++) {
488 std::stringstream ss;
512 std::stringstream sserr;
513 sserr <<
"Failed to detect an Apriltag, or detected multiple ones";
526 plotter.plot(0, iter, task.
getError());
529 std::stringstream sstime;
530 sstime <<
"Total time: " << totalTime <<
" ms";
538 #if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
539 if (display !=
nullptr) {
547 std::cout <<
"ERROR : failed to setup drone control." << std::endl;
548 #if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
549 if (display !=
nullptr) {
557 std::cout <<
"Caught an exception: " << e << std::endl;
558 #if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
559 if (display !=
nullptr) {
Adaptive gain computation.
Generic class defining intrinsic camera parameters.
void initPersProjWithoutDistortion(double px, double py, double u0, double v0)
vpCameraParametersProjType
@ perspectiveProjWithoutDistortion
Perspective projection without distortion model.
Implementation of column vector and the associated operations.
static const vpColor green
@ TAG_36h11
AprilTag 36h11 pattern (recommended)
Class that defines generic functionalities for display.
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 displayCross(const vpImage< unsigned char > &I, const vpImagePoint &ip, unsigned int size, const vpColor &color, unsigned int thickness=1)
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)
static void displayPolygon(const vpImage< unsigned char > &I, const std::vector< vpImagePoint > &vip, const vpColor &color, unsigned int thickness=1, bool closed=true)
error that can be emitted by ViSP classes.
static void create(vpFeaturePoint &s, const vpCameraParameters &cam, const vpImagePoint &t)
Functionality computation for normalized surface moment feature. Computes the interaction matrix asso...
Functionality computation for centered and normalized moment feature. Computes the interaction matrix...
static unsigned int selectAtanOneOverRho()
void setAlpha(double alpha)
Set vanishing point feature value.
void setAtanOneOverRho(double atan_one_over_rho)
Set vanishing point feature value.
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 ...
unsigned int getWidth() const
unsigned int getHeight() const
static double rad(double deg)
Implementation of a matrix and operations on matrices.
Class handling the normalized surface moment that is invariant in scale and used to estimate depth.
This class defines the 2D basic moment . This class is a wrapper for vpMomentObject which allows to u...
const std::vector< double > & get() const
This class defines the double-indexed centered moment descriptor .
This class allows to register all vpMoments so they can access each other according to their dependen...
virtual void updateAll(vpMomentObject &object)
Class describing 2D normalized gravity center moment.
Class describing 2D gravity center moment.
Class for generic objects.
void linkTo(vpMomentDatabase &moments)
static void convertPoint(const vpCameraParameters &cam, const double &u, const double &v, double &x, double &y)
This class enables real time drawing of 2D or 3D graphics. An instance of the class open a window whi...
Class that defines a 3D point in the object frame and allows forward projection of a 3D point in the ...
void set_x(double x)
Set the point x coordinate in the image plane.
void set_y(double y)
Set the point y coordinate in the image plane.
Implementation of a rotation matrix and operations on such kind of matrices.
Implementation of a rotation vector as Euler angle minimal representation.
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 set_cVe(const vpVelocityTwistMatrix &cVe_)
void set_eJe(const vpMatrix &eJe_)
void setServo(const vpServoType &servo_type)
vpColVector getError() const
vpColVector computeControlLaw()
Class that consider the case of a translation vector.
XML parser to load and save intrinsic camera parameters.
int parse(vpCameraParameters &cam, const std::string &filename, const std::string &camera_name, const vpCameraParameters::vpCameraParametersProjType &projModel, unsigned int image_width=0, unsigned int image_height=0, bool verbose=true)
std::shared_ptr< vpDisplay > createDisplay()
Return a smart pointer vpDisplay specialization if a GUI library is available or nullptr otherwise.
vpDisplay * allocateDisplay()
Return a newly allocated vpDisplay specialization if a GUI library is available or nullptr otherwise.
VISP_EXPORT int wait(double t0, double t)
VISP_EXPORT double measureTimeMs()