43 const sensor_msgs::ImageConstPtr& right_raw,
45 StereoImageSet& output,
int flags)
const
67 processDisparity(output.left.rect, output.right.rect, model, output.disparity);
72 processPoints(output.disparity, output.left.rect_color, output.left.color_encoding, model, output.points);
77 processPoints2(output.disparity, output.left.rect_color, output.left.color_encoding, model, output.points2);
85 stereo_msgs::DisparityImage& disparity)
const
88 static const int DPP = 16;
89 static const double inv_dpp = 1.0 / DPP;
93 #if CV_MAJOR_VERSION >= 3
104 sensor_msgs::Image& dimage = disparity.image;
108 dimage.step = dimage.width *
sizeof(float);
109 dimage.data.resize(dimage.step * dimage.height);
110 cv::Mat_<float> dmat(dimage.height, dimage.width, (
float*)&dimage.data[0], dimage.step);
118 disparity.f = model.
right().
fx();
126 disparity.delta_d = inv_dpp;
137 const cv::Mat& color,
const std::string& encoding,
139 sensor_msgs::PointCloud& points)
const
142 const sensor_msgs::Image& dimage = disparity.image;
143 const cv::Mat_<float> dmat(dimage.height, dimage.width, (
float*)&dimage.data[0], dimage.step);
147 points.points.resize(0);
148 points.channels.resize(3);
149 points.channels[0].name =
"rgb";
150 points.channels[0].values.resize(0);
151 points.channels[1].name =
"u";
152 points.channels[1].values.resize(0);
153 points.channels[2].name =
"v";
154 points.channels[2].values.resize(0);
160 geometry_msgs::Point32 pt;
164 points.points.push_back(pt);
166 points.channels[1].values.push_back(u);
167 points.channels[2].values.push_back(v);
174 points.channels[0].values.reserve(points.points.size());
175 if (encoding == enc::MONO8) {
179 uint8_t g = color.at<uint8_t>(u,v);
180 int32_t rgb = (g << 16) | (g << 8) | g;
181 points.channels[0].values.push_back(*(
float*)(&rgb));
186 else if (encoding == enc::RGB8) {
190 const cv::Vec3b& rgb = color.at<cv::Vec3b>(u,v);
191 int32_t rgb_packed = (rgb[0] << 16) | (rgb[1] << 8) | rgb[2];
192 points.channels[0].values.push_back(*(
float*)(&rgb_packed));
197 else if (encoding == enc::RGBA8) {
201 const cv::Vec4b& rgba = color.at<cv::Vec4b>(u,v);
202 int32_t rgb_packed = (rgba[0] << 16) | (rgba[1] << 8) | rgba[2];
203 points.channels[0].values.push_back(*(
float*)(&rgb_packed));
208 else if (encoding == enc::BGR8) {
212 const cv::Vec3b& bgr = color.at<cv::Vec3b>(u,v);
213 int32_t rgb_packed = (bgr[2] << 16) | (bgr[1] << 8) | bgr[0];
214 points.channels[0].values.push_back(*(
float*)(&rgb_packed));
219 else if (encoding == enc::BGRA8) {
223 const cv::Vec4b& bgra = color.at<cv::Vec4b>(u,v);
224 int32_t rgb_packed = (bgra[2] << 16) | (bgra[1] << 8) | bgra[0];
225 points.channels[0].values.push_back(*(
float*)(&rgb_packed));
231 ROS_WARN(
"Could not fill color channel of the point cloud, unrecognized encoding '%s'", encoding.c_str());
236 const cv::Mat& color,
const std::string& encoding,
238 sensor_msgs::PointCloud2& points)
const
241 const sensor_msgs::Image& dimage = disparity.image;
242 const cv::Mat_<float> dmat(dimage.height, dimage.width, (
float*)&dimage.data[0], dimage.step);
248 points.fields.resize (4);
249 points.fields[0].name =
"x";
250 points.fields[0].offset = 0;
251 points.fields[0].count = 1;
252 points.fields[0].datatype = sensor_msgs::PointField::FLOAT32;
253 points.fields[1].name =
"y";
254 points.fields[1].offset = 4;
255 points.fields[1].count = 1;
256 points.fields[1].datatype = sensor_msgs::PointField::FLOAT32;
257 points.fields[2].name =
"z";
258 points.fields[2].offset = 8;
259 points.fields[2].count = 1;
260 points.fields[2].datatype = sensor_msgs::PointField::FLOAT32;
261 points.fields[3].name =
"rgb";
262 points.fields[3].offset = 12;
263 points.fields[3].count = 1;
264 points.fields[3].datatype = sensor_msgs::PointField::FLOAT32;
266 points.point_step = 16;
267 points.row_step = points.point_step * points.width;
268 points.data.resize (points.row_step * points.height);
269 points.is_dense =
false;
271 float bad_point = std::numeric_limits<float>::quiet_NaN ();
277 memcpy (&points.data[i * points.point_step + 0], &
dense_points_(u,v)[0],
sizeof (
float));
278 memcpy (&points.data[i * points.point_step + 4], &
dense_points_(u,v)[1],
sizeof (
float));
279 memcpy (&points.data[i * points.point_step + 8], &
dense_points_(u,v)[2],
sizeof (
float));
282 memcpy (&points.data[i * points.point_step + 0], &bad_point, sizeof (
float));
283 memcpy (&points.data[i * points.point_step + 4], &bad_point, sizeof (
float));
284 memcpy (&points.data[i * points.point_step + 8], &bad_point, sizeof (
float));
292 if (encoding == enc::MONO8) {
296 uint8_t g = color.at<uint8_t>(u,v);
297 int32_t rgb = (g << 16) | (g << 8) | g;
298 memcpy (&points.data[i * points.point_step + 12], &rgb, sizeof (int32_t));
301 memcpy (&points.data[i * points.point_step + 12], &bad_point, sizeof (
float));
306 else if (encoding == enc::RGB8) {
310 const cv::Vec3b& rgb = color.at<cv::Vec3b>(u,v);
311 int32_t rgb_packed = (rgb[0] << 16) | (rgb[1] << 8) | rgb[2];
312 memcpy (&points.data[i * points.point_step + 12], &rgb_packed, sizeof (int32_t));
315 memcpy (&points.data[i * points.point_step + 12], &bad_point, sizeof (
float));
320 else if (encoding == enc::RGBA8) {
324 const cv::Vec4b& rgba = color.at<cv::Vec4b>(u,v);
325 int32_t rgb_packed = (rgba[0] << 16) | (rgba[1] << 8) | rgba[2];
326 memcpy (&points.data[i * points.point_step + 12], &rgb_packed, sizeof (int32_t));
329 memcpy (&points.data[i * points.point_step + 12], &bad_point, sizeof (
float));
334 else if (encoding == enc::BGR8) {
338 const cv::Vec3b& bgr = color.at<cv::Vec3b>(u,v);
339 int32_t rgb_packed = (bgr[2] << 16) | (bgr[1] << 8) | bgr[0];
340 memcpy (&points.data[i * points.point_step + 12], &rgb_packed, sizeof (int32_t));
343 memcpy (&points.data[i * points.point_step + 12], &bad_point, sizeof (
float));
348 else if (encoding == enc::BGRA8) {
352 const cv::Vec4b& bgra = color.at<cv::Vec4b>(u,v);
353 int32_t rgb_packed = (bgra[2] << 16) | (bgra[1] << 8) | bgra[0];
354 memcpy (&points.data[i * points.point_step + 12], &rgb_packed, sizeof (int32_t));
357 memcpy (&points.data[i * points.point_step + 12], &bad_point, sizeof (
float));
363 ROS_WARN(
"Could not fill color channel of the point cloud, unrecognized encoding '%s'", encoding.c_str());