34 #include <sensor_msgs/CameraInfo.h>
44 #define POINT_STEP (sizeof(float) * 4)
57 static inline bool valid(
float depth)
63 return depth * 0.001f;
70 static inline bool valid(
float depth)
72 return std::isfinite(depth);
91 sensor_msgs::CameraInfoConstPtr& camera_info_msg)
93 if (!depth_msg || !camera_info_msg)
95 std::string error_msg(
"Waiting for CameraInfo message..");
100 unsigned binning_x = camera_info_msg->binning_x > 1 ? camera_info_msg->binning_x : 1;
101 unsigned binning_y = camera_info_msg->binning_y > 1 ? camera_info_msg->binning_y : 1;
104 camera_info_msg->roi.width > 0 ? camera_info_msg->roi.width : camera_info_msg->width;
105 unsigned roi_height =
106 camera_info_msg->roi.height > 0 ? camera_info_msg->roi.height : camera_info_msg->height;
108 unsigned expected_width = roi_width / binning_x;
109 unsigned expected_height = roi_height / binning_y;
111 if (expected_width != depth_msg->width || expected_height != depth_msg->height)
113 std::ostringstream
s;
114 s <<
"Depth image size and camera info don't match: ";
115 s << depth_msg->width <<
" x " << depth_msg->height;
116 s <<
" vs " << expected_width <<
" x " << expected_height;
117 s <<
"(binning: " << binning_x <<
" x " << binning_y;
118 s <<
", ROI size: " << roi_width <<
" x " << roi_height <<
")";
122 int width = depth_msg->width;
123 int height = depth_msg->height;
125 std::size_t size = width * height;
141 double scale_x = camera_info_msg->binning_x > 1 ? (1.0 / camera_info_msg->binning_x) : 1.0;
142 double scale_y = camera_info_msg->binning_y > 1 ? (1.0 / camera_info_msg->binning_y) : 1.0;
145 float center_x = (camera_info_msg->P[2] - camera_info_msg->roi.x_offset) * scale_x;
146 float center_y = (camera_info_msg->P[6] - camera_info_msg->roi.y_offset) * scale_y;
148 double fx = camera_info_msg->P[0] * scale_x;
149 double fy = camera_info_msg->P[5] * scale_y;
151 float constant_x = 1.0f / fx;
152 float constant_y = 1.0f / fy;
160 for (
int v = 0; v < height; ++v, ++projY)
161 *projY = (v - center_y) * constant_y;
163 for (
int u = 0; u < width; ++u, ++projX)
164 *projX = (u - center_x) * constant_x;
172 template <
typename T>
173 sensor_msgs::PointCloud2Ptr
175 std::vector<uint32_t>& rgba_color_raw)
177 int width = depth_msg->width;
178 int height = depth_msg->height;
181 cloud_msg->data.resize(height * width * cloud_msg->point_step);
183 uint32_t* color_img_ptr =
nullptr;
185 if (!rgba_color_raw.empty())
186 color_img_ptr = &rgba_color_raw[0];
192 float* cloud_data_ptr =
reinterpret_cast<float*
>(&cloud_msg->data[0]);
194 std::size_t point_count = 0;
195 std::size_t point_idx = 0;
197 const T* depth_img_ptr = (T*)&depth_msg->data[0];
199 std::vector<float>::iterator proj_x;
202 std::vector<float>::iterator proj_y;
208 for (proj_x =
projection_map_x_.begin(); proj_x != proj_x_end; ++proj_x, ++point_idx, ++depth_img_ptr)
210 T depth_raw = *depth_img_ptr;
219 color = *color_img_ptr;
223 color = ((uint32_t)255 << 16 | (uint32_t)255 << 8 | (uint32_t)255);
227 *cloud_data_ptr = (*proj_x) * depth;
229 *cloud_data_ptr = (*proj_y) * depth;
231 *cloud_data_ptr = depth;
233 *cloud_data_ptr = *
reinterpret_cast<float*
>(&color);
251 template <
typename T>
252 sensor_msgs::PointCloud2Ptr
254 std::vector<uint32_t>& rgba_color_raw)
256 int width = depth_msg->width;
257 int height = depth_msg->height;
260 cloud_msg->data.resize(height * width * cloud_msg->point_step * 2);
262 uint32_t* color_img_ptr =
nullptr;
264 if (!rgba_color_raw.empty())
265 color_img_ptr = &rgba_color_raw[0];
271 float* cloud_data_ptr =
reinterpret_cast<float*
>(&cloud_msg->data[0]);
274 const std::size_t point_step = cloud_msg->point_step;
276 std::size_t point_count = 0;
277 std::size_t point_idx = 0;
282 const T* depth_img_ptr = (T*)&depth_msg->data[0];
284 std::vector<float>::iterator proj_x;
287 std::vector<float>::iterator proj_y;
294 ++proj_x, ++point_idx, ++depth_img_ptr, cloud_shadow_buffer_ptr += point_step)
306 T depth_raw = *depth_img_ptr;
312 float* cloud_data_pixel_ptr = cloud_data_ptr;
318 color = *color_img_ptr;
322 color = ((uint32_t)255 << 16 | (uint32_t)255 << 8 | (uint32_t)255);
326 *cloud_data_ptr = (*proj_x) * depth;
328 *cloud_data_ptr = (*proj_y) * depth;
330 *cloud_data_ptr = depth;
332 *cloud_data_ptr = *
reinterpret_cast<float*
>(&color);
341 memcpy(cloud_data_ptr, cloud_shadow_buffer_ptr, point_step);
348 memcpy(cloud_shadow_buffer_ptr, cloud_data_pixel_ptr, point_step);
351 RGBA* color =
reinterpret_cast<RGBA*
>(cloud_shadow_buffer_ptr +
sizeof(float) * 3);
364 if (shadow_depth != 0)
367 memcpy(cloud_data_ptr, cloud_shadow_buffer_ptr, point_step);
385 template <
typename T>
387 std::vector<uint32_t>& rgba_color_raw)
390 size_t num_pixel = color_msg->width * color_msg->height;
393 int num_channels = enc::numChannels(color_msg->encoding);
395 bool rgb_encoding =
false;
396 if (color_msg->encoding.find(
"rgb") != std::string::npos)
399 bool has_alpha = enc::hasAlpha(color_msg->encoding);
402 rgba_color_raw.clear();
403 rgba_color_raw.reserve(num_pixel);
405 uint8_t* img_ptr = (uint8_t*)&color_msg->data[
sizeof(T) - 1];
408 switch (num_channels)
412 for (i = 0; i < num_pixel; ++i)
414 uint8_t gray_value = *img_ptr;
415 img_ptr +=
sizeof(T);
417 rgba_color_raw.push_back((uint32_t)gray_value << 16 | (uint32_t)gray_value << 8 |
418 (uint32_t)gray_value);
424 for (i = 0; i < num_pixel; ++i)
426 uint8_t color1 = *((uint8_t*)img_ptr);
427 img_ptr +=
sizeof(T);
428 uint8_t color2 = *((uint8_t*)img_ptr);
429 img_ptr +=
sizeof(T);
430 uint8_t color3 = *((uint8_t*)img_ptr);
431 img_ptr +=
sizeof(T);
434 img_ptr +=
sizeof(T);
439 rgba_color_raw.push_back((uint32_t)color1 << 16 | (uint32_t)color2 << 8 | (uint32_t)color3 << 0);
444 rgba_color_raw.push_back((uint32_t)color3 << 16 | (uint32_t)color2 << 8 | (uint32_t)color1 << 0);
453 sensor_msgs::PointCloud2Ptr
455 const sensor_msgs::ImageConstPtr& color_msg,
456 sensor_msgs::CameraInfoConstPtr camera_info_msg)
459 sensor_msgs::PointCloud2Ptr point_cloud_out;
462 int bitDepth = enc::bitDepth(depth_msg->encoding);
463 int numChannels = enc::numChannels(depth_msg->encoding);
465 if (!camera_info_msg)
473 std::vector<uint32_t> rgba_color_raw_;
477 if (depth_msg->width != color_msg->width || depth_msg->height != color_msg->height)
479 std::stringstream error_msg;
480 error_msg <<
"Depth image resolution (" << (int)depth_msg->width <<
"x" << (
int)depth_msg->height
482 "does not match color image resolution ("
483 << (int)color_msg->width <<
"x" << (
int)color_msg->height <<
")";
488 switch (enc::bitDepth(color_msg->encoding))
491 convertColor<uint8_t>(color_msg, rgba_color_raw_);
494 convertColor<uint16_t>(color_msg, rgba_color_raw_);
497 std::string error_msg(
"Color image has invalid bit depth");
507 if ((bitDepth == 32) && (numChannels == 1))
510 point_cloud_out = generatePointCloudSL<float>(depth_msg, rgba_color_raw_);
512 else if ((bitDepth == 16) && (numChannels == 1))
515 point_cloud_out = generatePointCloudSL<uint16_t>(depth_msg, rgba_color_raw_);
522 if ((bitDepth == 32) && (numChannels == 1))
525 point_cloud_out = generatePointCloudML<float>(depth_msg, rgba_color_raw_);
527 else if ((bitDepth == 16) && (numChannels == 1))
530 point_cloud_out = generatePointCloudML<uint16_t>(depth_msg, rgba_color_raw_);
534 if (!point_cloud_out)
536 std::string error_msg(
"Depth image has invalid format (only 16 bit and float are supported)!");
540 return point_cloud_out;
545 sensor_msgs::PointCloud2Ptr point_cloud_out =
546 sensor_msgs::PointCloud2Ptr(
new sensor_msgs::PointCloud2());
548 point_cloud_out->fields.resize(4);
549 std::size_t point_offset = 0;
551 point_cloud_out->fields[0].name =
"x";
552 point_cloud_out->fields[0].datatype = sensor_msgs::PointField::FLOAT32;
553 point_cloud_out->fields[0].count = 1;
554 point_cloud_out->fields[0].offset = point_offset;
555 point_offset +=
sizeof(float);
557 point_cloud_out->fields[1].name =
"y";
558 point_cloud_out->fields[1].datatype = sensor_msgs::PointField::FLOAT32;
559 point_cloud_out->fields[1].count = 1;
560 point_cloud_out->fields[1].offset = point_offset;
561 point_offset +=
sizeof(float);
563 point_cloud_out->fields[2].name =
"z";
564 point_cloud_out->fields[2].datatype = sensor_msgs::PointField::FLOAT32;
565 point_cloud_out->fields[2].count = 1;
566 point_cloud_out->fields[2].offset = point_offset;
567 point_offset +=
sizeof(float);
569 point_cloud_out->fields[3].name =
"rgb";
570 point_cloud_out->fields[3].datatype = sensor_msgs::PointField::FLOAT32;
571 point_cloud_out->fields[3].count = 1;
572 point_cloud_out->fields[3].offset = point_offset;
573 point_offset +=
sizeof(float);
575 point_cloud_out->point_step = point_offset;
577 point_cloud_out->is_bigendian =
false;
578 point_cloud_out->is_dense =
false;
580 return point_cloud_out;
585 point_cloud->width = size;
586 point_cloud->height = 1;
587 point_cloud->data.resize(point_cloud->height * point_cloud->width * point_cloud->point_step);
588 point_cloud->row_step = point_cloud->point_step * point_cloud->width;