1 #include <visp3/core/vpConfig.h>
3 #ifdef VISP_HAVE_MODULE_SENSOR
4 #include <visp3/sensor/vpRealSense2.h>
7 #include <visp3/detection/vpDetectorAprilTag.h>
9 #include <visp3/core/vpImageConvert.h>
10 #include <visp3/gui/vpDisplayGDI.h>
11 #include <visp3/gui/vpDisplayOpenCV.h>
12 #include <visp3/gui/vpDisplayX.h>
13 #include <visp3/vision/vpPose.h>
15 int main(
int argc,
const char **argv)
18 #if defined(VISP_HAVE_APRILTAG) && defined(VISP_HAVE_REALSENSE2)
20 #ifdef ENABLE_VISP_NAMESPACE
26 double tagSize = 0.053;
27 float quad_decimate = 1.0;
29 bool display_tag =
false;
31 unsigned int thickness = 2;
32 bool align_frame =
false;
33 bool opt_verbose =
false;
35 #if !(defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI) || defined(VISP_HAVE_OPENCV))
36 bool display_off =
true;
37 std::cout <<
"Warning: There is no 3rd party (X11, GDI or openCV) to dislay images..." << std::endl;
39 bool display_off =
false;
42 for (
int i = 1; i < argc; i++) {
43 if (std::string(argv[i]) ==
"--pose_method" && i + 1 < argc) {
46 else if (std::string(argv[i]) ==
"--tag_size" && i + 1 < argc) {
47 tagSize = atof(argv[i + 1]);
49 else if (std::string(argv[i]) ==
"--quad_decimate" && i + 1 < argc) {
50 quad_decimate = (float)atof(argv[i + 1]);
52 else if (std::string(argv[i]) ==
"--nthreads" && i + 1 < argc) {
53 nThreads = atoi(argv[i + 1]);
55 else if (std::string(argv[i]) ==
"--display_tag") {
58 else if (std::string(argv[i]) ==
"--display_off") {
61 else if (std::string(argv[i]) ==
"--color" && i + 1 < argc) {
62 color_id = atoi(argv[i + 1]);
64 else if (std::string(argv[i]) ==
"--thickness" && i + 1 < argc) {
65 thickness = (
unsigned int)atoi(argv[i + 1]);
67 else if (std::string(argv[i]) ==
"--tag_family" && i + 1 < argc) {
70 else if (std::string(argv[i]) ==
"--z_aligned") {
73 else if (std::string(argv[i]) ==
"--verbose" || std::string(argv[i]) ==
"-v") {
76 else if (std::string(argv[i]) ==
"--help" || std::string(argv[i]) ==
"-h") {
77 std::cout <<
"Usage: " << argv[0]
78 <<
" [--tag_size <tag_size in m> (default: 0.053)]"
79 " [--quad_decimate <quad_decimate> (default: 1)]"
80 " [--nthreads <nb> (default: 1)]"
81 " [--pose_method <method> (0: HOMOGRAPHY, 1: HOMOGRAPHY_VIRTUAL_VS, "
82 " 2: DEMENTHON_VIRTUAL_VS, 3: LAGRANGE_VIRTUAL_VS, "
83 " 4: BEST_RESIDUAL_VIRTUAL_VS, 5: HOMOGRAPHY_ORTHOGONAL_ITERATION) (default: 0)]"
84 " [--tag_family <family> (0: TAG_36h11, 1: TAG_36h10 (DEPRECATED), 2: TAG_36ARTOOLKIT (DEPRECATED),"
85 " 3: TAG_25h9, 4: TAG_25h7 (DEPRECATED), 5: TAG_16h5, 6: TAG_CIRCLE21h7, 7: TAG_CIRCLE49h12,"
86 " 8: TAG_CUSTOM48h12, 9: TAG_STANDARD41h12, 10: TAG_STANDARD52h13) (default: 0)]"
87 " [--display_tag] [--z_aligned]";
88 #if (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI) || defined(VISP_HAVE_OPENCV))
89 std::cout <<
" [--display_off] [--color <color id>] [--thickness <line thickness>]";
91 std::cout <<
" [--verbose,-v] [--help,-h]" << std::endl;
98 std::cout <<
"Use Realsense 2 grabber" << std::endl;
101 unsigned int width = 640, height = 480;
102 config.enable_stream(RS2_STREAM_COLOR,
static_cast<int>(width),
static_cast<int>(height), RS2_FORMAT_RGBA8, 30);
103 config.enable_stream(RS2_STREAM_DEPTH,
static_cast<int>(width),
static_cast<int>(height), RS2_FORMAT_Z16, 30);
104 config.enable_stream(RS2_STREAM_INFRARED,
static_cast<int>(width),
static_cast<int>(height), RS2_FORMAT_Y8, 30);
113 std::cout <<
"I_color: " << I_color.getWidth() <<
" " << I_color.getHeight() << std::endl;
114 std::cout <<
"I_depth_raw: " << I_depth_raw.getWidth() <<
" " << I_depth_raw.getHeight() << std::endl;
116 rs2::align align_to_color = RS2_STREAM_COLOR;
117 g.
acquire(
reinterpret_cast<unsigned char *
>(I_color.bitmap),
reinterpret_cast<unsigned char *
>(I_depth_raw.bitmap),
118 nullptr,
nullptr, &align_to_color);
120 std::cout <<
"Read camera parameters from Realsense device" << std::endl;
125 std::cout << cam << std::endl;
126 std::cout <<
"poseEstimationMethod: " << poseEstimationMethod << std::endl;
127 std::cout <<
"tagFamily: " << tagFamily << std::endl;
128 std::cout <<
"nThreads : " << nThreads << std::endl;
129 std::cout <<
"Z aligned: " << align_frame << std::endl;
140 d1 =
new vpDisplayX(I_color, 100, 30,
"Pose from Homography");
141 d2 =
new vpDisplayX(I_color2, I_color.getWidth() + 120, 30,
"Pose from RGBD fusion");
142 d3 =
new vpDisplayX(I_depth, 100, I_color.getHeight() + 70,
"Depth");
143 #elif defined(VISP_HAVE_GDI)
144 d1 =
new vpDisplayGDI(I_color, 100, 30,
"Pose from Homography");
145 d2 =
new vpDisplayGDI(I_color2, I_color.getWidth() + 120, 30,
"Pose from RGBD fusion");
146 d3 =
new vpDisplayGDI(I_depth, 100, I_color.getHeight() + 70,
"Depth");
147 #elif defined(HAVE_OPENCV_HIGHGUI)
149 d2 =
new vpDisplayOpenCV(I_color2, I_color.getWidth() + 120, 30,
"Pose from RGBD fusion");
150 d3 =
new vpDisplayOpenCV(I_depth, 100, I_color.getHeight() + 70,
"Depth");
159 detector.setAprilTagQuadDecimate(quad_decimate);
160 detector.setAprilTagPoseEstimationMethod(poseEstimationMethod);
161 detector.setAprilTagNbThreads(nThreads);
163 detector.setZAlignedWithCameraAxis(align_frame);
165 std::vector<double> time_vec;
170 g.
acquire(
reinterpret_cast<unsigned char *
>(I_color.bitmap),
171 reinterpret_cast<unsigned char *
>(I_depth_raw.bitmap),
nullptr,
nullptr, &align_to_color);
178 depthMap.
resize(I_depth_raw.getHeight(), I_depth_raw.getWidth());
179 #ifdef VISP_HAVE_OPENMP
180 #pragma omp parallel for
182 for (
int i = 0; i < static_cast<int>(I_depth_raw.getHeight()); i++) {
183 for (
int j = 0; j < static_cast<int>(I_depth_raw.getWidth()); j++) {
184 if (I_depth_raw[i][j]) {
185 float Z = I_depth_raw[i][j] * depth_scale;
198 std::vector<vpHomogeneousMatrix> cMo_vec;
199 detector.detect(I, tagSize, cam, cMo_vec);
202 for (
size_t i = 0; i < cMo_vec.size(); i++) {
207 std::vector<std::vector<vpImagePoint> > tags_corners = detector.getPolygon();
208 std::vector<int> tags_id = detector.getTagsId();
209 std::map<int, double> tags_size;
210 tags_size[-1] = tagSize;
211 std::vector<std::vector<vpPoint> > tags_points3d = detector.getTagsPoints3D(tags_id, tags_size);
212 for (
size_t i = 0; i < tags_corners.size(); i++) {
214 double confidence_index;
216 &confidence_index)) {
217 if (confidence_index > 0.5) {
220 else if (confidence_index > 0.25) {
226 std::stringstream ss;
227 ss <<
"Tag id " << tags_id[i] <<
" confidence: " << confidence_index;
231 std::cout <<
"cMo[" << i <<
"]: \n" << cMo_vec[i] << std::endl;
232 std::cout <<
"cMo[" << i <<
"] using depth: \n" << cMo << std::endl;
242 time_vec.push_back(t);
244 std::stringstream ss;
245 ss <<
"Detection time: " << t <<
" ms for " << detector.getNbObjects() <<
" tags";
256 std::cout <<
"Benchmark loop processing time" << std::endl;
257 std::cout <<
"Mean / Median / Std: " <<
vpMath::getMean(time_vec) <<
" ms"
269 std::cerr <<
"Catch an exception: " << e.
getMessage() << std::endl;
276 #ifndef VISP_HAVE_APRILTAG
277 std::cout <<
"Enable Apriltag support, configure and build ViSP to run this tutorial" << std::endl;
279 std::cout <<
"Install librealsense 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 vpColor getColor(const unsigned int &i)
static const vpColor none
static const vpColor orange
@ TAG_36h11
AprilTag 36h11 pattern (recommended)
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...
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)
void resize(unsigned int h, unsigned int w)
resize the image : Image initialization
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)
static bool computePlanarObjectPoseFromRGBD(const vpImage< float > &depthMap, const std::vector< vpImagePoint > &corners, const vpCameraParameters &colorIntrinsics, const std::vector< vpPoint > &point3d, vpHomogeneousMatrix &cMo, double *confidence_index=nullptr)
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())
VISP_EXPORT double measureTimeMs()