Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034 #include <ros/ros.h>
00035 #include <nodelet/nodelet.h>
00036 #include <image_transport/image_transport.h>
00037 #include <pcl_ros/point_cloud.h>
00038 #include <pcl/point_types.h>
00039 #include <sensor_msgs/image_encodings.h>
00040 #include <image_geometry/pinhole_camera_model.h>
00041 #include <boost/thread.hpp>
00042 #include <depth_image_proc/depth_conversions.h>
00043
00044 #include <pcl_conversions/pcl_conversions.h>
00045
00046 namespace depth_image_proc {
00047
00048 namespace enc = sensor_msgs::image_encodings;
00049
00050 class PointCloudXyzNodelet : public nodelet::Nodelet
00051 {
00052
00053 boost::shared_ptr<image_transport::ImageTransport> it_;
00054 image_transport::CameraSubscriber sub_depth_;
00055 int queue_size_;
00056
00057
00058 boost::mutex connect_mutex_;
00059 typedef pcl::PointCloud<pcl::PointXYZ> PointCloud;
00060 ros::Publisher pub_point_cloud_;
00061
00062 image_geometry::PinholeCameraModel model_;
00063
00064 virtual void onInit();
00065
00066 void connectCb();
00067
00068 void depthCb(const sensor_msgs::ImageConstPtr& depth_msg,
00069 const sensor_msgs::CameraInfoConstPtr& info_msg);
00070 };
00071
00072 void PointCloudXyzNodelet::onInit()
00073 {
00074 ros::NodeHandle& nh = getNodeHandle();
00075 ros::NodeHandle& private_nh = getPrivateNodeHandle();
00076 it_.reset(new image_transport::ImageTransport(nh));
00077
00078
00079 private_nh.param("queue_size", queue_size_, 5);
00080
00081
00082 ros::SubscriberStatusCallback connect_cb = boost::bind(&PointCloudXyzNodelet::connectCb, this);
00083
00084 boost::lock_guard<boost::mutex> lock(connect_mutex_);
00085 pub_point_cloud_ = nh.advertise<PointCloud>("points", 1, connect_cb, connect_cb);
00086 }
00087
00088
00089 void PointCloudXyzNodelet::connectCb()
00090 {
00091 boost::lock_guard<boost::mutex> lock(connect_mutex_);
00092 if (pub_point_cloud_.getNumSubscribers() == 0)
00093 {
00094 sub_depth_.shutdown();
00095 }
00096 else if (!sub_depth_)
00097 {
00098 image_transport::TransportHints hints("raw", ros::TransportHints(), getPrivateNodeHandle());
00099 sub_depth_ = it_->subscribeCamera("image_rect", queue_size_, &PointCloudXyzNodelet::depthCb, this, hints);
00100 }
00101 }
00102
00103 void PointCloudXyzNodelet::depthCb(const sensor_msgs::ImageConstPtr& depth_msg,
00104 const sensor_msgs::CameraInfoConstPtr& info_msg)
00105 {
00106 PointCloud::Ptr cloud_msg(new PointCloud);
00107 cloud_msg->header = pcl_conversions::toPCL(depth_msg->header);
00108 cloud_msg->height = depth_msg->height;
00109 cloud_msg->width = depth_msg->width;
00110 cloud_msg->is_dense = false;
00111 cloud_msg->points.resize(cloud_msg->height * cloud_msg->width);
00112
00113
00114 model_.fromCameraInfo(info_msg);
00115
00116 if (depth_msg->encoding == enc::TYPE_16UC1)
00117 {
00118 convert<uint16_t>(depth_msg, cloud_msg, model_);
00119 }
00120 else if (depth_msg->encoding == enc::TYPE_32FC1)
00121 {
00122 convert<float>(depth_msg, cloud_msg, model_);
00123 }
00124 else
00125 {
00126 NODELET_ERROR_THROTTLE(5, "Depth image has unsupported encoding [%s]", depth_msg->encoding.c_str());
00127 return;
00128 }
00129
00130 pub_point_cloud_.publish (cloud_msg);
00131 }
00132
00133 }
00134
00135
00136 #include <pluginlib/class_list_macros.h>
00137 PLUGINLIB_EXPORT_CLASS(depth_image_proc::PointCloudXyzNodelet,nodelet::Nodelet);