40 #include <pcl/common/centroid.h>
46 vital_checker_->poke();
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);