00001 #include <ros/ros.h>
00002 #include <nodelet/nodelet.h>
00003 #include <image_transport/image_transport.h>
00004 #include <image_transport/subscriber_filter.h>
00005 #include <message_filters/subscriber.h>
00006 #include <message_filters/synchronizer.h>
00007 #include <message_filters/sync_policies/exact_time.h>
00008 #include <message_filters/sync_policies/approximate_time.h>
00009 #include <image_geometry/stereo_camera_model.h>
00010
00011 #include <stereo_msgs/DisparityImage.h>
00012 #include <sensor_msgs/PointCloud2.h>
00013 #include <sensor_msgs/image_encodings.h>
00014
00015 namespace stereo_image_proc {
00016
00017 using namespace sensor_msgs;
00018 using namespace stereo_msgs;
00019 using namespace message_filters::sync_policies;
00020
00021 class PointCloud2Nodelet : public nodelet::Nodelet
00022 {
00023 boost::shared_ptr<image_transport::ImageTransport> it_;
00024
00025
00026 image_transport::SubscriberFilter sub_l_image_;
00027 message_filters::Subscriber<CameraInfo> sub_l_info_, sub_r_info_;
00028 message_filters::Subscriber<DisparityImage> sub_disparity_;
00029 typedef ExactTime<Image, CameraInfo, CameraInfo, DisparityImage> ExactPolicy;
00030 typedef ApproximateTime<Image, CameraInfo, CameraInfo, DisparityImage> ApproximatePolicy;
00031 typedef message_filters::Synchronizer<ExactPolicy> ExactSync;
00032 typedef message_filters::Synchronizer<ApproximatePolicy> ApproximateSync;
00033 boost::shared_ptr<ExactSync> exact_sync_;
00034 boost::shared_ptr<ApproximateSync> approximate_sync_;
00035
00036
00037 boost::mutex connect_mutex_;
00038 ros::Publisher pub_points2_;
00039
00040
00041 image_geometry::StereoCameraModel model_;
00042 cv::Mat_<cv::Vec3f> points_mat_;
00043
00044 virtual void onInit();
00045
00046 void connectCb();
00047
00048 void imageCb(const ImageConstPtr& l_image_msg,
00049 const CameraInfoConstPtr& l_info_msg,
00050 const CameraInfoConstPtr& r_info_msg,
00051 const DisparityImageConstPtr& disp_msg);
00052 };
00053
00054 void PointCloud2Nodelet::onInit()
00055 {
00056 ros::NodeHandle &nh = getNodeHandle();
00057 ros::NodeHandle &private_nh = getPrivateNodeHandle();
00058 it_.reset(new image_transport::ImageTransport(nh));
00059
00060
00061
00062 int queue_size;
00063 private_nh.param("queue_size", queue_size, 5);
00064 bool approx;
00065 private_nh.param("approximate_sync", approx, false);
00066 if (approx)
00067 {
00068 approximate_sync_.reset( new ApproximateSync(ApproximatePolicy(queue_size),
00069 sub_l_image_, sub_l_info_,
00070 sub_r_info_, sub_disparity_) );
00071 approximate_sync_->registerCallback(boost::bind(&PointCloud2Nodelet::imageCb,
00072 this, _1, _2, _3, _4));
00073 }
00074 else
00075 {
00076 exact_sync_.reset( new ExactSync(ExactPolicy(queue_size),
00077 sub_l_image_, sub_l_info_,
00078 sub_r_info_, sub_disparity_) );
00079 exact_sync_->registerCallback(boost::bind(&PointCloud2Nodelet::imageCb,
00080 this, _1, _2, _3, _4));
00081 }
00082
00083
00084 ros::SubscriberStatusCallback connect_cb = boost::bind(&PointCloud2Nodelet::connectCb, this);
00085
00086 boost::lock_guard<boost::mutex> lock(connect_mutex_);
00087 pub_points2_ = nh.advertise<PointCloud2>("points2", 1, connect_cb, connect_cb);
00088 }
00089
00090
00091 void PointCloud2Nodelet::connectCb()
00092 {
00093 boost::lock_guard<boost::mutex> lock(connect_mutex_);
00094 if (pub_points2_.getNumSubscribers() == 0)
00095 {
00096 sub_l_image_ .unsubscribe();
00097 sub_l_info_ .unsubscribe();
00098 sub_r_info_ .unsubscribe();
00099 sub_disparity_.unsubscribe();
00100 }
00101 else if (!sub_l_image_.getSubscriber())
00102 {
00103 ros::NodeHandle &nh = getNodeHandle();
00104
00105 sub_l_image_ .subscribe(*it_, "left/image_rect_color", 1);
00106 sub_l_info_ .subscribe(nh, "left/camera_info", 1);
00107 sub_r_info_ .subscribe(nh, "right/camera_info", 1);
00108 sub_disparity_.subscribe(nh, "disparity", 1);
00109 }
00110 }
00111
00112 inline bool isValidPoint(const cv::Vec3f& pt)
00113 {
00114
00115
00116 return pt[2] != image_geometry::StereoCameraModel::MISSING_Z && !std::isinf(pt[2]);
00117 }
00118
00119 void PointCloud2Nodelet::imageCb(const ImageConstPtr& l_image_msg,
00120 const CameraInfoConstPtr& l_info_msg,
00121 const CameraInfoConstPtr& r_info_msg,
00122 const DisparityImageConstPtr& disp_msg)
00123 {
00124
00125 model_.fromCameraInfo(l_info_msg, r_info_msg);
00126
00127
00128 const Image& dimage = disp_msg->image;
00129 const cv::Mat_<float> dmat(dimage.height, dimage.width, (float*)&dimage.data[0], dimage.step);
00130 model_.projectDisparityImageTo3d(dmat, points_mat_, true);
00131 cv::Mat_<cv::Vec3f> mat = points_mat_;
00132
00133
00134 PointCloud2Ptr points_msg = boost::make_shared<PointCloud2>();
00135 points_msg->header = disp_msg->header;
00136 points_msg->height = mat.rows;
00137 points_msg->width = mat.cols;
00138 points_msg->fields.resize (4);
00139 points_msg->fields[0].name = "x";
00140 points_msg->fields[0].offset = 0;
00141 points_msg->fields[0].count = 1;
00142 points_msg->fields[0].datatype = PointField::FLOAT32;
00143 points_msg->fields[1].name = "y";
00144 points_msg->fields[1].offset = 4;
00145 points_msg->fields[1].count = 1;
00146 points_msg->fields[1].datatype = PointField::FLOAT32;
00147 points_msg->fields[2].name = "z";
00148 points_msg->fields[2].offset = 8;
00149 points_msg->fields[2].count = 1;
00150 points_msg->fields[2].datatype = PointField::FLOAT32;
00151 points_msg->fields[3].name = "rgb";
00152 points_msg->fields[3].offset = 12;
00153 points_msg->fields[3].count = 1;
00154 points_msg->fields[3].datatype = PointField::FLOAT32;
00155
00156 static const int STEP = 16;
00157 points_msg->point_step = STEP;
00158 points_msg->row_step = points_msg->point_step * points_msg->width;
00159 points_msg->data.resize (points_msg->row_step * points_msg->height);
00160 points_msg->is_dense = false;
00161
00162 float bad_point = std::numeric_limits<float>::quiet_NaN ();
00163 int offset = 0;
00164 for (int v = 0; v < mat.rows; ++v)
00165 {
00166 for (int u = 0; u < mat.cols; ++u, offset += STEP)
00167 {
00168 if (isValidPoint(mat(v,u)))
00169 {
00170
00171 memcpy (&points_msg->data[offset + 0], &mat(v,u)[0], sizeof (float));
00172 memcpy (&points_msg->data[offset + 4], &mat(v,u)[1], sizeof (float));
00173 memcpy (&points_msg->data[offset + 8], &mat(v,u)[2], sizeof (float));
00174 }
00175 else
00176 {
00177 memcpy (&points_msg->data[offset + 0], &bad_point, sizeof (float));
00178 memcpy (&points_msg->data[offset + 4], &bad_point, sizeof (float));
00179 memcpy (&points_msg->data[offset + 8], &bad_point, sizeof (float));
00180 }
00181 }
00182 }
00183
00184
00185 namespace enc = sensor_msgs::image_encodings;
00186 const std::string& encoding = l_image_msg->encoding;
00187 offset = 0;
00188 if (encoding == enc::MONO8)
00189 {
00190 const cv::Mat_<uint8_t> color(l_image_msg->height, l_image_msg->width,
00191 (uint8_t*)&l_image_msg->data[0],
00192 l_image_msg->step);
00193 for (int v = 0; v < mat.rows; ++v)
00194 {
00195 for (int u = 0; u < mat.cols; ++u, offset += STEP)
00196 {
00197 if (isValidPoint(mat(v,u)))
00198 {
00199 uint8_t g = color(v,u);
00200 int32_t rgb = (g << 16) | (g << 8) | g;
00201 memcpy (&points_msg->data[offset + 12], &rgb, sizeof (int32_t));
00202 }
00203 else
00204 {
00205 memcpy (&points_msg->data[offset + 12], &bad_point, sizeof (float));
00206 }
00207 }
00208 }
00209 }
00210 else if (encoding == enc::RGB8)
00211 {
00212 const cv::Mat_<cv::Vec3b> color(l_image_msg->height, l_image_msg->width,
00213 (cv::Vec3b*)&l_image_msg->data[0],
00214 l_image_msg->step);
00215 for (int v = 0; v < mat.rows; ++v)
00216 {
00217 for (int u = 0; u < mat.cols; ++u, offset += STEP)
00218 {
00219 if (isValidPoint(mat(v,u)))
00220 {
00221 const cv::Vec3b& rgb = color(v,u);
00222 int32_t rgb_packed = (rgb[0] << 16) | (rgb[1] << 8) | rgb[2];
00223 memcpy (&points_msg->data[offset + 12], &rgb_packed, sizeof (int32_t));
00224 }
00225 else
00226 {
00227 memcpy (&points_msg->data[offset + 12], &bad_point, sizeof (float));
00228 }
00229 }
00230 }
00231 }
00232 else if (encoding == enc::BGR8)
00233 {
00234 const cv::Mat_<cv::Vec3b> color(l_image_msg->height, l_image_msg->width,
00235 (cv::Vec3b*)&l_image_msg->data[0],
00236 l_image_msg->step);
00237 for (int v = 0; v < mat.rows; ++v)
00238 {
00239 for (int u = 0; u < mat.cols; ++u, offset += STEP)
00240 {
00241 if (isValidPoint(mat(v,u)))
00242 {
00243 const cv::Vec3b& bgr = color(v,u);
00244 int32_t rgb_packed = (bgr[2] << 16) | (bgr[1] << 8) | bgr[0];
00245 memcpy (&points_msg->data[offset + 12], &rgb_packed, sizeof (int32_t));
00246 }
00247 else
00248 {
00249 memcpy (&points_msg->data[offset + 12], &bad_point, sizeof (float));
00250 }
00251 }
00252 }
00253 }
00254 else
00255 {
00256 NODELET_WARN_THROTTLE(30, "Could not fill color channel of the point cloud, "
00257 "unsupported encoding '%s'", encoding.c_str());
00258 }
00259
00260 pub_points2_.publish(points_msg);
00261 }
00262
00263 }
00264
00265
00266 #include <pluginlib/class_list_macros.h>
00267 PLUGINLIB_DECLARE_CLASS(stereo_image_proc, point_cloud2,
00268 stereo_image_proc::PointCloud2Nodelet, nodelet::Nodelet)