40 #include <pcl/common/centroid.h> 47 sensor_msgs::PointCloud2
output;
51 sensor_msgs::PointCloud2 latest_pointcloud(*input);
52 latest_pointcloud.header.stamp =
ros::Time(0);
55 output.header.stamp = input->header.stamp;
82 DiagnosticNodelet::onInit();
86 ROS_WARN(
"~target_frame_id is not specified, using %s",
"/base_footprint");
92 pub_cloud_ = advertise<sensor_msgs::PointCloud2>(*
pnh_,
"output", 1);
#define NODELET_ERROR(...)
void publish(const boost::shared_ptr< M > &message) const
void output(int index, double value)
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
void transformPointCloud(const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const tf::Transform &transform)
static tf::TransformListener * getInstance()