Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #include <ros/ros.h>
00036
00037 #include <tf/transform_listener.h>
00038 #include <tf/message_filter.h>
00039 #include <message_filters/subscriber.h>
00040
00041 #include <pcl_conversions/pcl_conversions.h>
00042
00043 #include <sensor_msgs/PointCloud2.h>
00044 #include <sick_ldmrs_msgs/sick_ldmrs_point_type.h>
00045 #include <pcl/point_cloud.h>
00046
00047 #include <pcl_ros/transforms.h>
00048 #include <pcl_ros/impl/transforms.hpp>
00049
00050 typedef sick_ldmrs_msgs::SICK_LDMRS_Point PointT;
00051 typedef pcl::PointCloud<PointT> PointCloudT;
00052
00053 tf::TransformListener* tf_;
00054 ros::Publisher pub_;
00055
00056 std::string fixed_frame_;
00057
00058 PointCloudT::Ptr cloud_lower_ = boost::make_shared<PointCloudT>();
00059
00060 void callback(const sensor_msgs::PointCloud2::ConstPtr& pc)
00061 {
00062 PointCloudT::Ptr cloud = boost::make_shared<PointCloudT>();
00063 pcl::fromROSMsg(*pc, *cloud);
00064
00065
00066 try
00067 {
00068 PointCloudT::Ptr cloud_fixed = boost::make_shared<PointCloudT>();
00069
00070 if (!pcl_ros::transformPointCloud(fixed_frame_, *cloud, *cloud_fixed, *tf_))
00071 {
00072 ROS_WARN("TF exception in transformPointCloud!");
00073 cloud_lower_.reset();
00074 return ;
00075 }
00076 cloud = cloud_fixed;
00077 }
00078 catch (tf::TransformException& ex)
00079 {
00080 ROS_WARN("TF Exception %s", ex.what());
00081 cloud_lower_.reset();
00082 return ;
00083 }
00084
00085
00086 if (cloud->size() == 0)
00087 return;
00088
00089 if (cloud->at(0).layer < 4)
00090 {
00091 cloud_lower_ = cloud;
00092 return;
00093 }
00094 else if (!cloud_lower_)
00095 {
00096 return;
00097 }
00098
00099
00100 *cloud_lower_ += *cloud;
00101
00102
00103 sensor_msgs::PointCloud2::Ptr msg = boost::make_shared<sensor_msgs::PointCloud2>();
00104 pcl::toROSMsg(*cloud_lower_, *msg);
00105 msg->header.stamp = pc->header.stamp;
00106 msg->header.frame_id = fixed_frame_;
00107 pub_.publish(msg);
00108
00109 cloud_lower_.reset();
00110 }
00111
00112 int main(int argc, char **argv)
00113 {
00114 ros::init(argc, argv, "sick_ldmrs_all_layer_assembler");
00115 ros::NodeHandle nh;
00116 ros::NodeHandle private_nh("~");
00117
00118 if (!private_nh.getParam("fixed_frame", fixed_frame_))
00119 {
00120 ROS_FATAL("Need to set parameter fixed_frame");
00121 return 1;
00122 }
00123
00124 tf_ = new tf::TransformListener(nh, ros::Duration(3.0));
00125
00126 message_filters::Subscriber<sensor_msgs::PointCloud2> sub;
00127 tf::MessageFilter<sensor_msgs::PointCloud2>* tf_filter;
00128
00129 sub.subscribe(nh, "cloud", 10);
00130 tf_filter = new tf::MessageFilter<sensor_msgs::PointCloud2>(sub, *tf_, fixed_frame_, 10);
00131 tf_filter->registerCallback(boost::bind(callback, _1));
00132
00133 pub_ = nh.advertise<sensor_msgs::PointCloud2>("all_layers", 10);
00134
00135 ros::spin();
00136
00137 delete tf_filter;
00138 delete tf_;
00139
00140 return 0;
00141 }