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/PointCloud.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 PointCloudNodelet : 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_points_;
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 PointCloudNodelet::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(&PointCloudNodelet::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(&PointCloudNodelet::imageCb,
00080 this, _1, _2, _3, _4));
00081 }
00082
00083
00084 ros::SubscriberStatusCallback connect_cb = boost::bind(&PointCloudNodelet::connectCb, this);
00085
00086 boost::lock_guard<boost::mutex> lock(connect_mutex_);
00087 pub_points_ = nh.advertise<PointCloud>("points", 1, connect_cb, connect_cb);
00088 }
00089
00090
00091 void PointCloudNodelet::connectCb()
00092 {
00093 boost::lock_guard<boost::mutex> lock(connect_mutex_);
00094 if (pub_points_.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 image_transport::TransportHints hints("raw", ros::TransportHints(), getPrivateNodeHandle());
00106 sub_l_image_ .subscribe(*it_, "left/image_rect_color", 1, hints);
00107 sub_l_info_ .subscribe(nh, "left/camera_info", 1);
00108 sub_r_info_ .subscribe(nh, "right/camera_info", 1);
00109 sub_disparity_.subscribe(nh, "disparity", 1);
00110 }
00111 }
00112
00113 inline bool isValidPoint(const cv::Vec3f& pt)
00114 {
00115
00116
00117 return pt[2] != image_geometry::StereoCameraModel::MISSING_Z && !std::isinf(pt[2]);
00118 }
00119
00120 void PointCloudNodelet::imageCb(const ImageConstPtr& l_image_msg,
00121 const CameraInfoConstPtr& l_info_msg,
00122 const CameraInfoConstPtr& r_info_msg,
00123 const DisparityImageConstPtr& disp_msg)
00124 {
00125
00126 model_.fromCameraInfo(l_info_msg, r_info_msg);
00127
00128
00129 const Image& dimage = disp_msg->image;
00130 const cv::Mat_<float> dmat(dimage.height, dimage.width, (float*)&dimage.data[0], dimage.step);
00131 model_.projectDisparityImageTo3d(dmat, points_mat_, true);
00132 cv::Mat_<cv::Vec3f> mat = points_mat_;
00133
00134
00135 PointCloudPtr points_msg = boost::make_shared<PointCloud>();
00136 points_msg->header = disp_msg->header;
00137
00138 points_msg->channels.resize(3);
00139 points_msg->channels[0].name = "rgb";
00140 points_msg->channels[0].values.resize(0);
00141 points_msg->channels[1].name = "u";
00142 points_msg->channels[1].values.resize(0);
00143 points_msg->channels[2].name = "v";
00144 points_msg->channels[2].values.resize(0);
00145
00146
00147
00148 for (int32_t u = 0; u < mat.rows; ++u) {
00149 for (int32_t v = 0; v < mat.cols; ++v) {
00150 if (isValidPoint(mat(u,v))) {
00151
00152 geometry_msgs::Point32 pt;
00153 pt.x = mat(u,v)[0];
00154 pt.y = mat(u,v)[1];
00155 pt.z = mat(u,v)[2];
00156 points_msg->points.push_back(pt);
00157
00158 points_msg->channels[1].values.push_back(u);
00159 points_msg->channels[2].values.push_back(v);
00160 }
00161 }
00162 }
00163
00164
00165 namespace enc = sensor_msgs::image_encodings;
00166 const std::string& encoding = l_image_msg->encoding;
00167 points_msg->channels[0].values.reserve(points_msg->points.size());
00168 if (encoding == enc::MONO8) {
00169 const cv::Mat_<uint8_t> color(l_image_msg->height, l_image_msg->width,
00170 (uint8_t*)&l_image_msg->data[0],
00171 l_image_msg->step);
00172 for (int32_t u = 0; u < mat.rows; ++u) {
00173 for (int32_t v = 0; v < mat.cols; ++v) {
00174 if (isValidPoint(mat(u,v))) {
00175 uint8_t g = color(u,v);
00176 int32_t rgb = (g << 16) | (g << 8) | g;
00177 points_msg->channels[0].values.push_back(*(float*)(&rgb));
00178 }
00179 }
00180 }
00181 }
00182 else if (encoding == enc::RGB8) {
00183 const cv::Mat_<cv::Vec3b> color(l_image_msg->height, l_image_msg->width,
00184 (cv::Vec3b*)&l_image_msg->data[0],
00185 l_image_msg->step);
00186 for (int32_t u = 0; u < mat.rows; ++u) {
00187 for (int32_t v = 0; v < mat.cols; ++v) {
00188 if (isValidPoint(mat(u,v))) {
00189 const cv::Vec3b& rgb = color(u,v);
00190 int32_t rgb_packed = (rgb[0] << 16) | (rgb[1] << 8) | rgb[2];
00191 points_msg->channels[0].values.push_back(*(float*)(&rgb_packed));
00192 }
00193 }
00194 }
00195 }
00196 else if (encoding == enc::BGR8) {
00197 const cv::Mat_<cv::Vec3b> color(l_image_msg->height, l_image_msg->width,
00198 (cv::Vec3b*)&l_image_msg->data[0],
00199 l_image_msg->step);
00200 for (int32_t u = 0; u < mat.rows; ++u) {
00201 for (int32_t v = 0; v < mat.cols; ++v) {
00202 if (isValidPoint(mat(u,v))) {
00203 const cv::Vec3b& bgr = color(u,v);
00204 int32_t rgb_packed = (bgr[2] << 16) | (bgr[1] << 8) | bgr[0];
00205 points_msg->channels[0].values.push_back(*(float*)(&rgb_packed));
00206 }
00207 }
00208 }
00209 }
00210 else {
00211 NODELET_WARN_THROTTLE(30, "Could not fill color channel of the point cloud, "
00212 "unsupported encoding '%s'", encoding.c_str());
00213 }
00214
00215 pub_points_.publish(points_msg);
00216 }
00217
00218 }
00219
00220
00221 #include <pluginlib/class_list_macros.h>
00222 PLUGINLIB_DECLARE_CLASS(stereo_image_proc, point_cloud,
00223 stereo_image_proc::PointCloudNodelet, nodelet::Nodelet)