43 #include <sensor_msgs/PointCloud2.h>
45 #include <pcl/point_cloud.h>
60 void callback(
const sensor_msgs::PointCloud2::ConstPtr& pc)
62 PointCloudT::Ptr cloud = pcl::make_shared<PointCloudT>();
68 PointCloudT::Ptr cloud_fixed = pcl::make_shared<PointCloudT>();
72 ROS_WARN(
"TF exception in transformPointCloud!");
80 ROS_WARN(
"TF Exception %s", ex.what());
86 if (cloud->size() == 0)
89 if (cloud->at(0).layer < 4)
103 sensor_msgs::PointCloud2::Ptr
msg = boost::make_shared<sensor_msgs::PointCloud2>();
105 msg->header.stamp = pc->header.stamp;
112 int main(
int argc,
char **argv)
114 ros::init(argc, argv,
"sick_ldmrs_all_layer_assembler");
120 ROS_FATAL(
"Need to set parameter fixed_frame");
131 tf_filter->registerCallback(boost::bind(
callback, boost::placeholders::_1));
133 pub_ = nh.
advertise<sensor_msgs::PointCloud2>(
"all_layers", 10);