34 #ifndef DEPTH_IMAGE_PROC_DEPTH_CONVERSIONS
35 #define DEPTH_IMAGE_PROC_DEPTH_CONVERSIONS
37 #include <sensor_msgs/Image.h>
51 const sensor_msgs::ImageConstPtr& depth_msg,
52 PointCloud::Ptr& cloud_msg,
54 double range_max = 0.0)
57 float center_x = model.
cx();
58 float center_y = model.
cy();
62 float constant_x = unit_scaling / model.
fx();
63 float constant_y = unit_scaling / model.
fy();
64 float bad_point = std::numeric_limits<float>::quiet_NaN();
69 const T* depth_row =
reinterpret_cast<const T*
>(&depth_msg->data[0]);
70 int row_step = depth_msg->step /
sizeof(T);
71 for (
int v = 0; v < (int)cloud_msg->height; ++v, depth_row += row_step)
73 for (
int u = 0; u < (int)cloud_msg->width; ++u, ++iter_x, ++iter_y, ++iter_z)
75 T depth = depth_row[u];
86 *iter_x = *iter_y = *iter_z = bad_point;
92 *iter_x = (u - center_x) * depth * constant_x;
93 *iter_y = (v - center_y) * depth * constant_y;
94 *iter_z = DepthTraits<T>::toMeters(depth);