34 #include <boost/version.hpp>    35 #if ((BOOST_VERSION / 100) % 1000) >= 53    36 #include <boost/thread/lock_guard.hpp>    49 #include <sensor_msgs/PointCloud2.h>    53 #include <opencv2/imgproc/imgproc.hpp>    82   virtual void onInit();
    86   void imageCb(
const sensor_msgs::ImageConstPtr& depth_msg,
    87                const sensor_msgs::ImageConstPtr& rgb_msg,
    88                const sensor_msgs::CameraInfoConstPtr& info_msg);
    91   void convert(
const sensor_msgs::ImageConstPtr& depth_msg,
    92                const sensor_msgs::ImageConstPtr& rgb_msg,
    93                const PointCloud::Ptr& cloud_msg,
    94                int red_offset, 
int green_offset, 
int blue_offset, 
int color_step);
   108   private_nh.
param(
"queue_size", queue_size, 5);
   110   private_nh.
param(
"exact_sync", use_exact_sync, 
false);
   127   boost::lock_guard<boost::mutex> lock(connect_mutex_);
   134   boost::lock_guard<boost::mutex> lock(connect_mutex_);
   135   if (pub_point_cloud_.getNumSubscribers() == 0)
   137     sub_depth_.unsubscribe();
   138     sub_rgb_  .unsubscribe();
   139     sub_info_ .unsubscribe();
   141   else if (!sub_depth_.getSubscriber())
   145     std::string depth_image_transport_param = 
"depth_image_transport";
   149     sub_depth_.subscribe(*depth_it_, 
"image_rect",       1, depth_hints);
   153     sub_rgb_  .subscribe(*rgb_it_,   
"image_rect_color", 1, hints);
   154     sub_info_ .subscribe(*rgb_nh_,   
"camera_info",      1);
   159                                       const sensor_msgs::ImageConstPtr& rgb_msg_in,
   160                                       const sensor_msgs::CameraInfoConstPtr& info_msg)
   163   if (depth_msg->header.frame_id != rgb_msg_in->header.frame_id)
   166                            depth_msg->header.frame_id.c_str(), rgb_msg_in->header.frame_id.c_str());
   171   model_.fromCameraInfo(info_msg);
   174   sensor_msgs::ImageConstPtr rgb_msg = rgb_msg_in;
   175   if (depth_msg->width != rgb_msg->width || depth_msg->height != rgb_msg->height)
   177     sensor_msgs::CameraInfo info_msg_tmp = *info_msg;
   178     info_msg_tmp.width = depth_msg->width;
   179     info_msg_tmp.height = depth_msg->height;
   180     float ratio = float(depth_msg->width)/float(rgb_msg->width);
   181     info_msg_tmp.K[0] *= ratio;
   182     info_msg_tmp.K[2] *= ratio;
   183     info_msg_tmp.K[4] *= ratio;
   184     info_msg_tmp.K[5] *= ratio;
   185     info_msg_tmp.P[0] *= ratio;
   186     info_msg_tmp.P[2] *= ratio;
   187     info_msg_tmp.P[5] *= ratio;
   188     info_msg_tmp.P[6] *= ratio;
   189     model_.fromCameraInfo(info_msg_tmp);
   198       ROS_ERROR(
"cv_bridge exception: %s", e.what());
   202     cv_rsz.
header = cv_ptr->header;
   204     cv::resize(cv_ptr->image.rowRange(0,depth_msg->height/ratio), cv_rsz.
image, cv::Size(depth_msg->width, depth_msg->height));
   205     if ((rgb_msg->encoding == enc::RGB8) || (rgb_msg->encoding == enc::BGR8) || (rgb_msg->encoding == enc::MONO8))
   214     rgb_msg = rgb_msg_in;
   217   int red_offset, green_offset, blue_offset, color_step;
   218   if (rgb_msg->encoding == enc::RGB8)
   225   if (rgb_msg->encoding == enc::RGBA8)
   232   else if (rgb_msg->encoding == enc::BGR8)
   239   else if (rgb_msg->encoding == enc::BGRA8)
   246   else if (rgb_msg->encoding == enc::MONO8)
   272   cloud_msg->header = depth_msg->header; 
   273   cloud_msg->height = depth_msg->height;
   274   cloud_msg->width  = depth_msg->width;
   275   cloud_msg->is_dense = 
false;
   276   cloud_msg->is_bigendian = 
false;
   281   if (depth_msg->encoding == enc::TYPE_16UC1)
   283     convert<uint16_t>(depth_msg, rgb_msg, cloud_msg, red_offset, green_offset, blue_offset, color_step);
   285   else if (depth_msg->encoding == enc::TYPE_32FC1)
   287     convert<float>(depth_msg, rgb_msg, cloud_msg, red_offset, green_offset, blue_offset, color_step);
   295   pub_point_cloud_.publish (cloud_msg);
   300                                       const sensor_msgs::ImageConstPtr& rgb_msg,
   301                                       const PointCloud::Ptr& cloud_msg,
   302                                       int red_offset, 
int green_offset, 
int blue_offset, 
int color_step)
   305   float center_x = model_.cx();
   306   float center_y = model_.cy();
   310   float constant_x = unit_scaling / model_.fx();
   311   float constant_y = unit_scaling / model_.fy();
   312   float bad_point = std::numeric_limits<float>::quiet_NaN ();
   314   const T* depth_row = 
reinterpret_cast<const T*
>(&depth_msg->data[0]);
   315   int row_step = depth_msg->step / 
sizeof(T);
   316   const uint8_t* rgb = &rgb_msg->data[0];
   317   int rgb_skip = rgb_msg->step - rgb_msg->width * color_step;
   327   for (
int v = 0; v < int(cloud_msg->height); ++v, depth_row += row_step, rgb += rgb_skip)
   329     for (
int u = 0; u < int(cloud_msg->width); ++u, rgb += color_step, ++iter_x, ++iter_y, ++iter_z, ++iter_a, ++iter_r, ++iter_g, ++iter_b)
   331       T depth = depth_row[u];
   336         *iter_x = *iter_y = *iter_z = bad_point;
   341         *iter_x = (u - center_x) * depth * constant_x;
   342         *iter_y = (v - center_y) * depth * constant_y;
   348       *iter_r = rgb[red_offset];
   349       *iter_g = rgb[green_offset];
   350       *iter_b = rgb[blue_offset];
 
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
void convert(const sensor_msgs::ImageConstPtr &depth_msg, PointCloud::Ptr &cloud_msg, const image_geometry::PinholeCameraModel &model, double range_max=0.0)
boost::shared_ptr< Synchronizer > sync_
ros::NodeHandlePtr rgb_nh_
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
ros::Publisher pub_point_cloud_
#define NODELET_ERROR_THROTTLE(rate,...)
ExactTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo > SyncPolicy
image_transport::SubscriberFilter sub_rgb_
void imageCb(const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::ImageConstPtr &rgb_msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
boost::mutex connect_mutex_
message_filters::Synchronizer< ExactSyncPolicy > ExactSynchronizer
sensor_msgs::ImagePtr toImageMsg() const
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
image_geometry::PinholeCameraModel model_
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
message_filters::Synchronizer< SyncPolicy > Synchronizer
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
sensor_msgs::PointCloud2 PointCloud
boost::shared_ptr< ExactSynchronizer > exact_sync_
PLUGINLIB_EXPORT_CLASS(depth_image_proc::PointCloudXyzrgbNodelet, nodelet::Nodelet)
boost::shared_ptr< image_transport::ImageTransport > rgb_it_
ExactTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo > ExactSyncPolicy
message_filters::Subscriber< sensor_msgs::CameraInfo > sub_info_
void setPointCloud2FieldsByString(int n_fields,...)
ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo > SyncPolicy
void convert(const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::ImageConstPtr &rgb_msg, const PointCloud::Ptr &cloud_msg, int red_offset, int green_offset, int blue_offset, int color_step)