43 const sensor_msgs::ImageConstPtr& right_raw,
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::BGR8) {
201 const cv::Vec3b& bgr = color.at<cv::Vec3b>(u,v);
202 int32_t rgb_packed = (bgr[2] << 16) | (bgr[1] << 8) | bgr[0];
203 points.channels[0].values.push_back(*(
float*)(&rgb_packed));
209 ROS_WARN(
"Could not fill color channel of the point cloud, unrecognized encoding '%s'", encoding.c_str());
214 const cv::Mat& color,
const std::string& encoding,
216 sensor_msgs::PointCloud2& points)
const 219 const sensor_msgs::Image& dimage = disparity.image;
220 const cv::Mat_<float> dmat(dimage.height, dimage.width, (
float*)&dimage.data[0], dimage.step);
226 points.fields.resize (4);
227 points.fields[0].name =
"x";
228 points.fields[0].offset = 0;
229 points.fields[0].count = 1;
230 points.fields[0].datatype = sensor_msgs::PointField::FLOAT32;
231 points.fields[1].name =
"y";
232 points.fields[1].offset = 4;
233 points.fields[1].count = 1;
234 points.fields[1].datatype = sensor_msgs::PointField::FLOAT32;
235 points.fields[2].name =
"z";
236 points.fields[2].offset = 8;
237 points.fields[2].count = 1;
238 points.fields[2].datatype = sensor_msgs::PointField::FLOAT32;
239 points.fields[3].name =
"rgb";
240 points.fields[3].offset = 12;
241 points.fields[3].count = 1;
242 points.fields[3].datatype = sensor_msgs::PointField::FLOAT32;
244 points.point_step = 16;
245 points.row_step = points.point_step * points.width;
246 points.data.resize (points.row_step * points.height);
247 points.is_dense =
false;
249 float bad_point = std::numeric_limits<float>::quiet_NaN ();
255 memcpy (&points.data[i * points.point_step + 0], &
dense_points_(u,v)[0],
sizeof (
float));
256 memcpy (&points.data[i * points.point_step + 4], &
dense_points_(u,v)[1],
sizeof (
float));
257 memcpy (&points.data[i * points.point_step + 8], &
dense_points_(u,v)[2],
sizeof (
float));
260 memcpy (&points.data[i * points.point_step + 0], &bad_point, sizeof (
float));
261 memcpy (&points.data[i * points.point_step + 4], &bad_point, sizeof (
float));
262 memcpy (&points.data[i * points.point_step + 8], &bad_point, sizeof (
float));
270 if (encoding == enc::MONO8) {
274 uint8_t g = color.at<uint8_t>(u,v);
275 int32_t rgb = (g << 16) | (g << 8) | g;
276 memcpy (&points.data[i * points.point_step + 12], &rgb, sizeof (int32_t));
279 memcpy (&points.data[i * points.point_step + 12], &bad_point, sizeof (
float));
284 else if (encoding == enc::RGB8) {
288 const cv::Vec3b& rgb = color.at<cv::Vec3b>(u,v);
289 int32_t rgb_packed = (rgb[0] << 16) | (rgb[1] << 8) | rgb[2];
290 memcpy (&points.data[i * points.point_step + 12], &rgb_packed, sizeof (int32_t));
293 memcpy (&points.data[i * points.point_step + 12], &bad_point, sizeof (
float));
298 else if (encoding == enc::BGR8) {
302 const cv::Vec3b& bgr = color.at<cv::Vec3b>(u,v);
303 int32_t rgb_packed = (bgr[2] << 16) | (bgr[1] << 8) | bgr[0];
304 memcpy (&points.data[i * points.point_step + 12], &rgb_packed, sizeof (int32_t));
307 memcpy (&points.data[i * points.point_step + 12], &bad_point, sizeof (
float));
313 ROS_WARN(
"Could not fill color channel of the point cloud, unrecognized encoding '%s'", encoding.c_str());
const PinholeCameraModel & right() const
const PinholeCameraModel & left() const
image_proc::Processor mono_processor_
cv::Mat_< int16_t > disparity16_
std::string color_encoding
int getMinDisparity() const
bool process(const sensor_msgs::ImageConstPtr &raw_image, const image_geometry::PinholeCameraModel &model, ImageSet &output, int flags=ALL) const
void projectDisparityImageTo3d(const cv::Mat &disparity, cv::Mat &point_cloud, bool handleMissingValues=false) const
image_proc::ImageSet left
static const double MISSING_Z
cv::Mat_< cv::Vec3f > dense_points_
bool process(const sensor_msgs::ImageConstPtr &left_raw, const sensor_msgs::ImageConstPtr &right_raw, const image_geometry::StereoCameraModel &model, StereoImageSet &output, int flags) const
void processDisparity(const cv::Mat &left_rect, const cv::Mat &right_rect, const image_geometry::StereoCameraModel &model, stereo_msgs::DisparityImage &disparity) const
void processPoints(const stereo_msgs::DisparityImage &disparity, const cv::Mat &color, const std::string &encoding, const image_geometry::StereoCameraModel &model, sensor_msgs::PointCloud &points) const
const std::string TYPE_32FC1
sensor_msgs::PointCloud points
bool isValidPoint(const cv::Vec3f &pt)
stereo_msgs::DisparityImage disparity
cv::StereoBM block_matcher_
void processPoints2(const stereo_msgs::DisparityImage &disparity, const cv::Mat &color, const std::string &encoding, const image_geometry::StereoCameraModel &model, sensor_msgs::PointCloud2 &points) const
int getDisparityRange() const
StereoType current_stereo_algorithm_
cv::StereoSGBM sg_block_matcher_
image_proc::ImageSet right
sensor_msgs::PointCloud2 points2