42 #include <visp3/core/vpConfig.h> 43 #include <visp3/core/vpMomentAreaNormalized.h> 44 #include <visp3/core/vpMomentBasic.h> 45 #include <visp3/core/vpMomentCentered.h> 46 #include <visp3/core/vpMomentDatabase.h> 47 #include <visp3/core/vpMomentGravityCenter.h> 48 #include <visp3/core/vpMomentGravityCenterNormalized.h> 49 #include <visp3/core/vpMomentObject.h> 50 #include <visp3/core/vpPixelMeterConversion.h> 51 #include <visp3/core/vpPoint.h> 52 #include <visp3/core/vpTime.h> 53 #include <visp3/detection/vpDetectorAprilTag.h> 54 #include <visp3/gui/vpDisplayX.h> 55 #include <visp3/gui/vpPlot.h> 56 #include <visp3/robot/vpRobotBebop2.h> 57 #include <visp3/visual_features/vpFeatureBuilder.h> 58 #include <visp3/visual_features/vpFeatureMomentAreaNormalized.h> 59 #include <visp3/visual_features/vpFeatureMomentGravityCenterNormalized.h> 60 #include <visp3/visual_features/vpFeatureVanishingPoint.h> 61 #include <visp3/vs/vpServo.h> 62 #include <visp3/vs/vpServoDisplay.h> 63 #include <visp3/core/vpXmlParserCamera.h> 65 #if !defined(VISP_HAVE_ARSDK) 68 std::cout <<
"\nThis example requires Parrot ARSDK3 library. You should install it.\n" << std::endl;
71 #elif !defined(VISP_HAVE_FFMPEG) 74 std::cout <<
"\nThis example requires ffmpeg library. You should install it.\n" << std::endl;
77 #elif (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11) 80 std::cout <<
"\nThis example requires cxx11 standard or higher. Turn it on using cmake -DUSE_CXX_STANDARD=11.\n" << std::endl;
85 bool compareImagePoint(std::pair<size_t, vpImagePoint> p1, std::pair<size_t, vpImagePoint> p2)
87 return (p1.second.get_v() < p2.second.get_v());
101 int main(
int argc,
char **argv)
105 std::string ip_address =
"192.168.42.1";
106 std::string opt_cam_parameters;
107 bool opt_has_cam_parameters =
false;
111 double opt_distance_to_tag = -1;
112 bool opt_has_distance_to_tag =
false;
116 bool verbose =
false;
118 if (argc >= 3 && std::string(argv[1]) ==
"--tag_size") {
119 tagSize = std::atof(argv[2]);
121 std::cout <<
"Error : invalid tag size." << std::endl <<
"See " << argv[0] <<
" --help" << std::endl;
124 for (
int i = 3; i < argc; i++) {
125 if (std::string(argv[i]) ==
"--ip" && i + 1 < argc) {
126 ip_address = std::string(argv[i + 1]);
128 }
else if (std::string(argv[i]) ==
"--distance_to_tag" && i + 1 < argc) {
129 opt_distance_to_tag = std::atof(argv[i + 1]);
130 if (opt_distance_to_tag <= 0) {
131 std::cout <<
"Error : invalid distance to tag." << std::endl <<
"See " << argv[0] <<
" --help" << std::endl;
134 opt_has_distance_to_tag =
true;
136 }
else if (std::string(argv[i]) ==
"--intrinsic") {
138 opt_cam_parameters = std::string(argv[i + 1]);
139 opt_has_cam_parameters =
true;
141 }
else if (std::string(argv[i]) ==
"--hd_stream") {
143 }
else if (std::string(argv[i]) ==
"--verbose" || std::string(argv[i]) ==
"-v") {
146 std::cout <<
"Error : unknown parameter " << argv[i] << std::endl
147 <<
"See " << argv[0] <<
" --help" << std::endl;
151 }
else if (argc >= 2 && (std::string(argv[1]) ==
"--help" || std::string(argv[1]) ==
"-h")) {
152 std::cout <<
"\nUsage:\n" 154 <<
" [--tag_size <size>] [--ip <drone ip>] [--distance_to_tag <distance>] [--intrinsic <xml file>] " 155 <<
"[--hd_stream] [--verbose] [-v] [--help] [-h]\n" 158 <<
" --tag_size <size>\n" 159 <<
" The size of the tag to detect in meters, required.\n\n" 160 <<
" --ip <drone ip>\n" 161 <<
" Ip address of the drone to which you want to connect (default : 192.168.42.1).\n\n" 162 <<
" --distance_to_tag <distance>\n" 163 <<
" The desired distance to the tag in meters (default: 1 meter).\n\n" 164 <<
" --intrinsic <xml file>\n" 165 <<
" XML file containing computed intrinsic camera parameters (default: empty).\n\n" 167 <<
" Enables HD 720p streaming instead of default 480p.\n" 168 <<
" Allows to increase range and accuracy of the tag detection,\n" 169 <<
" but increases latency and computation time.\n" 170 <<
" Caution: camera calibration settings are different for the two resolutions.\n" 171 <<
" Make sure that if you pass custom intrinsic camera parameters,\n" 172 <<
" they were obtained with the correct resolution.\n\n" 173 <<
" --verbose, -v\n" 174 <<
" Enables verbose (drone information messages and velocity commands\n" 175 <<
" are then displayed).\n\n" 177 <<
" Print help message.\n" 182 std::cout <<
"Error : tag size parameter required." << std::endl <<
"See " << argv[0] <<
" --help" << std::endl;
187 <<
"\nWARNING: \n - This program does no sensing or avoiding of " 189 "the drone WILL collide with any objects in the way! Make sure " 191 "drone has approximately 3 meters of free space on all sides.\n" 192 " - The drone uses a downward-facing camera for horizontal speed estimation,\n make sure the drone flies " 193 "above a non-uniform flooring,\n or its movement will be inacurate and dangerous !\n" 198 verbose,
true, ip_address);
200 if (drone.isRunning()) {
202 drone.setVideoResolution(stream_res);
204 drone.setStreamingMode(0);
205 drone.setVideoStabilisationMode(0);
209 drone.startStreaming();
211 drone.setExposure(1.5f);
213 drone.setCameraOrientation(-5., 0.,
219 drone.getGrayscaleImage(I);
221 #if defined VISP_HAVE_X11 223 #elif defined VISP_HAVE_GTK 225 #elif defined VISP_HAVE_GDI 227 #elif defined VISP_HAVE_OPENCV 230 int orig_displayX = 100;
231 int orig_displayY = 100;
232 display.
init(I, orig_displayX, orig_displayY,
"DRONE VIEW");
236 vpPlot plotter(1, 700, 700, orig_displayX + static_cast<int>(I.
getWidth()) + 20, orig_displayY,
237 "Visual servoing tasks");
238 unsigned int iter = 0;
248 if (opt_has_cam_parameters) {
255 std::cout <<
"Cannot find parameters in XML file " << opt_cam_parameters << std::endl;
256 if (drone.getVideoHeight() == 720) {
263 std::cout <<
"Setting default camera parameters ... " << std::endl;
264 if (drone.getVideoHeight() == 720) {
312 double Z_d = (opt_has_distance_to_tag ? opt_distance_to_tag : 1.);
315 double X[4] = {tagSize / 2., tagSize / 2., -tagSize / 2., -tagSize / 2.};
316 double Y[4] = {tagSize / 2., -tagSize / 2., -tagSize / 2., tagSize / 2.};
317 std::vector<vpPoint> vec_P, vec_P_d;
319 for (
int i = 0; i < 4; i++) {
323 vec_P_d.push_back(P_d);
335 m_obj_d.fromVector(vec_P_d);
348 area = mb_d.
get(2, 0) + mb_d.
get(0, 2);
350 area = mb_d.
get(0, 0);
352 man_d.setDesiredArea(area);
360 double C = 1.0 / Z_d;
372 plotter.initGraph(0, 4);
373 plotter.setLegend(0, 0,
"Xn");
374 plotter.setLegend(0, 1,
"Yn");
375 plotter.setLegend(0, 2,
"an");
376 plotter.setLegend(0, 3,
"atan(1/rho)");
379 s_mgn_d.update(A, B, C);
380 s_mgn_d.compute_interaction();
382 s_man_d.update(A, B, C);
383 s_man_d.compute_interaction();
390 bool vec_ip_has_been_sorted =
false;
391 std::vector<std::pair<size_t, vpImagePoint> > vec_ip_sorted;
394 while (drone.isRunning() && drone.isStreaming() && runLoop) {
398 drone.getGrayscaleImage(I);
401 std::vector<vpHomogeneousMatrix> cMo_vec;
402 detector.
detect(I, tagSize, cam, cMo_vec);
406 std::stringstream ss;
407 ss <<
"Detection time: " << t <<
" ms";
414 std::vector<vpImagePoint> vec_ip = detector.
getPolygon(0);
416 for (
size_t i = 0; i < vec_ip.size(); i++) {
427 m_obj.fromVector(vec_P);
436 man.setDesiredArea(area);
440 s_mgn.update(A, B, C);
441 s_mgn.compute_interaction();
442 s_man.update(A, B, C);
443 s_man.compute_interaction();
448 if (!vec_ip_has_been_sorted) {
449 for (
size_t i = 0; i < vec_ip.size(); i++) {
452 std::pair<size_t, vpImagePoint> index_pair = std::pair<size_t, vpImagePoint>(i, vec_ip[i]);
453 vec_ip_sorted.push_back(index_pair);
457 std::sort(vec_ip_sorted.begin(), vec_ip_sorted.end(), compareImagePoint);
459 vec_ip_has_been_sorted =
true;
464 vec_ip[vec_ip_sorted[2].first], vec_ip[vec_ip_sorted[3].first],
475 std::cout <<
"ve: " << ve.
t() << std::endl;
477 drone.setVelocity(ve, 1.0);
479 for (
size_t i = 0; i < 4; i++) {
481 std::stringstream ss;
504 std::stringstream sserr;
505 sserr <<
"Failed to detect an Apriltag, or detected multiple ones";
518 plotter.plot(0, iter, task.
getError());
521 std::stringstream sstime;
522 sstime <<
"Total time: " << totalTime <<
" ms";
533 std::cout <<
"ERROR : failed to setup drone control." << std::endl;
537 std::cout <<
"Caught an exception: " << e << std::endl;
542 #endif // #elif !defined(VISP_HAVE_FFMPEG)
Implementation of a matrix and operations on matrices.
VISP_EXPORT int wait(double t0, double t)
Adaptive gain computation.
Class handling the normalized surface moment that is invariant in scale and used to estimate depth...
static bool getClick(const vpImage< unsigned char > &I, bool blocking=true)
This class defines the 2D basic moment . This class is a wrapper for vpMomentObject wich allows to us...
Implementation of an homogeneous matrix and operations on such kind of matrices.
static unsigned int selectAtanOneOverRho()
AprilTag 36h11 pattern (recommended)
Class describing 2D normalized gravity center moment.
void addFeature(vpBasicFeature &s, vpBasicFeature &s_star, unsigned int select=vpBasicFeature::FEATURE_ALL)
Display for windows using GDI (available on any windows 32 platform).
void set_eJe(const vpMatrix &eJe_)
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...
void linkTo(vpMomentDatabase &moments)
error that can be emited by ViSP classes.
void init(vpImage< unsigned char > &I, int winx=-1, int winy=-1, const std::string &title="")
Class for generic objects.
vpHomogeneousMatrix inverse() const
static void convertPoint(const vpCameraParameters &cam, const double &u, const double &v, double &x, double &y)
size_t getNbObjects() const
XML parser to load and save intrinsic camera parameters.
static const vpColor green
static void flush(const vpImage< unsigned char > &I)
VISP_EXPORT double measureTimeMs()
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.
Implementation of a rotation matrix and operations on such kind of matrices.
Functionality computation for normalized surface moment feature. Computes the interaction matrix asso...
void set_y(double y)
Set the point y coordinate in the image plane.
Functionality computation for centered and normalized moment feature. Computes the interaction matrix...
void setAprilTagQuadDecimate(float quadDecimate)
const std::vector< double > & get() const
static void displayPolygon(const vpImage< unsigned char > &I, const std::vector< vpImagePoint > &vip, const vpColor &color, unsigned int thickness=1, bool closed=true)
vpColVector computeControlLaw()
This class allows to register all vpMoments so they can access each other according to their dependen...
vpCameraParametersProjType
static void display(const vpImage< unsigned char > &I)
The vpDisplayOpenCV allows to display image using the OpenCV library. Thus to enable this class OpenC...
Generic class defining intrinsic camera parameters.
void setAprilTagNbThreads(int nThreads)
void setAtanOneOverRho(double atan_one_over_rho)
Set vanishing point feature value.
virtual void updateAll(vpMomentObject &object)
The vpDisplayGTK allows to display image using the GTK 3rd party library. Thus to enable this class G...
This class defines the double-indexed centered moment descriptor .
vpImagePoint getCog(size_t i) const
Class describing 2D gravity center moment.
void setInteractionMatrixType(const vpServoIteractionMatrixType &interactionMatrixType, const vpServoInversionType &interactionMatrixInversion=PSEUDO_INVERSE)
static double rad(double deg)
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)
void initPersProjWithoutDistortion(double px, double py, double u0, double v0)
void setAlpha(double alpha)
Set vanishing point feature value.
static void displayCross(const vpImage< unsigned char > &I, const vpImagePoint &ip, unsigned int size, const vpColor &color, unsigned int thickness=1)
unsigned int getHeight() const
Implementation of column vector and the associated operations.
void setDisplayTag(bool display, const vpColor &color=vpColor::none, unsigned int thickness=2)
void set_cVe(const vpVelocityTwistMatrix &cVe_)
This class enables real time drawing of 2D or 3D graphics. An instance of the class open a window whi...
Implementation of a rotation vector as Euler angle minimal representation.
vpColVector getError() const
Class that defines a 2D point in an image. This class is useful for image processing and stores only ...
static void create(vpFeaturePoint &s, const vpCameraParameters &cam, const vpDot &d)
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.
std::vector< std::vector< vpImagePoint > > & getPolygon()
bool detect(const vpImage< unsigned char > &I)