39 #include <visp3/core/vpConfig.h>
41 #if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) \
42 && defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI))
44 #include <visp3/core/vpImage.h>
45 #include <visp3/core/vpImageConvert.h>
46 #include <visp3/core/vpMeterPixelConversion.h>
47 #include <visp3/gui/vpDisplayGDI.h>
48 #include <visp3/gui/vpDisplayX.h>
49 #include <visp3/sensor/vpRealSense2.h>
51 #ifdef ENABLE_VISP_NAMESPACE
57 void createDepthHist(std::vector<uint32_t> &histogram2,
const pcl::PointCloud<pcl::PointXYZ>::Ptr &pointcloud,
60 std::fill(histogram2.begin(), histogram2.end(), 0);
62 for (uint32_t i = 0; i < pointcloud->height; i++) {
63 for (uint32_t j = 0; j < pointcloud->width; j++) {
64 const pcl::PointXYZ &pcl_pt = pointcloud->at(j, i);
65 ++histogram2[
static_cast<uint32_t
>(pcl_pt.z * depth_scale)];
69 for (
int i = 2; i < 0x10000; i++)
70 histogram2[i] += histogram2[i - 1];
74 void createDepthHist(std::vector<uint32_t> &histogram2,
const std::vector<vpColVector> &pointcloud,
double depth_scale)
76 std::fill(histogram2.begin(), histogram2.end(), 0);
78 for (
size_t i = 0; i < pointcloud.size(); i++) {
80 ++histogram2[
static_cast<uint32_t
>(pt[2] * depth_scale)];
83 for (
int i = 2; i < 0x10000; i++)
84 histogram2[i] += histogram2[i - 1];
88 unsigned char getDepthColor(
const std::vector<uint32_t> &histogram2,
double z,
double depth_scale)
91 return static_cast<unsigned char>(histogram2[
static_cast<uint32_t
>(z * depth_scale)] * 255 / histogram2[0xFFFF]);
95 int main(
int argc,
char *argv[])
97 bool align_to_depth =
false;
98 bool color_pointcloud =
false;
99 bool col_vector =
false;
100 bool no_align =
false;
101 for (
int i = 1; i < argc; i++) {
102 if (std::string(argv[i]) ==
"--align_to_depth") {
103 align_to_depth =
true;
105 else if (std::string(argv[i]) ==
"--color") {
106 color_pointcloud =
true;
108 else if (std::string(argv[i]) ==
"--col_vector") {
111 else if (std::string(argv[i]) ==
"--no_align") {
116 std::cout <<
"align_to_depth: " << align_to_depth << std::endl;
117 std::cout <<
"color_pointcloud: " << color_pointcloud << std::endl;
118 std::cout <<
"col_vector: " << col_vector << std::endl;
119 std::cout <<
"no_align: " << no_align << std::endl;
123 const int width = 640, height = 480, fps = 30;
124 config.enable_stream(RS2_STREAM_COLOR, width, height, RS2_FORMAT_RGBA8, fps);
125 config.enable_stream(RS2_STREAM_DEPTH, width, height, RS2_FORMAT_Z16, fps);
126 config.enable_stream(RS2_STREAM_INFRARED, width, height, RS2_FORMAT_Y8, fps);
130 vpImage<vpRGBa> I_color(height, width), I_depth(height, width), I_pcl(height, width), I_pcl2(height, width);
131 vpImage<vpRGBa> I_display(height * 2, width), I_display2(height * 2, width), I_display3(height * 2, width);
135 vpDisplayX d1, d2, d3;
139 d1.
init(I_display, 0, 0,
"Color + depth");
140 d2.init(I_display2, width, 0,
"Color + ROS pointcloud");
141 d3.init(I_display3, 2 * width, 0,
"Color + pointcloud");
143 pcl::PointCloud<pcl::PointXYZ>::Ptr pointcloud(
new pcl::PointCloud<pcl::PointXYZ>());
144 pcl::PointCloud<pcl::PointXYZRGB>::Ptr pointcloud_color(
new pcl::PointCloud<pcl::PointXYZRGB>());
145 std::vector<vpColVector> vp_pointcloud;
146 std::vector<uint32_t> histogram(0x10000), histogram2(0x10000);
148 rs2::align align_to(align_to_depth ? RS2_STREAM_DEPTH : RS2_STREAM_COLOR);
153 if (color_pointcloud) {
154 rs.
acquire(
reinterpret_cast<unsigned char *
>(I_color.bitmap),
155 reinterpret_cast<unsigned char *
>(I_depth_raw.bitmap), &vp_pointcloud, pointcloud_color,
nullptr,
156 no_align ?
nullptr : &align_to);
159 rs.
acquire(
reinterpret_cast<unsigned char *
>(I_color.bitmap),
160 reinterpret_cast<unsigned char *
>(I_depth_raw.bitmap), &vp_pointcloud, pointcloud,
nullptr,
161 no_align ?
nullptr : &align_to);
167 if (color_pointcloud) {
168 for (uint32_t i = 0; i < pointcloud_color->height; i++) {
169 for (uint32_t j = 0; j < pointcloud_color->width; j++) {
170 const pcl::PointXYZRGB &pcl_pt = pointcloud_color->at(j, i);
173 double x = pcl_pt.x / Z;
174 double y = pcl_pt.y / Z;
179 std::min<unsigned int>(
static_cast<unsigned int>(width - 1),
static_cast<unsigned int>(std::max<double>(0.0, imPt.
get_u())));
181 std::min<unsigned int>(
static_cast<unsigned int>(height - 1),
static_cast<unsigned int>(std::max<double>(0.0, imPt.
get_v())));
182 I_pcl[v][u] =
vpRGBa(pcl_pt.r, pcl_pt.g, pcl_pt.b);
188 createDepthHist(histogram, pointcloud, depth_scale);
190 for (uint32_t i = 0; i < pointcloud->height; i++) {
191 for (uint32_t j = 0; j < pointcloud->width; j++) {
192 const pcl::PointXYZ &pcl_pt = pointcloud->at(j, i);
195 double x = pcl_pt.x / Z;
196 double y = pcl_pt.y / Z;
201 std::min<unsigned int>(
static_cast<unsigned int>(width - 1),
static_cast<unsigned int>(std::max<double>(0.0, imPt.
get_u())));
203 std::min<unsigned int>(
static_cast<unsigned int>(height - 1),
static_cast<unsigned int>(std::max<double>(0.0, imPt.
get_v())));
204 unsigned char depth_viz = getDepthColor(histogram, pcl_pt.z, depth_scale);
205 I_pcl[v][u] =
vpRGBa(depth_viz, depth_viz, depth_viz);
212 createDepthHist(histogram2, vp_pointcloud, depth_scale);
213 for (
size_t i = 0; i < vp_pointcloud.size(); i++) {
217 double x = pt[0] / Z;
218 double y = pt[1] / Z;
223 std::min<unsigned int>(
static_cast<unsigned int>(width - 1),
static_cast<unsigned int>(std::max<double>(0.0, imPt.
get_u())));
225 std::min<unsigned int>(
static_cast<unsigned int>(height - 1),
static_cast<unsigned int>(std::max<double>(0.0, imPt.
get_v())));
226 unsigned char depth_viz = getDepthColor(histogram2, Z, depth_scale);
227 I_pcl2[v][u] =
vpRGBa(depth_viz, depth_viz, depth_viz);
232 I_display.insert(I_depth,
vpImagePoint(I_color.getHeight(), 0));
235 I_display2.insert(I_pcl,
vpImagePoint(I_color.getHeight(), 0));
238 I_display3.insert(I_pcl2,
vpImagePoint(I_color.getHeight(), 0));
244 const int nb_lines = 5;
245 for (
int i = 1; i < nb_lines; i++) {
246 const int col_idx = i * (width / nb_lines);
266 int main() {
return EXIT_SUCCESS; }
Generic class defining intrinsic camera parameters.
Implementation of column vector and the associated operations.
static const vpColor green
Display for windows using GDI (available on any windows 32 platform).
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 displayLine(const vpImage< unsigned char > &I, const vpImagePoint &ip1, const vpImagePoint &ip2, const vpColor &color, unsigned int thickness=1, bool segment=true)
static void flush(const vpImage< unsigned char > &I)
static void createDepthHistogram(const vpImage< uint16_t > &src_depth, vpImage< vpRGBa > &dest_rgba)
Class that defines a 2D point in an image. This class is useful for image processing and stores only ...
static void convertPoint(const vpCameraParameters &cam, const double &x, const double &y, double &u, double &v)
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())