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> 
   57 using namespace stereo_msgs;
 
   76   boost::mutex connect_mutex_;
 
   81   cv::Mat_<cv::Vec3f> points_mat_; 
 
   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, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
 
  116                                      sub_l_image_, sub_l_info_,
 
  117                                      sub_r_info_, sub_disparity_) );
 
  119                                               this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_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);