36 #include <visp3/core/vpConfig.h> 38 #if defined(VISP_HAVE_REALSENSE2) && defined(VISP_HAVE_CPP11_COMPATIBILITY) 42 #include <visp3/core/vpImageConvert.h> 43 #include <visp3/sensor/vpRealSense2.h> 45 #define MANUAL_POINTCLOUD 1 51 : m_colorIntrinsics(), m_depth2ColorExtrinsics(), m_depthIntrinsics(), m_depthScale(0.0f), m_invalidDepthValue(0.0f),
52 m_max_Z(8.0f), m_pipe(), m_pipelineProfile(), m_pointcloud(), m_points()
68 auto data =
m_pipe.wait_for_frames();
69 auto color_frame = data.get_color_frame();
79 auto data =
m_pipe.wait_for_frames();
80 auto color_frame = data.get_color_frame();
93 std::vector<vpColVector> *
const data_pointCloud,
unsigned char *
const data_infrared,
94 rs2::align *
const align_to)
96 auto data =
m_pipe.wait_for_frames();
98 data = align_to->proccess(data);
100 if (data_image != NULL) {
101 auto color_frame = data.get_color_frame();
105 if (data_depth != NULL || data_pointCloud != NULL) {
106 auto depth_frame = data.get_depth_frame();
107 if (data_depth != NULL)
110 if (data_pointCloud != NULL)
114 if (data_infrared != NULL) {
115 auto infrared_frame = data.first(RS2_STREAM_INFRARED);
132 std::vector<vpColVector> *
const data_pointCloud,
133 pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud,
unsigned char *
const data_infrared,
134 rs2::align *
const align_to)
136 auto data =
m_pipe.wait_for_frames();
137 if (align_to != NULL)
138 data = align_to->proccess(data);
140 if (data_image != NULL) {
141 auto color_frame = data.get_color_frame();
145 if (data_depth != NULL || data_pointCloud != NULL || pointcloud != NULL) {
146 auto depth_frame = data.get_depth_frame();
147 if (data_depth != NULL)
150 if (data_pointCloud != NULL)
153 if (pointcloud != NULL)
157 if (data_infrared != NULL) {
158 auto infrared_frame = data.first(RS2_STREAM_INFRARED);
174 std::vector<vpColVector> *
const data_pointCloud,
175 pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud,
unsigned char *
const data_infrared,
176 rs2::align *
const align_to)
178 auto data =
m_pipe.wait_for_frames();
179 if (align_to != NULL)
180 data = align_to->proccess(data);
182 auto color_frame = data.get_color_frame();
183 if (data_image != NULL) {
187 if (data_depth != NULL || data_pointCloud != NULL || pointcloud != NULL) {
188 auto depth_frame = data.get_depth_frame();
189 if (data_depth != NULL)
192 if (data_pointCloud != NULL)
195 if (pointcloud != NULL)
199 if (data_infrared != NULL) {
200 auto infrared_frame = data.first(RS2_STREAM_INFRARED);
230 auto rs_stream =
m_pipelineProfile.get_stream(stream).as<rs2::video_stream_profile>();
231 auto intrinsics = rs_stream.get_intrinsics();
234 double u0 = intrinsics.ppx;
235 double v0 = intrinsics.ppy;
236 double px = intrinsics.fx;
237 double py = intrinsics.fy;
240 double kdu = intrinsics.coeffs[0];
259 return vsp.get_intrinsics();
264 auto vf = frame.as<rs2::video_frame>();
265 const unsigned int width = (
unsigned int)vf.get_width();
266 const unsigned int height = (
unsigned int)vf.get_height();
267 color.
resize(height, width);
269 if (frame.get_profile().format() == RS2_FORMAT_RGB8) {
271 }
else if (frame.get_profile().format() == RS2_FORMAT_RGBA8) {
272 memcpy((
unsigned char *)color.
bitmap, (
unsigned char *)frame.get_data(), width * height *
sizeof(
vpRGBa));
273 }
else if (frame.get_profile().format() == RS2_FORMAT_BGR8) {
282 auto vf = frame.as<rs2::video_frame>();
283 const unsigned int width = (
unsigned int)vf.get_width();
284 const unsigned int height = (
unsigned int)vf.get_height();
285 grey.
resize(height, width);
287 if (frame.get_profile().format() == RS2_FORMAT_RGB8) {
289 }
else if (frame.get_profile().format() == RS2_FORMAT_RGBA8) {
291 }
else if (frame.get_profile().format() == RS2_FORMAT_BGR8) {
300 auto vf = frame.as<rs2::video_frame>();
301 int size = vf.get_width() * vf.get_height();
303 switch (frame.get_profile().format()) {
304 case RS2_FORMAT_RGB8:
305 case RS2_FORMAT_BGR8:
306 memcpy(data, frame.get_data(), size * 3);
309 case RS2_FORMAT_RGBA8:
310 case RS2_FORMAT_BGRA8:
311 memcpy(data, frame.get_data(), size * 4);
316 memcpy(data, frame.get_data(), size * 2);
320 memcpy(data, frame.get_data(), size);
330 auto vf = depth_frame.as<rs2::video_frame>();
331 const int width = vf.get_width();
332 const int height = vf.get_height();
333 pointcloud.resize((
size_t)(width * height));
335 const uint16_t *p_depth_frame =
reinterpret_cast<const uint16_t *
>(depth_frame.get_data());
337 #pragma omp parallel for schedule(dynamic) 338 for (
int i = 0; i < height; i++) {
339 auto depth_pixel_index = i * width;
341 for (
int j = 0; j < width; j++, depth_pixel_index++) {
343 auto pixels_distance =
m_depthScale * p_depth_frame[depth_pixel_index];
346 const float pixel[] = {(float)j, (
float)i};
347 rs2_deproject_pixel_to_point(points, &
m_depthIntrinsics, pixel, pixels_distance);
349 if (pixels_distance <= 0 || pixels_distance >
m_max_Z)
357 pointcloud[(size_t)depth_pixel_index] = v;
365 auto vf = depth_frame.as<rs2::video_frame>();
366 const int width = vf.get_width();
367 const int height = vf.get_height();
368 pointcloud->width = (uint32_t)width;
369 pointcloud->height = (uint32_t)height;
370 pointcloud->resize((
size_t)(width * height));
372 #if MANUAL_POINTCLOUD // faster when tested 373 const uint16_t *p_depth_frame =
reinterpret_cast<const uint16_t *
>(depth_frame.get_data());
375 #pragma omp parallel for schedule(dynamic) 376 for (
int i = 0; i < height; i++) {
377 auto depth_pixel_index = i * width;
379 for (
int j = 0; j < width; j++, depth_pixel_index++) {
381 auto pixels_distance =
m_depthScale * p_depth_frame[depth_pixel_index];
384 const float pixel[] = {(float)j, (
float)i};
385 rs2_deproject_pixel_to_point(points, &
m_depthIntrinsics, pixel, pixels_distance);
387 if (pixels_distance <= 0 || pixels_distance >
m_max_Z)
390 pointcloud->points[(size_t)(depth_pixel_index)].x = points[0];
391 pointcloud->points[(size_t)(depth_pixel_index)].y = points[1];
392 pointcloud->points[(size_t)(depth_pixel_index)].z = points[2];
397 auto vertices =
m_points.get_vertices();
399 for (
size_t i = 0; i <
m_points.size(); i++) {
400 if (vertices[i].z <= 0.0f || vertices[i].z >
m_max_Z) {
405 pointcloud->points[i].x = vertices[i].x;
406 pointcloud->points[i].y = vertices[i].y;
407 pointcloud->points[i].z = vertices[i].z;
414 pcl::PointCloud<pcl::PointXYZRGB>::Ptr &pointcloud)
416 auto vf = depth_frame.as<rs2::video_frame>();
417 const int width = vf.get_width();
418 const int height = vf.get_height();
419 pointcloud->width = (uint32_t)width;
420 pointcloud->height = (uint32_t)height;
421 pointcloud->resize((
size_t)(width * height));
423 const uint16_t *p_depth_frame =
reinterpret_cast<const uint16_t *
>(depth_frame.get_data());
426 auto color_format = color_frame.as<rs2::video_frame>().get_profile().format();
427 bool swap_rgb = color_format == RS2_FORMAT_BGR8 || color_format == RS2_FORMAT_BGRA8;
428 unsigned int nb_color_pixel = (color_format == RS2_FORMAT_RGB8 || color_format == RS2_FORMAT_BGR8) ? 3 : 4;
429 const unsigned char *p_color_frame =
reinterpret_cast<const unsigned char *
>(color_frame.get_data());
431 #pragma omp parallel for schedule(dynamic) 432 for (
int i = 0; i < height; i++) {
433 auto depth_pixel_index = i * width;
435 for (
int j = 0; j < width; j++, depth_pixel_index++) {
437 auto pixels_distance =
m_depthScale * p_depth_frame[depth_pixel_index];
439 float depth_point[3];
440 const float pixel[] = {(float)j, (
float)i};
441 rs2_deproject_pixel_to_point(depth_point, &
m_depthIntrinsics, pixel, pixels_distance);
443 if (pixels_distance <= 0 || pixels_distance >
m_max_Z)
446 pointcloud->points[(size_t)depth_pixel_index].x = depth_point[0];
447 pointcloud->points[(size_t)depth_pixel_index].y = depth_point[1];
448 pointcloud->points[(size_t)depth_pixel_index].z = depth_point[2];
450 float color_point[3];
452 float color_pixel[2];
455 if (color_pixel[1] < 0 || color_pixel[1] >= color_height || color_pixel[0] < 0 || color_pixel[0] >= color_width) {
459 #if PCL_VERSION_COMPARE(<, 1, 1, 0) 460 unsigned int r = 96, g = 157, b = 198;
461 uint32_t rgb = (
static_cast<uint32_t
>(r) << 16 | static_cast<uint32_t>(g) << 8 |
static_cast<uint32_t
>(b));
463 pointcloud->points[(size_t)depth_pixel_index].rgb = *reinterpret_cast<float *>(&rgb);
465 pointcloud->points[(size_t)depth_pixel_index].r = (uint8_t)96;
466 pointcloud->points[(size_t)depth_pixel_index].g = (uint8_t)157;
467 pointcloud->points[(size_t)depth_pixel_index].b = (uint8_t)198;
470 unsigned int i_ = (
unsigned int)color_pixel[1];
471 unsigned int j_ = (
unsigned int)color_pixel[0];
473 #if PCL_VERSION_COMPARE(<, 1, 1, 0) 477 (
static_cast<uint32_t
>(p_color_frame[(i_ * (
unsigned int)color_width + j_) * nb_color_pixel]) |
478 static_cast<uint32_t>(p_color_frame[(i_ * (
unsigned int)color_width + j_) * nb_color_pixel + 1]) << 8 |
479 static_cast<uint32_t
>(p_color_frame[(i_ * (
unsigned int)color_width + j_) * nb_color_pixel + 2]) << 16);
481 rgb = (
static_cast<uint32_t
>(p_color_frame[(i_ * (
unsigned int)color_width + j_) * nb_color_pixel]) << 16 |
482 static_cast<uint32_t>(p_color_frame[(i_ * (
unsigned int)color_width + j_) * nb_color_pixel + 1]) << 8 |
483 static_cast<uint32_t
>(p_color_frame[(i_ * (
unsigned int)color_width + j_) * nb_color_pixel + 2]));
486 pointcloud->points[(size_t)(i * depth_width + j)].rgb = *
reinterpret_cast<float *
>(&rgb);
489 pointcloud->points[(size_t)depth_pixel_index].b =
490 (uint32_t)p_color_frame[(i_ * (
unsigned int)color_width + j_) * nb_color_pixel];
491 pointcloud->points[(size_t)depth_pixel_index].g =
492 (uint32_t)p_color_frame[(i_ * (
unsigned int)color_width + j_) * nb_color_pixel + 1];
493 pointcloud->points[(size_t)depth_pixel_index].r =
494 (uint32_t)p_color_frame[(i_ * (
unsigned int)color_width + j_) * nb_color_pixel + 2];
496 pointcloud->points[(size_t)depth_pixel_index].r =
497 (uint32_t)p_color_frame[(i_ * (
unsigned int)color_width + j_) * nb_color_pixel];
498 pointcloud->points[(size_t)depth_pixel_index].g =
499 (uint32_t)p_color_frame[(i_ * (
unsigned int)color_width + j_) * nb_color_pixel + 1];
500 pointcloud->points[(size_t)depth_pixel_index].b =
501 (uint32_t)p_color_frame[(i_ * (
unsigned int)color_width + j_) * nb_color_pixel + 2];
520 rs2_extrinsics extrinsics = from_stream.get_extrinsics_to(to_stream);
524 for (
unsigned int i = 0; i < 3; i++) {
525 t[i] = extrinsics.translation[i];
526 for (
unsigned int j = 0; j < 3; j++)
527 R[i][j] = extrinsics.rotation[i * 3 + j];
544 for (rs2::sensor &sensor : dev.query_sensors()) {
546 if (rs2::depth_sensor dpt = sensor.as<rs2::depth_sensor>()) {
551 auto depth_stream =
m_pipelineProfile.get_stream(RS2_STREAM_DEPTH).as<rs2::video_stream_profile>();
562 void print(
const rs2_extrinsics &extrinsics, std::ostream &os)
564 std::stringstream ss;
565 ss <<
"Rotation Matrix:\n";
567 for (
auto i = 0; i < 3; ++i) {
568 for (
auto j = 0; j < 3; ++j) {
569 ss << std::left << std::setw(15) << std::setprecision(5) << extrinsics.rotation[j * 3 + i];
574 ss <<
"\nTranslation Vector: ";
575 for (
size_t i = 0; i <
sizeof(extrinsics.translation) /
sizeof(extrinsics.translation[0]); ++i)
576 ss << std::setprecision(15) << extrinsics.translation[i] <<
" ";
578 os << ss.str() <<
"\n\n";
581 void print(
const rs2_intrinsics &intrinsics, std::ostream &os)
583 std::stringstream ss;
584 ss << std::left << std::setw(14) <<
"Width: " 585 <<
"\t" << intrinsics.width <<
"\n" 586 << std::left << std::setw(14) <<
"Height: " 587 <<
"\t" << intrinsics.height <<
"\n" 588 << std::left << std::setw(14) <<
"PPX: " 589 <<
"\t" << std::setprecision(15) << intrinsics.ppx <<
"\n" 590 << std::left << std::setw(14) <<
"PPY: " 591 <<
"\t" << std::setprecision(15) << intrinsics.ppy <<
"\n" 592 << std::left << std::setw(14) <<
"Fx: " 593 <<
"\t" << std::setprecision(15) << intrinsics.fx <<
"\n" 594 << std::left << std::setw(14) <<
"Fy: " 595 <<
"\t" << std::setprecision(15) << intrinsics.fy <<
"\n" 596 << std::left << std::setw(14) <<
"Distortion: " 597 <<
"\t" << rs2_distortion_to_string(intrinsics.model) <<
"\n" 598 << std::left << std::setw(14) <<
"Coeffs: ";
600 for (
size_t i = 0; i <
sizeof(intrinsics.coeffs) /
sizeof(intrinsics.coeffs[0]); ++i)
601 ss <<
"\t" << std::setprecision(15) << intrinsics.coeffs[i] <<
" ";
603 os << ss.str() <<
"\n\n";
606 void safe_get_intrinsics(
const rs2::video_stream_profile &profile, rs2_intrinsics &intrinsics)
609 intrinsics = profile.get_intrinsics();
614 bool operator==(
const rs2_intrinsics &lhs,
const rs2_intrinsics &rhs)
616 return lhs.width == rhs.width && lhs.height == rhs.height && lhs.ppx == rhs.ppx && lhs.ppy == rhs.ppy &&
617 lhs.fx == rhs.fx && lhs.fy == rhs.fy && lhs.model == rhs.model &&
618 !std::memcmp(lhs.coeffs, rhs.coeffs,
sizeof(rhs.coeffs));
621 std::string get_str_formats(
const std::set<rs2_format> &formats)
623 std::stringstream ss;
624 for (
auto format = formats.begin(); format != formats.end(); ++format) {
625 ss << *format << ((format != formats.end()) && (next(format) == formats.end()) ?
"" :
"/");
630 struct stream_and_resolution {
635 std::string stream_name;
637 bool operator<(
const stream_and_resolution &obj)
const 639 return (std::make_tuple(stream, stream_index, width, height) <
640 std::make_tuple(obj.stream, obj.stream_index, obj.width, obj.height));
644 struct stream_and_index {
648 bool operator<(
const stream_and_index &obj)
const 650 return (std::make_tuple(stream, stream_index) < std::make_tuple(obj.stream, obj.stream_index));
677 os << std::left << std::setw(30) <<
"Device Name" << std::setw(20) <<
"Serial Number" << std::setw(20)
678 <<
"Firmware Version" << std::endl;
681 os << std::left << std::setw(30) << dev.get_info(RS2_CAMERA_INFO_NAME) << std::setw(20)
682 << dev.get_info(RS2_CAMERA_INFO_SERIAL_NUMBER) << std::setw(20) << dev.get_info(RS2_CAMERA_INFO_FIRMWARE_VERSION)
686 os <<
" Device info: \n";
687 for (
auto j = 0; j < RS2_CAMERA_INFO_COUNT; ++j) {
688 auto param =
static_cast<rs2_camera_info
>(j);
689 if (dev.supports(param))
690 os <<
" " << std::left << std::setw(30) << rs2_camera_info_to_string(rs2_camera_info(param)) <<
": \t" 691 << dev.get_info(param) <<
"\n";
696 for (
auto &&sensor : dev.query_sensors()) {
697 os <<
"Options for " << sensor.get_info(RS2_CAMERA_INFO_NAME) << std::endl;
699 os << std::setw(55) <<
" Supported options:" << std::setw(10) <<
"min" << std::setw(10) <<
" max" << std::setw(6)
700 <<
" step" << std::setw(10) <<
" default" << std::endl;
701 for (
auto j = 0; j < RS2_OPTION_COUNT; ++j) {
702 auto opt =
static_cast<rs2_option
>(j);
703 if (sensor.supports(opt)) {
704 auto range = sensor.get_option_range(opt);
705 os <<
" " << std::left << std::setw(50) << opt <<
" : " << std::setw(5) << range.min <<
"... " 706 << std::setw(12) << range.max << std::setw(6) << range.step << std::setw(10) << range.def <<
"\n";
713 for (
auto &&sensor : dev.query_sensors()) {
714 os <<
"Stream Profiles supported by " << sensor.get_info(RS2_CAMERA_INFO_NAME) <<
"\n";
716 os << std::setw(55) <<
" Supported modes:" << std::setw(10) <<
"stream" << std::setw(10) <<
" resolution" 717 << std::setw(6) <<
" fps" << std::setw(10) <<
" format" 720 for (
auto &&profile : sensor.get_stream_profiles()) {
721 if (
auto video = profile.as<rs2::video_stream_profile>()) {
722 os <<
" " << profile.stream_name() <<
"\t " << video.width() <<
"x" << video.height() <<
"\t@ " 723 << profile.fps() <<
"Hz\t" << profile.format() <<
"\n";
725 os <<
" " << profile.stream_name() <<
"\t@ " << profile.fps() <<
"Hz\t" << profile.format() <<
"\n";
732 std::map<stream_and_index, rs2::stream_profile> streams;
733 std::map<stream_and_resolution, std::vector<std::pair<std::set<rs2_format>, rs2_intrinsics> > > intrinsics_map;
734 for (
auto &&sensor : dev.query_sensors()) {
736 for (
auto &&profile : sensor.get_stream_profiles()) {
737 if (
auto video = profile.as<rs2::video_stream_profile>()) {
738 if (streams.find(stream_and_index{profile.stream_type(), profile.stream_index()}) == streams.end()) {
739 streams[stream_and_index{profile.stream_type(), profile.stream_index()}] = profile;
742 rs2_intrinsics intrinsics{};
743 stream_and_resolution stream_res{profile.stream_type(), profile.stream_index(), video.width(), video.height(),
744 profile.stream_name()};
745 safe_get_intrinsics(video, intrinsics);
746 auto it = std::find_if(
747 (intrinsics_map[stream_res]).begin(), (intrinsics_map[stream_res]).end(),
748 [&](
const std::pair<std::set<rs2_format>, rs2_intrinsics> &kvp) {
return intrinsics == kvp.second; });
749 if (it == (intrinsics_map[stream_res]).end()) {
750 (intrinsics_map[stream_res]).push_back({{profile.format()}, intrinsics});
752 it->first.insert(profile.format());
760 os <<
"Provided Intrinsic:\n";
761 for (
auto &kvp : intrinsics_map) {
762 auto stream_res = kvp.first;
763 for (
auto &intrinsics : kvp.second) {
764 auto formats = get_str_formats(intrinsics.first);
765 os <<
"Intrinsic of \"" << stream_res.stream_name <<
"\"\t " << stream_res.width <<
"x" << stream_res.height
766 <<
"\t " << formats <<
"\n";
767 if (intrinsics.second == rs2_intrinsics{}) {
768 os <<
"Intrinsic NOT available!\n\n";
770 print(intrinsics.second, os);
776 os <<
"\nProvided Extrinsic:\n";
777 for (
auto kvp1 = streams.begin(); kvp1 != streams.end(); ++kvp1) {
778 for (
auto kvp2 = streams.begin(); kvp2 != streams.end(); ++kvp2) {
779 os <<
"Extrinsic from \"" << kvp1->second.stream_name() <<
"\"\t " 781 <<
"\t \"" << kvp2->second.stream_name() <<
"\"\n";
782 auto extrinsics = kvp1->second.get_extrinsics_to(kvp2->second);
783 print(extrinsics, os);
790 #elif !defined(VISP_BUILD_SHARED_LIBS) 793 void dummy_vpRealSense2(){};
static void BGRToRGBa(unsigned char *bgr, unsigned char *rgba, unsigned int width, unsigned int height, bool flip=false)
rs2_intrinsics getIntrinsics(const rs2_stream &stream) const
static void RGBToGrey(unsigned char *rgb, unsigned char *grey, unsigned int size)
Implementation of an homogeneous matrix and operations on such kind of matrices.
static void RGBToRGBa(unsigned char *rgb, unsigned char *rgba, unsigned int size)
static void BGRToGrey(unsigned char *bgr, unsigned char *grey, unsigned int width, unsigned int height, bool flip=false)
Type * bitmap
points toward the bitmap
error that can be emited by ViSP classes.
void open(const rs2::config &cfg=rs2::config())
rs2_intrinsics m_depthIntrinsics
Implementation of a rotation matrix and operations on such kind of matrices.
void initPersProjWithoutDistortion(const double px, const double py, const double u0, const double v0)
rs2_intrinsics m_colorIntrinsics
rs2::pipeline_profile m_pipelineProfile
vpCameraParametersProjType
void getGreyFrame(const rs2::frame &frame, vpImage< unsigned char > &grey)
Generic class defining intrinsic camera parameters.
rs2_extrinsics m_depth2ColorExtrinsics
void resize(const unsigned int h, const unsigned int w)
resize the image : Image initialization
void acquire(vpImage< unsigned char > &grey)
rs2::pointcloud m_pointcloud
void getPointcloud(const rs2::depth_frame &depth_frame, std::vector< vpColVector > &pointcloud)
Implementation of column vector and the associated operations.
vpCameraParameters getCameraParameters(const rs2_stream &stream, vpCameraParameters::vpCameraParametersProjType type=vpCameraParameters::perspectiveProjWithDistortion) const
float m_invalidDepthValue
void getNativeFrameData(const rs2::frame &frame, unsigned char *const data)
friend VISP_EXPORT std::ostream & operator<<(std::ostream &os, const vpRealSense2 &rs)
vpHomogeneousMatrix getTransformation(const rs2_stream &from, const rs2_stream &to) const
static void RGBaToGrey(unsigned char *rgba, unsigned char *grey, unsigned int size)
void getColorFrame(const rs2::frame &frame, vpImage< vpRGBa > &color)
Class that consider the case of a translation vector.
void initPersProjWithDistortion(const double px, const double py, const double u0, const double v0, const double kud, const double kdu)