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
00039 #include <pluginlib/class_list_macros.h>
00040 #include <laser_slam/cloud_collector.h>
00041 #include <dynamic_reconfigure/server.h>
00042 #include <pcl_ros/transforms.h>
00043
00044 typedef laser_slam::CloudCollectorROS CloudCollectorROS;
00045 PLUGINLIB_DECLARE_CLASS(laser_slam, CloudCollectorROS,
00046 CloudCollectorROS, nodelet::Nodelet);
00047
00048 namespace laser_slam
00049 {
00050
00051 namespace sm=sensor_msgs;
00052 namespace dr=dynamic_reconfigure;
00053
00054 using std::string;
00055
00056 const ros::Duration TRANSFORM_TOLERANCE(0.3);
00057
00058 void CloudCollectorROS::onInit ()
00059 {
00060 ROS_INFO ("here");
00061 pcl_ros::Filter::onInit();
00062 ros::NodeHandle nh = getPrivateNodeHandle();
00063 nh.param("clouds_per_group", impl_.clouds_per_group_, 20);
00064 nh.param("fixed_frame", impl_.fixed_frame_, string("odom_combined"));
00065 nh.param("base_frame", impl_.base_frame_, string("base_footprint"));
00066 ROS_INFO_STREAM ("Initialized cloud collector with " << impl_.clouds_per_group_
00067 << " clouds per group, fixed frame " << impl_.fixed_frame_
00068 << " and base frame " << impl_.base_frame_);
00069 }
00070
00071
00072 void
00073 CloudCollector::applyFilter (sm::PointCloud2& output)
00074 {
00075
00076 pcl::PointCloud<pcl::PointXYZ> input_cloud, transformed_cloud;
00077 pcl::fromROSMsg(*input_, input_cloud);
00078
00079
00080 if (!tf_.waitForTransform(fixed_frame_, input_cloud.header.frame_id,
00081 input_cloud.header.stamp, ros::Duration(0.1)) ||
00082 !pcl_ros::transformPointCloud(fixed_frame_, input_cloud, transformed_cloud, tf_)) {
00083 ROS_INFO ("Not adding cloud since transform was unavailable");
00084 return;
00085 }
00086
00087
00088 cloud_.header.frame_id = fixed_frame_;
00089 cloud_ += transformed_cloud;
00090
00091
00092 if (num_clouds_++ > (unsigned) clouds_per_group_) {
00093 pcl::PointCloud<pcl::PointXYZ> output_cloud;
00094 ros::Time now = ros::Time::now();
00095 if (!tf_.waitForTransform(base_frame_, fixed_frame_, now, ros::Duration(0.1)) ||
00096 !pcl_ros::transformPointCloud(base_frame_, cloud_, output_cloud, tf_)) {
00097 ROS_INFO ("Not publishing combined cloud due to lack of transform");
00098 return;
00099 }
00100 pcl::toROSMsg(output_cloud, output);
00101 cloud_ = pcl::PointCloud<pcl::PointXYZ>();
00102 num_clouds_ = 0;
00103 }
00104 }
00105
00106
00107
00108 }