34 #include <boost/version.hpp>
35 #if ((BOOST_VERSION / 100) % 1000) >= 53
36 #include <boost/thread/lock_guard.hpp>
46 #include <stereo_msgs/DisparityImage.h>
72 void depthCb(
const sensor_msgs::ImageConstPtr& depth_msg,
73 const sensor_msgs::CameraInfoConstPtr& info_msg);
76 void convert(
const sensor_msgs::ImageConstPtr& depth_msg,
77 stereo_msgs::DisparityImagePtr& disp_msg);
90 private_nh.
param(
"queue_size", queue_size, 5);
92 private_nh.
param(
"max_range",
max_range_, std::numeric_limits<double>::infinity());
103 pub_disparity_ = left_nh.advertise<stereo_msgs::DisparityImage>(
"disparity", 1, connect_cb, connect_cb);
124 const sensor_msgs::CameraInfoConstPtr& info_msg)
127 stereo_msgs::DisparityImagePtr disp_msg(
new stereo_msgs::DisparityImage );
128 disp_msg->header = depth_msg->header;
129 disp_msg->image.header = disp_msg->header;
130 disp_msg->image.encoding = enc::TYPE_32FC1;
131 disp_msg->image.height = depth_msg->height;
132 disp_msg->image.width = depth_msg->width;
133 disp_msg->image.step = disp_msg->image.width *
sizeof (float);
134 disp_msg->image.data.resize( disp_msg->image.height * disp_msg->image.step, 0.0f );
135 double fx = info_msg->P[0];
136 disp_msg->T = -info_msg->P[3] / fx;
139 disp_msg->min_disparity = disp_msg->f * disp_msg->T /
max_range_;
140 disp_msg->max_disparity = disp_msg->f * disp_msg->T /
min_range_;
143 if (depth_msg->encoding == enc::TYPE_16UC1)
145 convert<uint16_t>(depth_msg, disp_msg);
147 else if (depth_msg->encoding == enc::TYPE_32FC1)
149 convert<float>(depth_msg, disp_msg);
162 stereo_msgs::DisparityImagePtr& disp_msg)
165 float unit_scaling = DepthTraits<T>::toMeters( T(1) );
166 float constant = disp_msg->f * disp_msg->T / unit_scaling;
168 const T* depth_row =
reinterpret_cast<const T*
>(&depth_msg->data[0]);
169 int row_step = depth_msg->step /
sizeof(T);
170 float* disp_data =
reinterpret_cast<float*
>(&disp_msg->image.data[0]);
171 for (
int v = 0; v < (int)depth_msg->height; ++v)
173 for (
int u = 0; u < (int)depth_msg->width; ++u)
175 T depth = depth_row[u];
176 if (DepthTraits<T>::valid(depth))
177 *disp_data = constant / depth;
181 depth_row += row_step;