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 = boost::make_shared<PointCloudT>();
68 PointCloudT::Ptr cloud_fixed = boost::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");
133 pub_ = nh.
advertise<sensor_msgs::PointCloud2>(
"all_layers", 10);
int main(int argc, char **argv)
void publish(const boost::shared_ptr< M > &message) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
sick_ldmrs_msgs::SICK_LDMRS_Point PointT
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
ROSCPP_DECL void spin(Spinner &spinner)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
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 callback(const sensor_msgs::PointCloud2::ConstPtr &pc)
tf::TransformListener * tf_
void transformPointCloud(const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const tf::Transform &transform)
bool getParam(const std::string &key, std::string &s) const
void toROSMsg(const sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image)
PointCloudT::Ptr cloud_lower_
pcl::PointCloud< PointT > PointCloudT
Connection registerCallback(const C &callback)