00001 #include <ros/ros.h>
00002 #include <nodelet/nodelet.h>
00003 #include <image_transport/image_transport.h>
00004 #include <pcl_ros/point_cloud.h>
00005 #include <pcl/point_types.h>
00006 #include <pcl/PointIndices.h>
00007 #include <sensor_msgs/image_encodings.h>
00008 #include <image_geometry/pinhole_camera_model.h>
00009
00010 namespace openni_camera {
00011
00012 namespace enc = sensor_msgs::image_encodings;
00013
00015
00016 class PointCloudXyzNodelet : public nodelet::Nodelet
00017 {
00018
00019 boost::shared_ptr<image_transport::ImageTransport> it_;
00020 image_transport::CameraSubscriber sub_depth_;
00021 ros::Subscriber sub_mask_indices_;
00022 bool subscribed_;
00023
00024
00025 typedef pcl::PointCloud<pcl::PointXYZ> PointCloud;
00026 ros::Publisher pub_point_cloud_;
00027
00028 image_geometry::PinholeCameraModel model_;
00029
00030 bool use_indices_;
00031 std::vector<int32_t> mask_indices_;
00032
00033 virtual void onInit();
00034
00035 void connectCb();
00036
00037 void depthCb(const sensor_msgs::ImageConstPtr& depth_msg,
00038 const sensor_msgs::CameraInfoConstPtr& info_msg);
00039
00040 void maskIndicesCb(const pcl::PointIndicesConstPtr& indices);
00041 };
00042
00043 void PointCloudXyzNodelet::onInit()
00044 {
00045 ros::NodeHandle& nh = getNodeHandle();
00046 it_.reset(new image_transport::ImageTransport(nh));
00047
00048
00049 subscribed_ = false;
00050 ros::SubscriberStatusCallback connect_cb = boost::bind(&PointCloudXyzNodelet::connectCb, this);
00051 pub_point_cloud_ = nh.advertise<PointCloud>("points", 1, connect_cb, connect_cb);
00052
00053 getPrivateNodeHandle().param("use_indices", use_indices_, false);
00054 if (use_indices_)
00055 sub_mask_indices_ = nh.subscribe("indices", 1, &PointCloudXyzNodelet::maskIndicesCb, this);
00056 }
00057
00058
00059 void PointCloudXyzNodelet::connectCb()
00060 {
00061 if (pub_point_cloud_.getNumSubscribers() == 0)
00062 {
00063 sub_depth_.shutdown();
00064 subscribed_ = false;
00065 }
00066 else if (!subscribed_)
00067 {
00068 image_transport::TransportHints hints("raw", ros::TransportHints(), getPrivateNodeHandle());
00069 sub_depth_ = it_->subscribeCamera("image_rect_raw", 1, &PointCloudXyzNodelet::depthCb, this, hints);
00070 subscribed_ = true;
00071 }
00072 }
00073
00074 void PointCloudXyzNodelet::depthCb(const sensor_msgs::ImageConstPtr& depth_msg,
00075 const sensor_msgs::CameraInfoConstPtr& info_msg)
00076 {
00078 if (depth_msg->encoding != enc::TYPE_16UC1)
00079 {
00080 NODELET_ERROR("Expected data of type [%s], got [%s]", enc::TYPE_16UC1.c_str(),
00081 depth_msg->encoding.c_str());
00082 return;
00083 }
00084
00085 PointCloud::Ptr cloud_msg (new PointCloud);
00086 cloud_msg->header = depth_msg->header;
00087
00088
00089 model_.fromCameraInfo(info_msg);
00090 float center_x = model_.cx();
00091 float center_y = model_.cy();
00092
00093 bool do_masking = (use_indices_ and (mask_indices_.size() != 0));
00094 if (not do_masking)
00095 {
00096 cloud_msg->height = depth_msg->height;
00097 cloud_msg->width = depth_msg->width;
00098 }
00099 else
00100 {
00101 cloud_msg->height = 1;
00102 cloud_msg->width = mask_indices_.size();
00103 }
00104 cloud_msg->is_dense = false;
00105 cloud_msg->points.resize (cloud_msg->height * cloud_msg->width);
00106
00107
00108 float constant_x = 0.001 / model_.fx();
00109 float constant_y = 0.001 / model_.fy();
00110 float bad_point = std::numeric_limits<float>::quiet_NaN ();
00111
00112 int depth_idx = 0;
00113 pcl::PointCloud<pcl::PointXYZ>::iterator pt_iter = cloud_msg->begin ();
00114 const uint16_t* depth_data = reinterpret_cast<const uint16_t*>(&depth_msg->data[0]);
00115
00116 if (not do_masking)
00117 {
00118 for (int v = 0; v < (int)cloud_msg->height; ++v)
00119 {
00120 for (int u = 0; u < (int)cloud_msg->width; ++u, ++depth_idx, ++pt_iter)
00121 {
00122 pcl::PointXYZ& pt = *pt_iter;
00123
00124
00126 if (depth_data[depth_idx] == 0)
00127 {
00128
00129 pt.x = pt.y = pt.z = bad_point;
00130 continue;
00131 }
00132
00133
00134 pt.x = (u - center_x) * depth_data[depth_idx] * constant_x;
00135 pt.y = (v - center_y) * depth_data[depth_idx] * constant_y;
00136 pt.z = depth_data[depth_idx] * 0.001;
00137 }
00138 }
00139 }
00140 else
00141 {
00142 int u, v;
00143 unsigned int nMask = mask_indices_.size();
00144 int max_index = (depth_msg->height * depth_msg->width) - 1;
00145 for (unsigned int i = 0; i < nMask; i++, ++pt_iter)
00146 {
00147 pcl::PointXYZ& pt = *pt_iter;
00148
00149 depth_idx = mask_indices_[i];
00150 if (depth_idx > max_index)
00151 {
00152 NODELET_ERROR("Mask index %d exceeds maximum index of %d", depth_idx, max_index);
00153 continue;
00154 }
00155 v = depth_idx / depth_msg->width;
00156 u = depth_idx % depth_msg->width;
00157
00158
00160 if (depth_data[depth_idx] == 0)
00161 {
00162
00163 pt.x = pt.y = pt.z = bad_point;
00164 continue;
00165 }
00166
00167
00168 pt.x = (u - center_x) * depth_data[depth_idx] * constant_x;
00169 pt.y = (v - center_y) * depth_data[depth_idx] * constant_y;
00170 pt.z = depth_data[depth_idx] * 0.001;
00171 }
00172 }
00173
00174 pub_point_cloud_.publish (cloud_msg);
00175 }
00176
00177 void PointCloudXyzNodelet::maskIndicesCb(const pcl::PointIndicesConstPtr& indices)
00178 {
00179 mask_indices_.resize(indices->indices.size());
00180
00181 memcpy(mask_indices_.data(), indices->indices.data(), indices->indices.size() * sizeof(int32_t));
00182 }
00183
00184 }
00185
00186
00187 #include <pluginlib/class_list_macros.h>
00188 PLUGINLIB_DECLARE_CLASS (openni_camera, point_cloud_xyz, openni_camera::PointCloudXyzNodelet, nodelet::Nodelet);