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_SEGMENTATION) && defined(VISP_HAVE_PCL_FILTERS) && 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
32std::string depthTypeToString(
const DepthType &type)
53DepthType depthTypeFromString(
const std::string &name)
55 DepthType
type(DEPTH_COUNT);
58 while ((i <
static_cast<unsigned int>(DEPTH_COUNT)) && notFound) {
59 DepthType candidate =
static_cast<DepthType
>(
i);
69std::string getDepthTypeList(
const std::string &prefix =
"<",
const std::string &sep =
" , ",
const std::string &suffix =
">")
71 std::string list(prefix);
73 while (i <
static_cast<unsigned int>(DEPTH_COUNT - 1)) {
74 DepthType
type =
static_cast<DepthType
>(
i);
75 std::string name = depthTypeToString(type);
79 DepthType
type =
static_cast<DepthType
>(DEPTH_COUNT - 1);
80 std::string name = depthTypeToString(type);
81 list += name + suffix;
85struct vpRealsenseIntrinsics_t
98void rs_deproject_pixel_to_point(
float point[3],
const vpRealsenseIntrinsics_t &intrin,
const float pixel[2],
float depth)
100 float x = (pixel[0] - intrin.ppx) / intrin.fx;
101 float y = (pixel[1] - intrin.ppy) / intrin.fy;
103 float r2 =
x *
x +
y *
y;
104 float f = 1 + intrin.coeffs[0] * r2 + intrin.coeffs[1] * r2 * r2 + intrin.coeffs[4] * r2 * r2 * r2;
105 float ux =
x * f + 2 * intrin.coeffs[2] *
x *
y + intrin.coeffs[3] * (r2 + 2 *
x *
x);
106 float uy =
y * f + 2 * intrin.coeffs[3] *
x *
y + intrin.coeffs[2] * (r2 + 2 *
y *
y);
125 std::cerr <<
"Cannot read: " << filename_color << std::endl;
133 std::ifstream file_depth(filename_depth.c_str(), std::ios::in | std::ios::binary);
134 if (!file_depth.is_open()) {
141 I_depth_raw.
resize(height, width);
143 uint16_t depth_value = 0;
144 for (
unsigned int i = 0;
i <
height;
i++) {
145 for (
unsigned int j = 0;
j <
width;
j++) {
147 I_depth_raw[
i][
j] = depth_value;
152 pointcloud->width =
width;
153 pointcloud->height =
height;
154 pointcloud->resize(
static_cast<size_t>(width * height));
158 vpRealsenseIntrinsics_t depth_intrinsic;
159 depth_intrinsic.ppx = 320.503509521484f;
160 depth_intrinsic.ppy = 235.602951049805f;
161 depth_intrinsic.fx = 383.970001220703f;
162 depth_intrinsic.fy = 383.970001220703f;
163 depth_intrinsic.coeffs[0] = 0.0f;
164 depth_intrinsic.coeffs[1] = 0.0f;
165 depth_intrinsic.coeffs[2] = 0.0f;
166 depth_intrinsic.coeffs[3] = 0.0f;
167 depth_intrinsic.coeffs[4] = 0.0f;
169 for (
unsigned int i = 0;
i <
height;
i++) {
170 for (
unsigned int j = 0;
j <
width;
j++) {
173 float pixel[2] = {
static_cast<float>(
j),
static_cast<float>(i) };
174 rs_deproject_pixel_to_point(point, depth_intrinsic, pixel, scaled_depth);
175 pointcloud->points[
static_cast<size_t>(
i *
width +
j)].x = point[0];
176 pointcloud->points[
static_cast<size_t>(
i *
width +
j)].y = point[1];
177 pointcloud->points[
static_cast<size_t>(
i *
width +
j)].z = point[2];
185int main(
int argc,
char *argv[])
187 std::string input_directory =
"data";
188 std::string config_color =
"model/cube/cube.xml", config_depth =
"model/cube/cube_depth.xml";
189 std::string model_color =
"model/cube/cube.cao", model_depth =
"model/cube/cube.cao";
190 std::string init_file =
"model/cube/cube.init";
191 unsigned int frame_cpt = 0;
192 DepthType use_depth = DEPTH_DENSE;
194 for (
int i = 1;
i < argc;
i++) {
195 if (std::string(argv[i]) ==
"--input_directory" && i + 1 < argc) {
196 input_directory = std::string(argv[i + 1]);
198 else if (std::string(argv[i]) ==
"--config_color" && i + 1 < argc) {
199 config_color = std::string(argv[i + 1]);
201 else if (std::string(argv[i]) ==
"--config_depth" && i + 1 < argc) {
202 config_depth = std::string(argv[i + 1]);
204 else if (std::string(argv[i]) ==
"--model_color" && i + 1 < argc) {
205 model_color = std::string(argv[i + 1]);
207 else if (std::string(argv[i]) ==
"--model_depth" && i + 1 < argc) {
208 model_depth = std::string(argv[i + 1]);
210 else if (std::string(argv[i]) ==
"--init_file" && i + 1 < argc) {
211 init_file = std::string(argv[i + 1]);
213 else if (std::string(argv[i]) ==
"--use_depth" && i + 1 < argc) {
214 use_depth = depthTypeFromString(std::string(argv[i + 1]));
216 else if (std::string(argv[i]) ==
"--help" || std::string(argv[i]) ==
"-h") {
217 std::cout <<
"Usage: \n"
219 <<
" --input_directory <data directory> --config_color <object.xml> --config_depth <object.xml>"
220 " --model_color <object.cao> --model_depth <object.cao> --init_file <object.init> --use_depth " << getDepthTypeList()
225 <<
" --config_color model/cube/cube.xml --config_depth model/cube/cube.xml"
226 " --model_color model/cube/cube.cao --model_depth model/cube/cube.cao --init_file model/cube/cube.init --use_depth "<< depthTypeToString(use_depth) <<
"\n"
232 std::cout <<
"Tracked features: " << std::endl;
233#if defined(VISP_HAVE_OPENCV)
234 std::cout <<
" Use edges : 1" << std::endl;
235#if defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_VIDEO)
236 std::cout <<
" Use klt : 1" << std::endl;
238 std::cout <<
" Use klt : 0" << std::endl;
240 std::cout <<
" Use depth : " << depthTypeToString(use_depth) << std::endl;
242 std::cout <<
" Use edges : 1" << std::endl;
243 std::cout <<
" Use klt : 0" << std::endl;
244 std::cout <<
" Use depth : 0" << std::endl;
246 std::cout <<
"Config files: " << std::endl;
247 std::cout <<
" Input directory: "
248 <<
"\"" << input_directory <<
"\"" << std::endl;
249 std::cout <<
" Config color: "
250 <<
"\"" << config_color <<
"\"" << std::endl;
251 std::cout <<
" Config depth: "
252 <<
"\"" << config_depth <<
"\"" << std::endl;
253 std::cout <<
" Model color : "
254 <<
"\"" << model_color <<
"\"" << std::endl;
255 std::cout <<
" Model depth : "
256 <<
"\"" << model_depth <<
"\"" << std::endl;
257 std::cout <<
" Init file : "
258 <<
"\"" << init_file <<
"\"" << std::endl;
266 pcl::PointCloud<pcl::PointXYZ>::Ptr pointcloud(
new pcl::PointCloud<pcl::PointXYZ>());
270 read_data(frame_cpt, input_directory, I_color, I_depth_raw, pointcloud);
274#if defined(VISP_HAVE_DISPLAY)
275#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
282 unsigned int _posx = 100, _posy = 50, _posdx = 10;
283 display1->init(I_gray, _posx, _posy,
"Color stream");
284 display2->init(I_depth, _posx + I_gray.
getWidth() + _posdx, _posy,
"Depth stream");
293 std::vector<int> trackerTypes;
294#if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_VIDEO)
299 if (use_depth == DEPTH_DENSE) {
302 else if (use_depth == DEPTH_NORMAL) {
307#if defined(VISP_HAVE_PUGIXML)
309 tracker.loadConfigFile(config_color, config_depth);
314 cam_color.initPersProjWithoutDistortion(614.9, 614.9, 320.2, 241.5);
315 cam_depth.initPersProjWithoutDistortion(384.0, 384.0, 320.5, 235.6);
316 tracker.setCameraParameters(cam_color, cam_depth);
332#if defined(VISP_HAVE_MODULE_KLT) && defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_VIDEO)
348 tracker.setDepthNormalPclPlaneEstimationMethod(2);
349 tracker.setDepthNormalPclPlaneEstimationRansacMaxIter(200);
350 tracker.setDepthNormalPclPlaneEstimationRansacThreshold(0.001);
351 tracker.setDepthNormalSamplingStep(2, 2);
353 tracker.setDepthDenseSamplingStep(4, 4);
357 tracker.setNearClippingDistance(0.001);
358 tracker.setFarClippingDistance(5.0);
362 tracker.loadModel(model_color, model_depth);
365 tracker.getCameraParameters(cam_color, cam_depth);
367 std::cout <<
"Camera parameters for color camera (from XML file): " <<
cam_color << std::endl;
368 std::cout <<
"Camera parameters for depth camera (from XML file): " <<
cam_depth << std::endl;
371 tracker.setDisplayFeatures(
true);
377 std::ifstream file((std::string(input_directory +
"/depth_M_color.txt")).c_str());
381 std::map<std::string, vpHomogeneousMatrix> mapOfCameraTransformations;
384 tracker.setCameraTransformationMatrix(mapOfCameraTransformations);
386 std::cout <<
"depth_M_color: \n" <<
depth_M_color << std::endl;
389 std::map<std::string, const vpImage<unsigned char> *> mapOfImages;
390 mapOfImages[
"Camera1"] = &I_gray;
391 mapOfImages[
"Camera2"] = &
I_depth;
395 std::map<std::string, std::string> mapOfInitFiles;
396 mapOfInitFiles[
"Camera1"] = init_file;
397 tracker.initClick(mapOfImages, mapOfInitFiles,
true);
401 pcl::PointCloud<pcl::PointXYZ>::Ptr empty_pointcloud(
new pcl::PointCloud<pcl::PointXYZ>);
402 std::vector<double> times_vec;
408 quit = !
read_data(frame_cpt, input_directory, I_color, I_depth_raw, pointcloud);
415 mapOfImages[
"Camera1"] = &I_gray;
416 std::map<std::string, pcl::PointCloud<pcl::PointXYZ>::ConstPtr> mapOfPointclouds;
417 if (use_depth == DEPTH_UNUSED) {
418 mapOfPointclouds[
"Camera2"] = empty_pointcloud;
421 mapOfPointclouds[
"Camera2"] = pointcloud;
425 tracker.track(mapOfImages, mapOfPointclouds);
432 std::cout <<
"iter: " << frame_cpt <<
" cMo:\n" <<
cMo << std::endl;
435 tracker.display(I_gray, I_depth, cMo, depth_M_color * cMo, cam_color, cam_depth,
vpColor::red, 3);
441 times_vec.push_back(t);
443 std::stringstream ss;
444 ss <<
"Computation time: " <<
t <<
" ms";
447 std::stringstream ss;
448 ss <<
"Nb features: " <<
tracker.getError().size();
452 std::stringstream ss;
453 ss <<
"Features: edges " <<
tracker.getNbFeaturesEdge() <<
", klt " <<
tracker.getNbFeaturesKlt() <<
", depth "
454 <<
tracker.getNbFeaturesDepthDense();
470 std::cout <<
"Catch exception: " <<
e.getStringMessage() << std::endl;
473#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11) && defined(VISP_HAVE_DISPLAY)
474 if (display1 !=
nullptr) {
477 if (display2 !=
nullptr) {
495 std::cout <<
"To run this tutorial, ViSP should be build with PCL library."
496 " Install libpcl, configure and build again ViSP..."
Generic class defining intrinsic camera parameters.
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.
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)
static void read(vpImage< unsigned char > &I, const std::string &filename, int backend=IO_DEFAULT_BACKEND)
Definition of the vpImage class member functions.
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)
read_data(CameraParameters|None cam_depth, ImageGray I, rs.pipeline pipe)
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()