34 #include <boost/version.hpp> 35 #if ((BOOST_VERSION / 100) % 1000) >= 53 36 #include <boost/thread/lock_guard.hpp> 49 #include <stereo_msgs/DisparityImage.h> 50 #include <sensor_msgs/PointCloud2.h> 83 virtual void onInit();
87 void imageCb(
const ImageConstPtr& l_image_msg,
88 const CameraInfoConstPtr& l_info_msg,
89 const CameraInfoConstPtr& r_info_msg,
90 const DisparityImageConstPtr& disp_msg);
102 private_nh.
param(
"queue_size", queue_size, 5);
104 private_nh.
param(
"approximate_sync", approx,
false);
108 sub_l_image_, sub_l_info_,
109 sub_r_info_, sub_disparity_) );
111 this, _1, _2, _3, _4));
116 sub_l_image_, sub_l_info_,
117 sub_r_info_, sub_disparity_) );
119 this, _1, _2, _3, _4));
125 boost::lock_guard<boost::mutex> lock(connect_mutex_);
126 pub_points2_ = nh.
advertise<PointCloud2>(
"points2", 1, connect_cb, connect_cb);
132 boost::lock_guard<boost::mutex> lock(connect_mutex_);
133 if (pub_points2_.getNumSubscribers() == 0)
135 sub_l_image_ .unsubscribe();
136 sub_l_info_ .unsubscribe();
137 sub_r_info_ .unsubscribe();
138 sub_disparity_.unsubscribe();
140 else if (!sub_l_image_.getSubscriber())
145 sub_l_image_ .subscribe(*it_,
"left/image_rect_color", 1, hints);
146 sub_l_info_ .subscribe(nh,
"left/camera_info", 1);
147 sub_r_info_ .subscribe(nh,
"right/camera_info", 1);
148 sub_disparity_.subscribe(nh,
"disparity", 1);
160 const CameraInfoConstPtr& l_info_msg,
161 const CameraInfoConstPtr& r_info_msg,
162 const DisparityImageConstPtr& disp_msg)
165 model_.fromCameraInfo(l_info_msg, r_info_msg);
168 const Image& dimage = disp_msg->image;
169 const cv::Mat_<float> dmat(dimage.height, dimage.width, (
float*)&dimage.data[0], dimage.step);
170 model_.projectDisparityImageTo3d(dmat, points_mat_,
true);
171 cv::Mat_<cv::Vec3f> mat = points_mat_;
174 PointCloud2Ptr points_msg = boost::make_shared<PointCloud2>();
175 points_msg->header = disp_msg->header;
176 points_msg->height = mat.rows;
177 points_msg->width = mat.cols;
178 points_msg->is_bigendian =
false;
179 points_msg->is_dense =
false;
191 float bad_point = std::numeric_limits<float>::quiet_NaN ();
192 for (
int v = 0; v < mat.rows; ++v)
194 for (
int u = 0; u < mat.cols; ++u, ++iter_x, ++iter_y, ++iter_z)
199 *iter_x = mat(v, u)[0];
200 *iter_y = mat(v, u)[1];
201 *iter_z = mat(v, u)[2];
205 *iter_x = *iter_y = *iter_z = bad_point;
212 const std::string& encoding = l_image_msg->encoding;
213 if (encoding == enc::MONO8)
215 const cv::Mat_<uint8_t> color(l_image_msg->height, l_image_msg->width,
216 (uint8_t*)&l_image_msg->data[0],
218 for (
int v = 0; v < mat.rows; ++v)
220 for (
int u = 0; u < mat.cols; ++u, ++iter_r, ++iter_g, ++iter_b)
222 uint8_t g = color(v,u);
223 *iter_r = *iter_g = *iter_b = g;
227 else if (encoding == enc::RGB8)
229 const cv::Mat_<cv::Vec3b> color(l_image_msg->height, l_image_msg->width,
230 (cv::Vec3b*)&l_image_msg->data[0],
232 for (
int v = 0; v < mat.rows; ++v)
234 for (
int u = 0; u < mat.cols; ++u, ++iter_r, ++iter_g, ++iter_b)
236 const cv::Vec3b& rgb = color(v,u);
243 else if (encoding == enc::RGBA8)
245 const cv::Mat_<cv::Vec4b> color(l_image_msg->height, l_image_msg->width,
246 (cv::Vec4b*)&l_image_msg->data[0],
248 for (
int v = 0; v < mat.rows; ++v)
250 for (
int u = 0; u < mat.cols; ++u, ++iter_r, ++iter_g, ++iter_b)
252 const cv::Vec4b& rgba = color(v,u);
259 else if (encoding == enc::BGR8)
261 const cv::Mat_<cv::Vec3b> color(l_image_msg->height, l_image_msg->width,
262 (cv::Vec3b*)&l_image_msg->data[0],
264 for (
int v = 0; v < mat.rows; ++v)
266 for (
int u = 0; u < mat.cols; ++u, ++iter_r, ++iter_g, ++iter_b)
268 const cv::Vec3b& bgr = color(v,u);
275 else if (encoding == enc::BGRA8)
277 const cv::Mat_<cv::Vec4b> color(l_image_msg->height, l_image_msg->width,
278 (cv::Vec4b*)&l_image_msg->data[0],
280 for (
int v = 0; v < mat.rows; ++v)
282 for (
int u = 0; u < mat.cols; ++u, ++iter_r, ++iter_g, ++iter_b)
284 const cv::Vec4b& bgra = color(v,u);
294 "unsupported encoding '%s'", encoding.c_str());
297 pub_points2_.publish(points_msg);
cv::Mat_< cv::Vec3f > points_mat_
message_filters::Synchronizer< ApproximatePolicy > ApproximateSync
boost::shared_ptr< ApproximateSync > approximate_sync_
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
boost::mutex connect_mutex_
message_filters::Subscriber< CameraInfo > sub_r_info_
image_geometry::StereoCameraModel model_
static const double MISSING_Z
boost::shared_ptr< image_transport::ImageTransport > it_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
PLUGINLIB_EXPORT_CLASS(image_proc::CropNonZeroNodelet, nodelet::Nodelet)
#define NODELET_WARN_THROTTLE(rate,...)
void imageCb(const ImageConstPtr &l_image_msg, const CameraInfoConstPtr &l_info_msg, const CameraInfoConstPtr &r_info_msg, const DisparityImageConstPtr &disp_msg)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
boost::shared_ptr< ExactSync > exact_sync_
image_transport::SubscriberFilter sub_l_image_
message_filters::Synchronizer< ExactPolicy > ExactSync
bool isValidPoint(const cv::Vec3f &pt)
ApproximateTime< Image, CameraInfo, CameraInfo, DisparityImage > ApproximatePolicy
message_filters::Subscriber< DisparityImage > sub_disparity_
ros::Publisher pub_points2_
void setPointCloud2FieldsByString(int n_fields,...)
ExactTime< Image, CameraInfo, CameraInfo, DisparityImage > ExactPolicy