4 #include <visp3/core/vpConfig.h>
6 #if defined(VISP_HAVE_REALSENSE2) && defined(VISP_HAVE_OPENCV) && defined(VISP_HAVE_PUGIXML)
7 #include <visp3/core/vpDisplay.h>
8 #include <visp3/core/vpIoTools.h>
9 #include <visp3/gui/vpDisplayGDI.h>
10 #include <visp3/gui/vpDisplayOpenCV.h>
11 #include <visp3/gui/vpDisplayX.h>
12 #include <visp3/mbt/vpMbGenericTracker.h>
13 #include <visp3/sensor/vpRealSense2.h>
14 #include <visp3/vision/vpKeyPoint.h>
16 int main(
int argc,
char *argv[])
18 #ifdef ENABLE_VISP_NAMESPACE
22 std::string config_color =
"", config_depth =
"";
23 std::string model_color =
"", model_depth =
"";
24 std::string init_file =
"";
25 bool use_ogre =
false;
26 bool use_scanline =
false;
27 bool use_edges =
true;
29 bool use_depth =
true;
31 bool auto_init =
false;
32 double proj_error_threshold = 25;
33 std::string learning_data =
"learning/data-learned.bin";
34 bool display_projection_error =
false;
36 for (
int i = 1; i < argc; i++) {
37 if (std::string(argv[i]) ==
"--config_color" && i + 1 < argc) {
38 config_color = std::string(argv[i + 1]);
40 else if (std::string(argv[i]) ==
"--config_depth" && i + 1 < argc) {
41 config_depth = std::string(argv[i + 1]);
43 else if (std::string(argv[i]) ==
"--model_color" && i + 1 < argc) {
44 model_color = std::string(argv[i + 1]);
46 else if (std::string(argv[i]) ==
"--model_depth" && i + 1 < argc) {
47 model_depth = std::string(argv[i + 1]);
49 else if (std::string(argv[i]) ==
"--init_file" && i + 1 < argc) {
50 init_file = std::string(argv[i + 1]);
52 else if (std::string(argv[i]) ==
"--proj_error_threshold" && i + 1 < argc) {
53 proj_error_threshold = std::atof(argv[i + 1]);
55 else if (std::string(argv[i]) ==
"--use_ogre") {
58 else if (std::string(argv[i]) ==
"--use_scanline") {
61 else if (std::string(argv[i]) ==
"--use_edges" && i + 1 < argc) {
62 use_edges = (std::atoi(argv[i + 1]) == 0 ? false :
true);
64 else if (std::string(argv[i]) ==
"--use_klt" && i + 1 < argc) {
65 use_klt = (std::atoi(argv[i + 1]) == 0 ? false :
true);
67 else if (std::string(argv[i]) ==
"--use_depth" && i + 1 < argc) {
68 use_depth = (std::atoi(argv[i + 1]) == 0 ? false :
true);
70 else if (std::string(argv[i]) ==
"--learn") {
73 else if (std::string(argv[i]) ==
"--learning_data" && i + 1 < argc) {
74 learning_data = argv[i + 1];
76 else if (std::string(argv[i]) ==
"--auto_init") {
79 else if (std::string(argv[i]) ==
"--display_proj_error") {
80 display_projection_error =
true;
82 else if (std::string(argv[i]) ==
"--help" || std::string(argv[i]) ==
"-h") {
83 std::cout <<
"Usage: \n"
85 <<
" [--model_color <object.cao>] [--model_depth <object.cao>]"
86 " [--config_color <object.xml>] [--config_depth <object.xml>]"
87 " [--init_file <object.init>] [--use_ogre] [--use_scanline]"
88 " [--proj_error_threshold <threshold between 0 and 90> (default: "
89 << proj_error_threshold
91 " [--use_edges <0|1> (default: 1)] [--use_klt <0|1> (default: 1)] [--use_depth <0|1> (default: 1)]"
92 " [--learn] [--auto_init] [--learning_data <path to .bin> (default: learning/data-learned.bin)]"
93 " [--display_proj_error]"
96 std::cout <<
"\n** How to track a 4.2 cm width cube with manual initialization:\n"
97 << argv[0] <<
" --model_color model/cube/cube.cao --use_edges 1 --use_klt 1 --use_depth 1" << std::endl;
98 std::cout <<
"\n** How to learn the cube and create a learning database:\n"
99 << argv[0] <<
" --model_color model/cube/cube.cao --use_edges 1 --use_klt 1 --use_depth 1 --learn"
101 std::cout <<
"\n** How to track the cube with initialization from learning database:\n"
102 << argv[0] <<
" --model_color model/cube/cube.cao --use_edges 1 --use_klt 1 --use_depth 1 --auto_init"
109 if (model_depth.empty()) {
110 model_depth = model_color;
113 if (config_color.empty()) {
114 config_color = (parentname.empty() ?
"" : (parentname +
"/")) +
vpIoTools::getNameWE(model_color) +
".xml";
116 if (config_depth.empty()) {
117 config_depth = (parentname.empty() ?
"" : (parentname +
"/")) +
vpIoTools::getNameWE(model_color) +
"_depth.xml";
119 if (init_file.empty()) {
120 init_file = (parentname.empty() ?
"" : (parentname +
"/")) +
vpIoTools::getNameWE(model_color) +
".init";
122 std::cout <<
"Tracked features: " << std::endl;
123 std::cout <<
" Use edges : " << use_edges << std::endl;
124 std::cout <<
" Use klt : " << use_klt << std::endl;
125 std::cout <<
" Use depth : " << use_depth << std::endl;
126 std::cout <<
"Tracker options: " << std::endl;
127 std::cout <<
" Use ogre : " << use_ogre << std::endl;
128 std::cout <<
" Use scanline: " << use_scanline << std::endl;
129 std::cout <<
" Proj. error : " << proj_error_threshold << std::endl;
130 std::cout <<
" Display proj. error: " << display_projection_error << std::endl;
131 std::cout <<
"Config files: " << std::endl;
132 std::cout <<
" Config color: "
133 <<
"\"" << config_color <<
"\"" << std::endl;
134 std::cout <<
" Config depth: "
135 <<
"\"" << config_depth <<
"\"" << std::endl;
136 std::cout <<
" Model color : "
137 <<
"\"" << model_color <<
"\"" << std::endl;
138 std::cout <<
" Model depth : "
139 <<
"\"" << model_depth <<
"\"" << std::endl;
140 std::cout <<
" Init file : "
141 <<
"\"" << init_file <<
"\"" << std::endl;
142 std::cout <<
"Learning options : " << std::endl;
143 std::cout <<
" Learn : " << learn << std::endl;
144 std::cout <<
" Auto init : " << auto_init << std::endl;
145 std::cout <<
" Learning data: " << learning_data << std::endl;
147 if (!use_edges && !use_klt && !use_depth) {
148 std::cout <<
"You must choose at least one visual features between edge, KLT and depth." << std::endl;
152 if (config_color.empty() || config_depth.empty() || model_color.empty() || model_depth.empty() || init_file.empty()) {
153 std::cout <<
"config_color.empty() || config_depth.empty() || model_color.empty() || model_depth.empty() || "
160 int width = 640, height = 480;
163 config.enable_stream(RS2_STREAM_COLOR, width, height, RS2_FORMAT_RGBA8, fps);
164 config.enable_stream(RS2_STREAM_DEPTH, width, height, RS2_FORMAT_Z16, fps);
167 realsense.
open(config);
170 std::cout <<
"Catch an exception: " << e.
what() << std::endl;
171 std::cout <<
"Check if the Realsense camera is connected..." << std::endl;
180 std::cout <<
"Sensor internal camera parameters for color camera: " << cam_color << std::endl;
181 std::cout <<
"Sensor internal camera parameters for depth camera: " << cam_depth << std::endl;
188 unsigned int _posx = 100, _posy = 50;
192 #elif defined(VISP_HAVE_GDI)
194 #elif defined(HAVE_OPENCV_HIGHGUI)
197 if (use_edges || use_klt)
198 d1.
init(I_gray, _posx, _posy,
"Color stream");
200 d2.init(I_depth, _posx + I_gray.getWidth() + 10, _posy,
"Depth stream");
203 realsense.
acquire((
unsigned char *)I_color.bitmap, (
unsigned char *)I_depth_raw.bitmap,
nullptr,
nullptr);
205 if (use_edges || use_klt) {
228 std::vector<int> trackerTypes;
229 if (use_edges && use_klt)
234 trackerTypes.push_back(vpMbGenericTracker::KLT_TRACKER);
240 std::map<std::string, vpHomogeneousMatrix> mapOfCameraTransformations;
241 std::map<std::string, const vpImage<unsigned char> *> mapOfImages;
242 std::map<std::string, std::string> mapOfInitFiles;
243 std::map<std::string, const std::vector<vpColVector> *> mapOfPointclouds;
244 std::map<std::string, unsigned int> mapOfWidths, mapOfHeights;
245 std::map<std::string, vpHomogeneousMatrix> mapOfCameraPoses;
247 std::vector<vpColVector> pointcloud;
251 if ((use_edges || use_klt) && use_depth) {
252 tracker.loadConfigFile(config_color, config_depth);
253 tracker.loadModel(model_color, model_depth);
254 std::cout <<
"Sensor internal depth_M_color: \n" << depth_M_color << std::endl;
255 mapOfCameraTransformations[
"Camera2"] = depth_M_color;
256 tracker.setCameraTransformationMatrix(mapOfCameraTransformations);
257 mapOfImages[
"Camera1"] = &I_gray;
258 mapOfImages[
"Camera2"] = &I_depth;
259 mapOfInitFiles[
"Camera1"] = init_file;
260 tracker.setCameraParameters(cam_color, cam_depth);
262 else if (use_edges || use_klt) {
263 tracker.loadConfigFile(config_color);
264 tracker.loadModel(model_color);
265 tracker.setCameraParameters(cam_color);
267 else if (use_depth) {
268 tracker.loadConfigFile(config_depth);
269 tracker.loadModel(model_depth);
270 tracker.setCameraParameters(cam_depth);
273 tracker.setDisplayFeatures(
true);
274 tracker.setOgreVisibilityTest(use_ogre);
275 tracker.setScanLineVisibilityTest(use_scanline);
276 tracker.setProjectionErrorComputation(
true);
277 tracker.setProjectionErrorDisplay(display_projection_error);
279 #if (defined(VISP_HAVE_OPENCV_NONFREE) || defined(VISP_HAVE_OPENCV_XFEATURES2D)) || \
280 (VISP_HAVE_OPENCV_VERSION >= 0x030411 && CV_MAJOR_VERSION < 4) || (VISP_HAVE_OPENCV_VERSION >= 0x040400)
281 std::string detectorName =
"SIFT";
282 std::string extractorName =
"SIFT";
283 std::string matcherName =
"BruteForce";
285 std::string detectorName =
"FAST";
286 std::string extractorName =
"ORB";
287 std::string matcherName =
"BruteForce-Hamming";
290 if (learn || auto_init) {
294 #if !(defined(VISP_HAVE_OPENCV_NONFREE) || defined(VISP_HAVE_OPENCV_XFEATURES2D))
295 #if (VISP_HAVE_OPENCV_VERSION < 0x030000)
296 keypoint.setDetectorParameter(
"ORB",
"nLevels", 1);
298 cv::Ptr<cv::ORB> orb_detector = keypoint.
getDetector(
"ORB").dynamicCast<cv::ORB>();
300 orb_detector->setNLevels(1);
308 std::cout <<
"Cannot enable auto detection. Learning file \"" << learning_data <<
"\" doesn't exist" << std::endl;
314 if ((use_edges || use_klt) && use_depth)
315 tracker.initClick(mapOfImages, mapOfInitFiles,
true);
316 else if (use_edges || use_klt)
317 tracker.initClick(I_gray, init_file,
true);
319 tracker.initClick(I_depth, init_file,
true);
325 bool run_auto_init =
false;
327 run_auto_init =
true;
329 std::vector<double> times_vec;
335 bool learn_position =
false;
341 bool tracking_failed =
false;
344 realsense.
acquire((
unsigned char *)I_color.bitmap, (
unsigned char *)I_depth_raw.bitmap, &pointcloud,
nullptr,
nullptr);
346 if (use_edges || use_klt || run_auto_init) {
355 if ((use_edges || use_klt) && use_depth) {
356 mapOfImages[
"Camera1"] = &I_gray;
357 mapOfPointclouds[
"Camera2"] = &pointcloud;
358 mapOfWidths[
"Camera2"] = width;
359 mapOfHeights[
"Camera2"] = height;
361 else if (use_edges || use_klt) {
362 mapOfImages[
"Camera"] = &I_gray;
364 else if (use_depth) {
365 mapOfPointclouds[
"Camera"] = &pointcloud;
366 mapOfWidths[
"Camera"] = width;
367 mapOfHeights[
"Camera"] = height;
372 if (keypoint.
matchPoint(I_gray, cam_color, cMo)) {
373 std::cout <<
"Auto init succeed" << std::endl;
374 if ((use_edges || use_klt) && use_depth) {
375 mapOfCameraPoses[
"Camera1"] = cMo;
376 mapOfCameraPoses[
"Camera2"] = depth_M_color * cMo;
377 tracker.initFromPose(mapOfImages, mapOfCameraPoses);
379 else if (use_edges || use_klt) {
380 tracker.initFromPose(I_gray, cMo);
382 else if (use_depth) {
383 tracker.initFromPose(I_depth, depth_M_color * cMo);
387 if (use_edges || use_klt) {
401 tracker.setDisplayFeatures(
false);
403 run_auto_init =
false;
405 if ((use_edges || use_klt) && use_depth) {
406 tracker.track(mapOfImages, mapOfPointclouds, mapOfWidths, mapOfHeights);
408 else if (use_edges || use_klt) {
409 tracker.track(I_gray);
411 else if (use_depth) {
412 tracker.track(mapOfImages, mapOfPointclouds, mapOfWidths, mapOfHeights);
417 tracking_failed =
true;
419 std::cout <<
"Tracker needs to restart (tracking exception)" << std::endl;
420 run_auto_init =
true;
425 cMo = tracker.getPose();
428 double proj_error = 0;
431 proj_error = tracker.getProjectionError();
434 proj_error = tracker.computeCurrentProjectionError(I_gray, cMo, cam_color);
437 if (auto_init && proj_error > proj_error_threshold) {
438 std::cout <<
"Tracker needs to restart (projection error detected: " << proj_error <<
")" << std::endl;
439 run_auto_init =
true;
440 tracking_failed =
true;
444 if (!tracking_failed) {
446 tracker.setDisplayFeatures(
true);
448 if ((use_edges || use_klt) && use_depth) {
449 tracker.display(I_gray, I_depth, cMo, depth_M_color * cMo, cam_color, cam_depth,
vpColor::red, 3);
453 else if (use_edges || use_klt) {
454 tracker.display(I_gray, cMo, cam_color,
vpColor::red, 3);
457 else if (use_depth) {
458 tracker.display(I_depth, cMo, cam_depth,
vpColor::red, 3);
463 std::stringstream ss;
464 ss <<
"Nb features: " << tracker.getError().size();
468 std::stringstream ss;
469 ss <<
"Features: edges " << tracker.getNbFeaturesEdge() <<
", klt " << tracker.getNbFeaturesKlt()
470 <<
", depth " << tracker.getNbFeaturesDepthDense();
475 std::stringstream ss;
476 ss <<
"Loop time: " << loop_t <<
" ms";
479 if (use_edges || use_klt) {
495 learn_position =
true;
498 run_auto_init =
true;
512 if (learn_position) {
514 std::vector<cv::KeyPoint> trainKeyPoints;
515 keypoint.
detect(I_gray, trainKeyPoints);
518 std::vector<vpPolygon> polygons;
519 std::vector<std::vector<vpPoint> > roisPt;
520 std::pair<std::vector<vpPolygon>, std::vector<std::vector<vpPoint> > > pair = tracker.getPolygonFaces();
521 polygons = pair.first;
522 roisPt = pair.second;
525 std::vector<cv::Point3f> points3f;
529 keypoint.
buildReference(I_gray, trainKeyPoints, points3f,
true, learn_id++);
532 for (std::vector<cv::KeyPoint>::const_iterator it = trainKeyPoints.begin(); it != trainKeyPoints.end(); ++it) {
535 learn_position =
false;
536 std::cout <<
"Data learned" << std::endl;
539 times_vec.push_back(loop_t);
542 std::cout <<
"Save learning file: " << learning_data << std::endl;
547 std::cout <<
"Catch an exception: " << e.
what() << std::endl;
550 if (!times_vec.empty()) {
558 #elif defined(VISP_HAVE_REALSENSE2)
561 std::cout <<
"Install OpenCV 3rd party, configure and build ViSP again to use this example" << std::endl;
567 std::cout <<
"Install librealsense2 3rd party, configure and build ViSP again to use this example" << std::endl;
Generic class defining intrinsic camera parameters.
@ perspectiveProjWithoutDistortion
Perspective projection without distortion model.
static const vpColor none
static const vpColor yellow
Display for windows using GDI (available on any windows 32 platform).
The vpDisplayOpenCV allows to display image using the OpenCV library. Thus to enable this class OpenC...
void init(vpImage< unsigned char > &I, int winx=-1, int winy=-1, const std::string &title="") VP_OVERRIDE
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 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)
error that can be emitted by ViSP classes.
const std::string & getStringMessage() const
const char * what() 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)
Class that allows keypoints detection (and descriptors extraction) and matching thanks to OpenCV libr...
unsigned int matchPoint(const vpImage< unsigned char > &I)
void setExtractor(const vpFeatureDescriptorType &extractorType)
void loadLearningData(const std::string &filename, bool binaryMode=false, bool append=false)
void detect(const vpImage< unsigned char > &I, std::vector< cv::KeyPoint > &keyPoints, const vpRect &rectangle=vpRect())
static void compute3DForPointsInPolygons(const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, std::vector< cv::KeyPoint > &candidates, const std::vector< vpPolygon > &polygons, const std::vector< std::vector< vpPoint > > &roisPt, std::vector< cv::Point3f > &points, cv::Mat *descriptors=nullptr)
void setMatcher(const std::string &matcherName)
void saveLearningData(const std::string &filename, bool binaryMode=false, bool saveTrainingImages=true)
void setDetector(const vpFeatureDetectorType &detectorType)
unsigned int buildReference(const vpImage< unsigned char > &I)
cv::Ptr< cv::FeatureDetector > getDetector(const vpFeatureDetectorType &type) const
static double getMedian(const std::vector< double > &v)
static double getStdev(const std::vector< double > &v, bool useBesselCorrection=false)
static double getMean(const std::vector< double > &v)
Real-time 6D object pose tracking using its CAD model.
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
VISP_EXPORT double measureTimeMs()