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