5 #include <visp3/core/vpConfig.h>
8 #if defined(VISP_HAVE_APRILTAG) && defined(VISP_HAVE_REALSENSE2) && defined(VISP_HAVE_MODULE_MBT)
14 #include <visp3/detection/vpDetectorAprilTag.h>
15 #include <visp3/gui/vpDisplayFactory.h>
16 #include <visp3/mbt/vpMbGenericTracker.h>
17 #include <visp3/sensor/vpRealSense2.h>
19 #ifdef ENABLE_VISP_NAMESPACE
23 typedef enum { state_detection, state_tracking, state_quit } state_t;
27 void createCaoFile(
double cubeEdgeSize)
29 std::ofstream fileStream;
30 fileStream.open(
"cube.cao", std::ofstream::out | std::ofstream::trunc);
32 fileStream <<
"# 3D Points\n";
33 fileStream <<
"8 # Number of points\n";
34 fileStream << cubeEdgeSize / 2 <<
" " << cubeEdgeSize / 2 <<
" " << 0 <<
" # Point 0: (X, Y, Z)\n";
35 fileStream << cubeEdgeSize / 2 <<
" " << -cubeEdgeSize / 2 <<
" " << 0 <<
" # Point 1\n";
36 fileStream << -cubeEdgeSize / 2 <<
" " << -cubeEdgeSize / 2 <<
" " << 0 <<
" # Point 2\n";
37 fileStream << -cubeEdgeSize / 2 <<
" " << cubeEdgeSize / 2 <<
" " << 0 <<
" # Point 3\n";
38 fileStream << -cubeEdgeSize / 2 <<
" " << cubeEdgeSize / 2 <<
" " << -cubeEdgeSize <<
" # Point 4\n";
39 fileStream << -cubeEdgeSize / 2 <<
" " << -cubeEdgeSize / 2 <<
" " << -cubeEdgeSize <<
" # Point 5\n";
40 fileStream << cubeEdgeSize / 2 <<
" " << -cubeEdgeSize / 2 <<
" " << -cubeEdgeSize <<
" # Point 6\n";
41 fileStream << cubeEdgeSize / 2 <<
" " << cubeEdgeSize / 2 <<
" " << -cubeEdgeSize <<
" # Point 7\n";
42 fileStream <<
"# 3D Lines\n";
43 fileStream <<
"0 # Number of lines\n";
44 fileStream <<
"# Faces from 3D lines\n";
45 fileStream <<
"0 # Number of faces\n";
46 fileStream <<
"# Faces from 3D points\n";
47 fileStream <<
"6 # Number of faces\n";
48 fileStream <<
"4 0 3 2 1 # Face 0: [number of points] [index of the 3D points]...\n";
49 fileStream <<
"4 1 2 5 6\n";
50 fileStream <<
"4 4 7 6 5\n";
51 fileStream <<
"4 0 7 4 3\n";
52 fileStream <<
"4 5 2 3 4\n";
53 fileStream <<
"4 0 1 6 7 # Face 5\n";
54 fileStream <<
"# 3D cylinders\n";
55 fileStream <<
"0 # Number of cylinders\n";
56 fileStream <<
"# 3D circles\n";
57 fileStream <<
"0 # Number of circles\n";
64 std::vector<vpHomogeneousMatrix> cMo_vec;
67 bool ret = detector.
detect(I, tagSize, cam, cMo_vec);
70 for (
size_t i = 0; i < cMo_vec.size(); i++) {
78 return state_tracking;
81 return state_detection;
95 return state_detection;
102 if (projection_error > projection_error_threshold) {
103 return state_detection;
111 std::stringstream ss;
116 return state_tracking;
120 #
if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON)
121 std::map<std::string, pcl::PointCloud<pcl::PointXYZ>::ConstPtr> mapOfPointclouds,
123 std::map<std::string,
const std::vector<vpColVector> *> mapOfPointclouds,
124 std::map<std::string, unsigned int> mapOfWidths, std::map<std::string, unsigned int> mapOfHeights,
135 #if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON)
136 tracker.
track(mapOfImages, mapOfPointclouds);
138 tracker.
track(mapOfImages, mapOfPointclouds, mapOfWidths, mapOfHeights);
142 return state_detection;
149 if (projection_error > projection_error_threshold) {
150 return state_detection;
154 tracker.
display(I_gray, I_depth, cMo, depth_M_color * cMo, cam_color, cam_depth,
vpColor::red, 3);
158 return state_tracking;
161 int main(
int argc,
const char **argv)
164 double opt_tag_size = 0.08;
165 float opt_quad_decimate = 1.0;
166 int opt_nthreads = 1;
167 double opt_cube_size = 0.125;
168 #ifdef VISP_HAVE_OPENCV
169 bool opt_use_texture =
false;
171 bool opt_use_depth =
false;
172 double opt_projection_error_threshold = 40.;
174 #if !(defined(VISP_HAVE_DISPLAY))
175 bool display_off =
true;
177 bool display_off =
false;
180 for (
int i = 1; i < argc; i++) {
181 if (std::string(argv[i]) ==
"--tag-size" && i + 1 < argc) {
182 opt_tag_size = atof(argv[i + 1]);
184 else if (std::string(argv[i]) ==
"--quad-decimate" && i + 1 < argc) {
185 opt_quad_decimate = (float)atof(argv[i + 1]);
187 else if (std::string(argv[i]) ==
"--nthreads" && i + 1 < argc) {
188 opt_nthreads = atoi(argv[i + 1]);
190 else if (std::string(argv[i]) ==
"--display-off") {
193 else if (std::string(argv[i]) ==
"--tag-family" && i + 1 < argc) {
196 else if (std::string(argv[i]) ==
"--cube-size" && i + 1 < argc) {
197 opt_cube_size = atof(argv[i + 1]);
198 #ifdef VISP_HAVE_OPENCV
200 else if (std::string(argv[i]) ==
"--texture") {
201 opt_use_texture =
true;
204 else if (std::string(argv[i]) ==
"--depth") {
205 opt_use_depth =
true;
207 else if (std::string(argv[i]) ==
"--projection-error" && i + 1 < argc) {
208 opt_projection_error_threshold = atof(argv[i + 1]);
210 else if (std::string(argv[i]) ==
"--help" || std::string(argv[i]) ==
"-h") {
211 std::cout <<
"Usage: " << argv[0]
212 <<
" [--cube-size <size in m>]"
213 <<
" [--tag-size <size in m>]"
214 <<
" [--quad-decimate <decimation>]"
215 <<
" [--nthreads <nb>]"
216 <<
" [--tag-family <0: TAG_36h11, 1: TAG_36h10, 2: TAG_36ARTOOLKIT, 3: TAG_25h9, 4: TAG_25h7, 5: TAG_16h5>]";
217 #if (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI) || defined(VISP_HAVE_OPENCV))
218 std::cout <<
" [--display-off]";
220 std::cout <<
" [--texture]"
222 <<
" [--projection-error <30 - 100>]"
223 <<
" [--help,h]" << std::endl;
228 createCaoFile(opt_cube_size);
230 #if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
231 std::shared_ptr<vpDisplay> d_gray;
232 std::shared_ptr<vpDisplay> d_depth;
242 int width = 640, height = 480, stream_fps = 30;
243 config.enable_stream(RS2_STREAM_COLOR, width, height, RS2_FORMAT_RGBA8, stream_fps);
244 config.enable_stream(RS2_STREAM_DEPTH, width, height, RS2_FORMAT_Z16, stream_fps);
245 config.disable_stream(RS2_STREAM_INFRARED);
246 realsense.
open(config);
260 std::map<std::string, vpHomogeneousMatrix> mapOfCameraTransformations;
261 std::map<std::string, const vpImage<unsigned char> *> mapOfImages;
262 #if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON)
263 std::map<std::string, pcl::PointCloud<pcl::PointXYZ>::ConstPtr> mapOfPointclouds;
264 pcl::PointCloud<pcl::PointXYZ>::Ptr pointcloud(
new pcl::PointCloud<pcl::PointXYZ>());
266 std::map<std::string, const std::vector<vpColVector> *> mapOfPointclouds;
267 std::map<std::string, unsigned int> mapOfWidths, mapOfHeights;
268 std::vector<vpColVector> pointcloud;
271 std::map<std::string, vpHomogeneousMatrix> mapOfCameraPoses;
273 std::cout <<
"Cube size: " << opt_cube_size << std::endl;
274 std::cout <<
"AprilTag size: " << opt_tag_size << std::endl;
275 std::cout <<
"AprilTag family: " << opt_tag_family << std::endl;
276 std::cout <<
"Camera parameters:" << std::endl;
277 std::cout <<
" Color:\n" << cam_color << std::endl;
279 std::cout <<
" Depth:\n" << cam_depth << std::endl;
280 std::cout <<
"Detection: " << std::endl;
281 std::cout <<
" Quad decimate: " << opt_quad_decimate << std::endl;
282 std::cout <<
" Threads number: " << opt_nthreads << std::endl;
283 std::cout <<
"Tracker: " << std::endl;
284 std::cout <<
" Use edges : 1" << std::endl;
285 std::cout <<
" Use texture: "
286 #ifdef VISP_HAVE_OPENCV
287 << opt_use_texture << std::endl;
289 <<
" na" << std::endl;
291 std::cout <<
" Use depth : " << opt_use_depth << std::endl;
292 std::cout <<
" Projection error: " << opt_projection_error_threshold << std::endl;
296 #if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
313 std::vector<int> trackerTypes;
314 #if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_VIDEO)
339 #if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_VIDEO)
340 if (opt_use_texture) {
349 tracker.setKltOpencv(klt_settings);
350 tracker.setKltMaskBorder(5);
358 tracker.
loadModel(
"cube.cao",
"cube.cao");
359 mapOfCameraTransformations[
"Camera2"] = depth_M_color;
375 state_t state = state_detection;
378 while (state != state_quit) {
380 #if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON)
381 realsense.
acquire((
unsigned char *)I_color.bitmap, (
unsigned char *)I_depth_raw.bitmap,
nullptr, pointcloud,
nullptr);
383 realsense.
acquire((
unsigned char *)I_color.bitmap, (
unsigned char *)I_depth_raw.bitmap, &pointcloud,
nullptr,
391 mapOfImages[
"Camera1"] = &I_gray;
392 mapOfImages[
"Camera2"] = &I_depth;
393 #if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON)
394 mapOfPointclouds[
"Camera2"] = pointcloud;
396 mapOfPointclouds[
"Camera2"] = &pointcloud;
397 mapOfWidths[
"Camera2"] = width;
398 mapOfHeights[
"Camera2"] = height;
406 if (state == state_detection) {
407 state = detectAprilTag(I_gray, detector, opt_tag_size, cam_color, cMo);
410 if (state == state_tracking) {
412 mapOfCameraPoses[
"Camera1"] = cMo;
413 mapOfCameraPoses[
"Camera2"] = depth_M_color * cMo;
422 if (state == state_tracking) {
424 #if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON)
425 state = track(mapOfImages, mapOfPointclouds, I_gray, I_depth, depth_M_color, tracker,
426 opt_projection_error_threshold, cMo);
428 state = track(mapOfImages, mapOfPointclouds, mapOfWidths, mapOfHeights, I_gray, I_depth, depth_M_color,
429 tracker, opt_projection_error_threshold, cMo);
433 state = track(I_gray, tracker, opt_projection_error_threshold, cMo);
436 std::stringstream ss;
459 std::cerr <<
"Catch an exception: " << e.
getMessage() << std::endl;
462 #if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
477 #ifndef VISP_HAVE_APRILTAG
478 std::cout <<
"ViSP is not build with Apriltag support" << std::endl;
480 #ifndef VISP_HAVE_REALSENSE2
481 std::cout <<
"ViSP is not build with librealsense2 support" << std::endl;
483 std::cout <<
"Install missing 3rd parties, configure and build ViSP to run this tutorial" << std::endl;
Generic class defining intrinsic camera parameters.
@ perspectiveProjWithoutDistortion
Perspective projection without distortion model.
static const vpColor none
void setAprilTagQuadDecimate(float quadDecimate)
bool detect(const vpImage< unsigned char > &I) VP_OVERRIDE
@ TAG_36h11
AprilTag 36h11 pattern (recommended)
void setAprilTagNbThreads(int nThreads)
size_t getNbObjects() const
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 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 * getMessage() const
Implementation of an homogeneous matrix and operations on such kind of matrices.
static void createDepthHistogram(const vpImage< uint16_t > &src_depth, vpImage< vpRGBa > &dest_rgba)
static void convert(const vpImage< unsigned char > &src, vpImage< vpRGBa > &dest)
Wrapper for the KLT (Kanade-Lucas-Tomasi) feature tracker implemented in OpenCV. Thus to enable this ...
void setBlockSize(int blockSize)
void setQuality(double qualityLevel)
void setHarrisFreeParameter(double harris_k)
void setMaxFeatures(int maxCount)
void setMinDistance(double minDistance)
void setWindowSize(int winSize)
void setPyramidLevels(int pyrMaxLevel)
static double rad(double deg)
Real-time 6D object pose tracking using its CAD model.
virtual void setCameraParameters(const vpCameraParameters &camera) VP_OVERRIDE
virtual void setDisplayFeatures(bool displayF) VP_OVERRIDE
virtual unsigned int getNbFeaturesEdge() const
virtual double computeCurrentProjectionError(const vpImage< unsigned char > &I, const vpHomogeneousMatrix &_cMo, const vpCameraParameters &_cam) VP_OVERRIDE
virtual void getCameraParameters(vpCameraParameters &camera) const VP_OVERRIDE
virtual void initFromPose(const vpImage< unsigned char > &I, const vpHomogeneousMatrix &cMo) VP_OVERRIDE
virtual void getPose(vpHomogeneousMatrix &cMo) const VP_OVERRIDE
virtual unsigned int getNbFeaturesKlt() const
virtual void setMovingEdge(const vpMe &me)
virtual void setAngleDisappear(const double &a) VP_OVERRIDE
virtual void track(const vpImage< unsigned char > &I) VP_OVERRIDE
virtual unsigned int getNbFeaturesDepthDense() const
virtual void loadModel(const std::string &modelFile, bool verbose=false, const vpHomogeneousMatrix &T=vpHomogeneousMatrix()) VP_OVERRIDE
virtual void setCameraTransformationMatrix(const std::string &cameraName, const vpHomogeneousMatrix &cameraTransformationMatrix)
virtual void display(const vpImage< unsigned char > &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, const vpColor &col, unsigned int thickness=1, bool displayFullModel=false) VP_OVERRIDE
virtual void setAngleAppear(const double &a) VP_OVERRIDE
void setMu1(const double &mu_1)
void setRange(const unsigned int &range)
void setLikelihoodThresholdType(const vpLikelihoodThresholdType likelihood_threshold_type)
void setMaskNumber(const unsigned int &mask_number)
void setThreshold(const double &threshold)
void setSampleStep(const double &sample_step)
void setMaskSize(const unsigned int &mask_size)
void setMu2(const double &mu_2)
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())
vpHomogeneousMatrix getTransformation(const rs2_stream &from, const rs2_stream &to, int from_index=-1) const
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.