35 #define BOOST_PARAMETER_MAX_ARITY 7
46 DiagnosticNodelet::onInit();
47 pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_,
"output", 1);
63 vital_checker_->poke();
64 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_xyzrgb(
new pcl::PointCloud<pcl::PointXYZRGB>);
67 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_xyz(
new pcl::PointCloud<pcl::PointXYZ>);
68 cloud_xyz->points.resize(cloud_xyzrgb->points.size());
69 cloud_xyz->is_dense = cloud_xyzrgb->is_dense;
70 cloud_xyz->width = cloud_xyzrgb->width;
71 cloud_xyz->height = cloud_xyzrgb->height;
72 for (
size_t i = 0;
i < cloud_xyzrgb->points.size();
i++) {
74 p.x = cloud_xyzrgb->points[
i].x;
75 p.y = cloud_xyzrgb->points[
i].y;
76 p.z = cloud_xyzrgb->points[
i].z;
77 cloud_xyz->points[
i] =
p;
79 sensor_msgs::PointCloud2 out_cloud_msg;
81 out_cloud_msg.header = cloud_msg->header;