4 #include <visp3/core/vpConfig.h>
5 #include <visp3/core/vpDisplay.h>
6 #include <visp3/core/vpIoTools.h>
7 #include <visp3/gui/vpDisplayFactory.h>
8 #include <visp3/io/vpImageIo.h>
10 #include <visp3/mbt/vpMbGenericTracker.h>
13 #if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON)
14 #include <pcl/common/common.h>
15 #include <pcl/point_cloud.h>
16 #include <pcl/point_types.h>
18 #ifdef ENABLE_VISP_NAMESPACE
24 struct vpRealsenseIntrinsics_t
37 void rs_deproject_pixel_to_point(
float point[3],
const vpRealsenseIntrinsics_t &intrin,
const float pixel[2],
float depth)
39 float x = (pixel[0] - intrin.ppx) / intrin.fx;
40 float y = (pixel[1] - intrin.ppy) / intrin.fy;
42 float r2 = x * x + y * y;
43 float f = 1 + intrin.coeffs[0] * r2 + intrin.coeffs[1] * r2 * r2 + intrin.coeffs[4] * r2 * r2 * r2;
44 float ux = x * f + 2 * intrin.coeffs[2] * x * y + intrin.coeffs[3] * (r2 + 2 * x * x);
45 float uy = y * f + 2 * intrin.coeffs[3] * x * y + intrin.coeffs[2] * (r2 + 2 * y * y);
56 bool read_data(
unsigned int cpt,
const std::string &input_directory,
vpImage<vpRGBa> &I_color,
60 char buffer[FILENAME_MAX];
63 ss << input_directory <<
"/color_image_%04d.jpg";
64 snprintf(buffer, FILENAME_MAX, ss.str().c_str(), cpt);
65 std::string filename_color = buffer;
68 std::cerr <<
"Cannot read: " << filename_color << std::endl;
75 ss << input_directory <<
"/depth_image_%04d.bin";
76 snprintf(buffer, FILENAME_MAX, ss.str().c_str(), cpt);
77 std::string filename_depth = buffer;
79 std::ifstream file_depth(filename_depth.c_str(), std::ios::in | std::ios::binary);
80 if (!file_depth.is_open()) {
84 unsigned int height = 0, width = 0;
87 I_depth_raw.
resize(height, width);
89 uint16_t depth_value = 0;
90 for (
unsigned int i = 0; i < height; i++) {
91 for (
unsigned int j = 0; j < width; j++) {
93 I_depth_raw[i][j] = depth_value;
98 pointcloud->width = width;
99 pointcloud->height = height;
100 pointcloud->resize((
size_t)width * height);
103 const float depth_scale = 0.00100000005f;
104 vpRealsenseIntrinsics_t depth_intrinsic;
105 depth_intrinsic.ppx = 320.503509521484f;
106 depth_intrinsic.ppy = 235.602951049805f;
107 depth_intrinsic.fx = 383.970001220703f;
108 depth_intrinsic.fy = 383.970001220703f;
109 depth_intrinsic.coeffs[0] = 0.0f;
110 depth_intrinsic.coeffs[1] = 0.0f;
111 depth_intrinsic.coeffs[2] = 0.0f;
112 depth_intrinsic.coeffs[3] = 0.0f;
113 depth_intrinsic.coeffs[4] = 0.0f;
115 for (
unsigned int i = 0; i < height; i++) {
116 for (
unsigned int j = 0; j < width; j++) {
117 float scaled_depth = I_depth_raw[i][j] * depth_scale;
119 float pixel[2] = { (float)j, (
float)i };
120 rs_deproject_pixel_to_point(point, depth_intrinsic, pixel, scaled_depth);
121 pointcloud->points[(size_t)(i * width + j)].x = point[0];
122 pointcloud->points[(size_t)(i * width + j)].y = point[1];
123 pointcloud->points[(size_t)(i * width + j)].z = point[2];
131 int main(
int argc,
char *argv[])
133 std::string input_directory =
"data";
134 std::string config_color =
"model/cube/cube.xml", config_depth =
"model/cube/cube_depth.xml";
135 std::string model_color =
"model/cube/cube.cao", model_depth =
"model/cube/cube.cao";
136 std::string init_file =
"model/cube/cube.init";
137 unsigned int frame_cpt = 0;
138 bool disable_depth =
false;
140 for (
int i = 1; i < argc; i++) {
141 if (std::string(argv[i]) ==
"--input_directory" && i + 1 < argc) {
142 input_directory = std::string(argv[i + 1]);
144 else if (std::string(argv[i]) ==
"--config_color" && i + 1 < argc) {
145 config_color = std::string(argv[i + 1]);
147 else if (std::string(argv[i]) ==
"--config_depth" && i + 1 < argc) {
148 config_depth = std::string(argv[i + 1]);
150 else if (std::string(argv[i]) ==
"--model_color" && i + 1 < argc) {
151 model_color = std::string(argv[i + 1]);
153 else if (std::string(argv[i]) ==
"--model_depth" && i + 1 < argc) {
154 model_depth = std::string(argv[i + 1]);
156 else if (std::string(argv[i]) ==
"--init_file" && i + 1 < argc) {
157 init_file = std::string(argv[i + 1]);
159 else if (std::string(argv[i]) ==
"--disable_depth") {
160 disable_depth =
true;
162 else if (std::string(argv[i]) ==
"--help" || std::string(argv[i]) ==
"-h") {
163 std::cout <<
"Usage: \n"
165 <<
" --input_directory <data directory> --config_color <object.xml> --config_depth <object.xml>"
166 " --model_color <object.cao> --model_depth <object.cao> --init_file <object.init> --disable_depth"
171 <<
" --config_color model/cube/cube.xml --config_depth model/cube/cube.xml"
172 " --model_color model/cube/cube.cao --model_depth model/cube/cube.cao --init_file model/cube/cube.init\n"
178 std::cout <<
"Tracked features: " << std::endl;
179 #if defined(VISP_HAVE_OPENCV)
180 std::cout <<
" Use edges : 1" << std::endl;
181 #if defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_VIDEO)
182 std::cout <<
" Use klt : 1" << std::endl;
184 std::cout <<
" Use klt : 0" << std::endl;
186 std::cout <<
" Use depth : " << !disable_depth << std::endl;
188 std::cout <<
" Use edges : 1" << std::endl;
189 std::cout <<
" Use klt : 0" << std::endl;
190 std::cout <<
" Use depth : 0" << std::endl;
192 std::cout <<
"Config files: " << std::endl;
193 std::cout <<
" Input directory: "
194 <<
"\"" << input_directory <<
"\"" << std::endl;
195 std::cout <<
" Config color: "
196 <<
"\"" << config_color <<
"\"" << std::endl;
197 std::cout <<
" Config depth: "
198 <<
"\"" << config_depth <<
"\"" << std::endl;
199 std::cout <<
" Model color : "
200 <<
"\"" << model_color <<
"\"" << std::endl;
201 std::cout <<
" Model depth : "
202 <<
"\"" << model_depth <<
"\"" << std::endl;
203 std::cout <<
" Init file : "
204 <<
"\"" << init_file <<
"\"" << std::endl;
212 pcl::PointCloud<pcl::PointXYZ>::Ptr pointcloud(
new pcl::PointCloud<pcl::PointXYZ>());
216 read_data(frame_cpt, input_directory, I_color, I_depth_raw, pointcloud);
220 #if defined(VISP_HAVE_DISPLAY)
221 #if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
228 unsigned int _posx = 100, _posy = 50, _posdx = 10;
229 display1->init(I_gray, _posx, _posy,
"Color stream");
230 display2->init(I_depth, _posx + I_gray.
getWidth() + _posdx, _posy,
"Depth stream");
239 std::vector<int> trackerTypes;
240 #if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_VIDEO)
248 #if defined(VISP_HAVE_PUGIXML)
250 tracker.loadConfigFile(config_color, config_depth);
257 tracker.setCameraParameters(cam_color, cam_depth);
270 tracker.setMovingEdge(me);
273 #if defined(VISP_HAVE_MODULE_KLT) && defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_VIDEO)
275 tracker.setKltMaskBorder(5);
284 tracker.setKltOpencv(klt);
289 tracker.setDepthNormalPclPlaneEstimationMethod(2);
290 tracker.setDepthNormalPclPlaneEstimationRansacMaxIter(200);
291 tracker.setDepthNormalPclPlaneEstimationRansacThreshold(0.001);
292 tracker.setDepthNormalSamplingStep(2, 2);
294 tracker.setDepthDenseSamplingStep(4, 4);
298 tracker.setNearClippingDistance(0.001);
299 tracker.setFarClippingDistance(5.0);
303 tracker.loadModel(model_color, model_depth);
306 tracker.getCameraParameters(cam_color, cam_depth);
308 std::cout <<
"Camera parameters for color camera (from XML file): " << cam_color << std::endl;
309 std::cout <<
"Camera parameters for depth camera (from XML file): " << cam_depth << std::endl;
312 tracker.setDisplayFeatures(
true);
318 std::ifstream file((std::string(input_directory +
"/depth_M_color.txt")).c_str());
319 depth_M_color.
load(file);
322 std::map<std::string, vpHomogeneousMatrix> mapOfCameraTransformations;
324 mapOfCameraTransformations[
"Camera2"] = depth_M_color;
325 tracker.setCameraTransformationMatrix(mapOfCameraTransformations);
327 std::cout <<
"depth_M_color: \n" << depth_M_color << std::endl;
330 std::map<std::string, const vpImage<unsigned char> *> mapOfImages;
331 mapOfImages[
"Camera1"] = &I_gray;
332 mapOfImages[
"Camera2"] = &I_depth;
336 std::map<std::string, std::string> mapOfInitFiles;
337 mapOfInitFiles[
"Camera1"] = init_file;
338 tracker.initClick(mapOfImages, mapOfInitFiles,
true);
342 pcl::PointCloud<pcl::PointXYZ>::Ptr empty_pointcloud(
new pcl::PointCloud<pcl::PointXYZ>);
343 std::vector<double> times_vec;
349 quit = !read_data(frame_cpt, input_directory, I_color, I_depth_raw, pointcloud);
356 mapOfImages[
"Camera1"] = &I_gray;
357 std::map<std::string, pcl::PointCloud<pcl::PointXYZ>::ConstPtr> mapOfPointclouds;
359 mapOfPointclouds[
"Camera2"] = empty_pointcloud;
361 mapOfPointclouds[
"Camera2"] = pointcloud;
364 tracker.track(mapOfImages, mapOfPointclouds);
371 std::cout <<
"iter: " << frame_cpt <<
" cMo:\n" << cMo << std::endl;
374 tracker.display(I_gray, I_depth, cMo, depth_M_color * cMo, cam_color, cam_depth,
vpColor::red, 3);
380 times_vec.push_back(t);
382 std::stringstream ss;
383 ss <<
"Computation time: " << t <<
" ms";
386 std::stringstream ss;
387 ss <<
"Nb features: " << tracker.getError().size();
391 std::stringstream ss;
392 ss <<
"Features: edges " << tracker.getNbFeaturesEdge() <<
", klt " << tracker.getNbFeaturesKlt() <<
", depth "
393 << tracker.getNbFeaturesDepthDense();
412 #if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11) && defined(VISP_HAVE_DISPLAY)
413 if (display1 !=
nullptr) {
416 if (display2 !=
nullptr) {
434 std::cout <<
"To run this tutorial, ViSP should be build with PCL library."
435 " Install libpcl, configure and build again ViSP..."
Generic class defining intrinsic camera parameters.
void initPersProjWithoutDistortion(double px, double py, double u0, double v0)
static const vpColor none
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 std::string & getStringMessage() const
Implementation of an homogeneous matrix and operations on such kind of matrices.
void load(std::ifstream &f)
static void createDepthHistogram(const vpImage< uint16_t > &src_depth, vpImage< vpRGBa > &dest_rgba)
static void convert(const vpImage< unsigned char > &src, vpImage< vpRGBa > &dest)
static void read(vpImage< unsigned char > &I, const std::string &filename, int backend=IO_DEFAULT_BACKEND)
unsigned int getWidth() const
void resize(unsigned int h, unsigned int w)
resize the image : Image initialization
unsigned int getHeight() const
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)
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.
@ ROBUST_FEATURE_ESTIMATION
Robust scheme to estimate the normal of the plane.
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)
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 double measureTimeMs()