39 #include <boost/thread.hpp> 66 void depthCb(
const sensor_msgs::ImageConstPtr& depth_msg,
67 const sensor_msgs::CameraInfoConstPtr& info_msg);
102 const sensor_msgs::CameraInfoConstPtr& info_msg)
105 cloud_msg->header = depth_msg->header;
106 cloud_msg->height = depth_msg->height;
107 cloud_msg->width = depth_msg->width;
108 cloud_msg->is_dense =
false;
109 cloud_msg->is_bigendian =
false;
117 if (depth_msg->encoding == enc::TYPE_16UC1)
119 convert<uint16_t>(depth_msg, cloud_msg,
model_);
121 else if (depth_msg->encoding == enc::TYPE_32FC1)
123 convert<float>(depth_msg, cloud_msg,
model_);
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
void publish(const boost::shared_ptr< M > &message) const
image_geometry::PinholeCameraModel model_
#define NODELET_ERROR_THROTTLE(rate,...)
sensor_msgs::PointCloud2 PointCloud
PLUGINLIB_EXPORT_CLASS(xiaoqiang_depth_image_proc::PointCloudXyzNodelet, nodelet::Nodelet)
ros::Publisher pub_point_cloud_
ros::NodeHandle & getPrivateNodeHandle() const
boost::shared_ptr< image_transport::ImageTransport > it_
bool fromCameraInfo(const sensor_msgs::CameraInfo &msg)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::NodeHandle & getNodeHandle() const
void depthCb(const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
uint32_t getNumSubscribers() const
boost::mutex connect_mutex_
image_transport::CameraSubscriber sub_depth_
void setPointCloud2FieldsByString(int n_fields,...)