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/approximate_time.h>
00008 #include <pcl_ros/point_cloud.h>
00009 #include <pcl/point_types.h>
00010 #include <pcl/PointIndices.h>
00011 #include <sensor_msgs/image_encodings.h>
00012 #include <image_geometry/pinhole_camera_model.h>
00013
00014 namespace openni_camera {
00015
00016 using namespace message_filters::sync_policies;
00017 namespace enc = sensor_msgs::image_encodings;
00018
00020
00021 typedef union
00022 {
00023 struct
00024 {
00025 unsigned char Blue;
00026 unsigned char Green;
00027 unsigned char Red;
00028 unsigned char Alpha;
00029 };
00030 float float_value;
00031 long long_value;
00032 } RGBValue;
00033
00034 class PointCloudXyzrgbNodelet : public nodelet::Nodelet
00035 {
00036 ros::NodeHandlePtr rgb_nh_;
00037 boost::shared_ptr<image_transport::ImageTransport> rgb_it_, depth_it_;
00038
00039
00040 image_transport::SubscriberFilter sub_depth_, sub_rgb_;
00041 message_filters::Subscriber<sensor_msgs::CameraInfo> sub_info_;
00042 typedef ApproximateTime<sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo> SyncPolicy;
00043 typedef message_filters::Synchronizer<SyncPolicy> Synchronizer;
00044 boost::shared_ptr<Synchronizer> sync_;
00045 ros::Subscriber sub_mask_indices_;
00046 bool subscribed_;
00047
00048
00049 typedef pcl::PointCloud<pcl::PointXYZRGB> PointCloud;
00050 ros::Publisher pub_point_cloud_;
00051
00052 image_geometry::PinholeCameraModel model_;
00053
00054 bool use_indices_;
00055 std::vector<int32_t> mask_indices_;
00056
00057 virtual void onInit();
00058
00059 void connectCb();
00060
00061 void imageCb(const sensor_msgs::ImageConstPtr& depth_msg,
00062 const sensor_msgs::ImageConstPtr& rgb_msg,
00063 const sensor_msgs::CameraInfoConstPtr& info_msg);
00064
00065 void maskIndicesCb(const pcl::PointIndicesConstPtr& indices);
00066 };
00067
00068 void PointCloudXyzrgbNodelet::onInit()
00069 {
00070 ros::NodeHandle& nh = getNodeHandle();
00071 rgb_nh_.reset( new ros::NodeHandle(nh, "rgb") );
00072 ros::NodeHandle depth_nh(nh, "depth_registered");
00073 rgb_it_ .reset( new image_transport::ImageTransport(*rgb_nh_) );
00074 depth_it_.reset( new image_transport::ImageTransport(depth_nh) );
00075
00076
00077 subscribed_ = false;
00078 ros::SubscriberStatusCallback connect_cb = boost::bind(&PointCloudXyzrgbNodelet::connectCb, this);
00079 pub_point_cloud_ = depth_nh.advertise<PointCloud>("points", 1, connect_cb, connect_cb);
00080
00081
00083 int queue_size = 5;
00084 sync_.reset( new Synchronizer(SyncPolicy(queue_size), sub_depth_, sub_rgb_, sub_info_) );
00085 sync_->registerCallback(boost::bind(&PointCloudXyzrgbNodelet::imageCb, this, _1, _2, _3));
00086
00087
00088 getPrivateNodeHandle().param("use_indices", use_indices_, false);
00089 if (use_indices_)
00090 sub_mask_indices_ = depth_nh.subscribe("indices", 1, &PointCloudXyzrgbNodelet::maskIndicesCb, this);
00091 }
00092
00093
00094 void PointCloudXyzrgbNodelet::connectCb()
00095 {
00096
00097 if (pub_point_cloud_.getNumSubscribers() == 0)
00098 {
00099
00100 sub_depth_.unsubscribe();
00101 sub_rgb_ .unsubscribe();
00102 sub_info_ .unsubscribe();
00103 subscribed_ = false;
00104 }
00105 else if (!subscribed_)
00106 {
00107
00108 sub_depth_.subscribe(*depth_it_, "image_rect_raw", 1);
00109 sub_rgb_ .subscribe(*rgb_it_, "image_rect_color", 1);
00110 sub_info_ .subscribe(*rgb_nh_, "camera_info", 1);
00111 subscribed_ = true;
00112
00113 }
00114 }
00115
00116 void PointCloudXyzrgbNodelet::imageCb(const sensor_msgs::ImageConstPtr& depth_msg,
00117 const sensor_msgs::ImageConstPtr& rgb_msg,
00118 const sensor_msgs::CameraInfoConstPtr& info_msg)
00119 {
00120
00121 if (depth_msg->encoding != enc::TYPE_16UC1)
00122 {
00123 NODELET_ERROR_THROTTLE(5, "Expected depth data of type [%s], got [%s]",
00124 enc::TYPE_16UC1.c_str(), depth_msg->encoding.c_str());
00125 return;
00126 }
00127
00128 if (depth_msg->header.frame_id != rgb_msg->header.frame_id)
00129 {
00130 NODELET_ERROR_THROTTLE(5, "Depth image frame id [%s] doesn't match RGB image frame id [%s]",
00131 depth_msg->header.frame_id.c_str(), rgb_msg->header.frame_id.c_str());
00132 return;
00133 }
00134
00135 if (depth_msg->width != rgb_msg->width || depth_msg->height != rgb_msg->height)
00136 {
00137 NODELET_ERROR_THROTTLE(5, "Depth resolution (%ux%u) does not match RGB resolution (%ux%u)",
00138 depth_msg->width, depth_msg->height, rgb_msg->width, rgb_msg->height);
00139 return;
00140 }
00141
00142
00143 int red_offset, green_offset, blue_offset, color_step;
00144 if (rgb_msg->encoding == enc::RGB8)
00145 {
00146 red_offset = 0;
00147 green_offset = 1;
00148 blue_offset = 2;
00149 color_step = 3;
00150 }
00151 else if (rgb_msg->encoding == enc::BGR8)
00152 {
00153 red_offset = 2;
00154 green_offset = 1;
00155 blue_offset = 0;
00156 color_step = 3;
00157 }
00158 else if (rgb_msg->encoding == enc::MONO8)
00159 {
00160 red_offset = 0;
00161 green_offset = 0;
00162 blue_offset = 0;
00163 color_step = 1;
00164 }
00165 else
00166 {
00167 NODELET_ERROR_THROTTLE(5, "Unsupported encoding [%s]", rgb_msg->encoding.c_str());
00168 return;
00169 }
00170
00171
00172 PointCloud::Ptr cloud_msg (new PointCloud);
00173 cloud_msg->header = depth_msg->header;
00174
00175
00176 model_.fromCameraInfo(info_msg);
00177 float center_x = model_.cx();
00178 float center_y = model_.cy();
00179
00180 bool do_masking = (use_indices_ and (mask_indices_.size() != 0));
00181 if (not do_masking)
00182 {
00183 cloud_msg->height = depth_msg->height;
00184 cloud_msg->width = depth_msg->width;
00185 }
00186 else
00187 {
00188 cloud_msg->height = 1;
00189 cloud_msg->width = mask_indices_.size();
00190 }
00191 cloud_msg->is_dense = false;
00192 cloud_msg->points.resize (cloud_msg->height * cloud_msg->width);
00193
00194
00195 float constant_x = 0.001 / model_.fx();
00196 float constant_y = 0.001 / model_.fy();
00197 float bad_point = std::numeric_limits<float>::quiet_NaN ();
00198
00199 int depth_idx = 0, color_idx = 0;
00200 const uint16_t* depth_data = reinterpret_cast<const uint16_t*>(&depth_msg->data[0]);
00201 const uint8_t* rgb_buffer = &rgb_msg->data[0];
00202 PointCloud::iterator pt_iter = cloud_msg->begin ();
00203
00204 if (not do_masking)
00205 {
00206 for (int v = 0; v < (int)cloud_msg->height; ++v)
00207 {
00208 for (int u = 0; u < (int)cloud_msg->width; ++u, ++depth_idx, color_idx += color_step, ++pt_iter)
00209 {
00210 pcl::PointXYZRGB& pt = *pt_iter;
00211
00212
00214 if (depth_data[depth_idx] == 0)
00215 {
00216 pt.x = pt.y = pt.z = bad_point;
00217 }
00218 else
00219 {
00220
00221 pt.x = (u - center_x) * depth_data[depth_idx] * constant_x;
00222 pt.y = (v - center_y) * depth_data[depth_idx] * constant_y;
00223 pt.z = depth_data[depth_idx] * 0.001;
00224 }
00225
00226
00227 RGBValue color;
00228 color.Red = rgb_buffer[color_idx + red_offset];
00229 color.Green = rgb_buffer[color_idx + green_offset];
00230 color.Blue = rgb_buffer[color_idx + blue_offset];
00231 color.Alpha = 0;
00232 pt.rgb = color.float_value;
00233 }
00234 }
00235 }
00236 else
00237 {
00238 int u, v;
00239 unsigned int nMask = mask_indices_.size();
00240 int max_index = (depth_msg->height * depth_msg->width) - 1;
00241 for (unsigned int i = 0; i < nMask; i++, ++pt_iter)
00242 {
00243 pcl::PointXYZRGB& pt = *pt_iter;
00244
00245 depth_idx = mask_indices_[i];
00246 if (depth_idx > max_index)
00247 {
00248 NODELET_ERROR("Mask index %d exceeds maximum index of %d", depth_idx, max_index);
00249 continue;
00250 }
00251 v = depth_idx / depth_msg->width;
00252 u = depth_idx % depth_msg->width;
00253
00254
00256 if (depth_data[depth_idx] == 0)
00257 {
00258 pt.x = pt.y = pt.z = bad_point;
00259 }
00260 else
00261 {
00262
00263 pt.x = (u - center_x) * depth_data[depth_idx] * constant_x;
00264 pt.y = (v - center_y) * depth_data[depth_idx] * constant_y;
00265 pt.z = depth_data[depth_idx] * 0.001;
00266 }
00267
00268
00269 RGBValue color;
00270 color_idx = (v*depth_msg->width + u)*color_step;
00271 color.Red = rgb_buffer[color_idx + red_offset];
00272 color.Green = rgb_buffer[color_idx + green_offset];
00273 color.Blue = rgb_buffer[color_idx + blue_offset];
00274 color.Alpha = 0;
00275 pt.rgb = color.float_value;
00276 }
00277 }
00278
00279 pub_point_cloud_.publish (cloud_msg);
00280 }
00281
00282 void PointCloudXyzrgbNodelet::maskIndicesCb(const pcl::PointIndicesConstPtr& indices)
00283 {
00284 mask_indices_.resize(indices->indices.size());
00285
00286 memcpy(mask_indices_.data(), indices->indices.data(), indices->indices.size() * sizeof(int32_t));
00287 }
00288
00289 }
00290
00291
00292 #include <pluginlib/class_list_macros.h>
00293 PLUGINLIB_DECLARE_CLASS (openni_camera, point_cloud_xyzrgb, openni_camera::PointCloudXyzrgbNodelet, nodelet::Nodelet);