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 <sensor_msgs/image_encodings.h>
00038 #include <image_geometry/pinhole_camera_model.h>
00039 #include <boost/thread.hpp>
00040 #include <depth_image_proc/depth_conversions.h>
00041
00042 #include <sensor_msgs/point_cloud2_iterator.h>
00043
00044 namespace depth_image_proc {
00045
00046 namespace enc = sensor_msgs::image_encodings;
00047
00048 class PointCloudXyzNodelet : public nodelet::Nodelet
00049 {
00050
00051 boost::shared_ptr<image_transport::ImageTransport> it_;
00052 image_transport::CameraSubscriber sub_depth_;
00053 int queue_size_;
00054
00055
00056 boost::mutex connect_mutex_;
00057 typedef sensor_msgs::PointCloud2 PointCloud;
00058 ros::Publisher pub_point_cloud_;
00059
00060 image_geometry::PinholeCameraModel model_;
00061
00062 virtual void onInit();
00063
00064 void connectCb();
00065
00066 void depthCb(const sensor_msgs::ImageConstPtr& depth_msg,
00067 const sensor_msgs::CameraInfoConstPtr& info_msg);
00068 };
00069
00070 void PointCloudXyzNodelet::onInit()
00071 {
00072 ros::NodeHandle& nh = getNodeHandle();
00073 ros::NodeHandle& private_nh = getPrivateNodeHandle();
00074 it_.reset(new image_transport::ImageTransport(nh));
00075
00076
00077 private_nh.param("queue_size", queue_size_, 5);
00078
00079
00080 ros::SubscriberStatusCallback connect_cb = boost::bind(&PointCloudXyzNodelet::connectCb, this);
00081
00082 boost::lock_guard<boost::mutex> lock(connect_mutex_);
00083 pub_point_cloud_ = nh.advertise<PointCloud>("points", 1, connect_cb, connect_cb);
00084 }
00085
00086
00087 void PointCloudXyzNodelet::connectCb()
00088 {
00089 boost::lock_guard<boost::mutex> lock(connect_mutex_);
00090 if (pub_point_cloud_.getNumSubscribers() == 0)
00091 {
00092 sub_depth_.shutdown();
00093 }
00094 else if (!sub_depth_)
00095 {
00096 image_transport::TransportHints hints("raw", ros::TransportHints(), getPrivateNodeHandle());
00097 sub_depth_ = it_->subscribeCamera("image_rect", queue_size_, &PointCloudXyzNodelet::depthCb, this, hints);
00098 }
00099 }
00100
00101 void PointCloudXyzNodelet::depthCb(const sensor_msgs::ImageConstPtr& depth_msg,
00102 const sensor_msgs::CameraInfoConstPtr& info_msg)
00103 {
00104 PointCloud::Ptr cloud_msg(new PointCloud);
00105 cloud_msg->header = depth_msg->header;
00106 cloud_msg->height = depth_msg->height;
00107 cloud_msg->width = depth_msg->width;
00108 cloud_msg->is_dense = false;
00109 cloud_msg->is_bigendian = false;
00110
00111 sensor_msgs::PointCloud2Modifier pcd_modifier(*cloud_msg);
00112 pcd_modifier.setPointCloud2FieldsByString(1, "xyz");
00113
00114
00115 model_.fromCameraInfo(info_msg);
00116
00117 if (depth_msg->encoding == enc::TYPE_16UC1)
00118 {
00119 convert<uint16_t>(depth_msg, cloud_msg, model_);
00120 }
00121 else if (depth_msg->encoding == enc::TYPE_32FC1)
00122 {
00123 convert<float>(depth_msg, cloud_msg, model_);
00124 }
00125 else
00126 {
00127 NODELET_ERROR_THROTTLE(5, "Depth image has unsupported encoding [%s]", depth_msg->encoding.c_str());
00128 return;
00129 }
00130
00131 pub_point_cloud_.publish (cloud_msg);
00132 }
00133
00134 }
00135
00136
00137 #include <pluginlib/class_list_macros.h>
00138 PLUGINLIB_EXPORT_CLASS(depth_image_proc::PointCloudXyzNodelet,nodelet::Nodelet);