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
00035 #include <stdio.h>
00036 #include <ros/ros.h>
00037 #include <laser_geometry/laser_geometry.h>
00038 #include <sensor_msgs/LaserScan.h>
00039 #include <sensor_msgs/PointCloud2.h>
00040 #include <tf/transform_listener.h>
00041 #include <pcl_ros/transforms.h>
00042 #include <pcl/ros/conversions.h>
00043 #include <pcl/point_cloud.h>
00044 #include <pcl/point_types.h>
00045 #include <pcl/segmentation/extract_polygonal_prism_data.h>
00046 #include <pcl/filters/extract_indices.h>
00047 #include <pcl/filters/project_inliers.h>
00048
00049 ros::NodeHandle* p_n;
00050 tf::TransformListener *p_listener;
00051 pcl::PointCloud<pcl::PointXYZ> pc_accumulated;
00052 pcl::PointCloud<pcl::PointXYZ> convex_hull;
00053 double perpendicular_treshold = 0.2;
00054 double output_freq;
00055
00056 bool laserscan_0_arrived=false;
00057 bool laserscan_1_arrived=false;
00058
00059 void filter_cloud(pcl::PointCloud<pcl::PointXYZ>* pc_in, std::string pc_frame_id)
00060 {
00061 pcl::PointCloud<pcl::PointXYZ> pc_transformed;
00062 pcl::PointCloud<pcl::PointXYZ> pc_filtered;
00063 pcl::PointCloud<pcl::PointXYZ> pc_projected;
00064 tf::StampedTransform transform;
00065
00066
00067 try
00068 {
00069 p_listener->lookupTransform(pc_frame_id, ros::names::remap("/tracking_frame"), ros::Time(0), transform);
00070
00071 }
00072 catch (tf::TransformException ex)
00073 {
00074 ROS_ERROR("%s",ex.what());
00075 }
00076
00077
00078 pcl_ros::transformPointCloud(*pc_in,pc_transformed,transform.inverse());
00079 pc_transformed.header.frame_id = ros::names::remap("/tracking_frame");
00080
00081
00082 pcl::ExtractPolygonalPrismData<pcl::PointXYZ> epp;
00083 pcl::PointCloud<pcl::PointXYZ>::ConstPtr input_cloud_constptr;
00084 input_cloud_constptr.reset (new pcl::PointCloud<pcl::PointXYZ> (pc_transformed));
00085 pcl::PointCloud<pcl::PointXYZ>::ConstPtr convex_hull_constptr;
00086 convex_hull_constptr.reset (new pcl::PointCloud<pcl::PointXYZ> (convex_hull));
00087
00088
00089 pcl::ExtractIndices<pcl::PointXYZ> extract;
00090 pcl::PointIndices::Ptr indices;
00091 indices.reset();
00092 indices = pcl::PointIndices::Ptr(new pcl::PointIndices);
00093
00094
00095 epp.setInputCloud(input_cloud_constptr);
00096 epp.setInputPlanarHull(convex_hull_constptr);
00097 epp.setHeightLimits(-perpendicular_treshold, perpendicular_treshold);
00098 epp.setViewPoint(0,0,0);
00099 epp.segment(*indices);
00100
00101 extract.setInputCloud(pc_transformed.makeShared());
00102 extract.setIndices(indices);
00103 extract.setNegative(false);
00104 extract.filter(pc_filtered);
00105
00106 pcl::ProjectInliers<pcl::PointXYZ> projection;
00107 projection.setModelType(pcl::SACMODEL_PLANE);
00108 pcl::ModelCoefficients::Ptr coeff(new pcl::ModelCoefficients);
00109 coeff->values.resize(4);
00110 coeff->values[0] = 0;
00111 coeff->values[1] = 0;
00112 coeff->values[2] = 1;
00113 coeff->values[3] = 0;
00114
00115 projection.setInputCloud(pc_filtered.makeShared());
00116 projection.setModelCoefficients(coeff);
00117 projection.filter(pc_projected);
00118
00119 coeff.reset();
00120 input_cloud_constptr.reset();
00121 convex_hull_constptr.reset();
00122 indices.reset();
00123
00124 pc_accumulated += pc_projected;
00125
00126 #if _USE_DEBUG_
00127 ROS_INFO("pc_transformed has %d points", (int)pc_transformed.size());
00128 ROS_INFO("pc_filtered has %d points", (int)pc_filtered.size());
00129 ROS_INFO("pc_accumulated now has %d points", (int)pc_accumulated.size());
00130 #endif
00131 }
00132
00133 void scan_0_cb (const sensor_msgs::LaserScan::ConstPtr& scan_in)
00134 {
00135 laser_geometry::LaserProjection projector;
00136 sensor_msgs::PointCloud2 pcmsg_in;
00137
00138 projector.transformLaserScanToPointCloud(scan_in->header.frame_id, *scan_in,pcmsg_in,*p_listener);
00139 pcmsg_in.header.stamp=ros::Time();
00140 pcmsg_in.header.frame_id=scan_in->header.frame_id;
00141
00142 pcl::PointCloud<pcl::PointXYZ> pc_in;
00143 pcl::fromROSMsg(pcmsg_in,pc_in);
00144 filter_cloud(&pc_in, scan_in->header.frame_id);
00145
00146 laserscan_0_arrived=true;
00147 }
00148
00149 void scan_1_cb (const sensor_msgs::LaserScan::ConstPtr& scan_in)
00150 {
00151 laser_geometry::LaserProjection projector;
00152 sensor_msgs::PointCloud2 pcmsg_in;
00153
00154 projector.transformLaserScanToPointCloud(scan_in->header.frame_id, *scan_in,pcmsg_in,*p_listener);
00155 pcmsg_in.header.stamp=ros::Time();
00156 pcmsg_in.header.frame_id=scan_in->header.frame_id;
00157
00158 pcl::PointCloud<pcl::PointXYZ> pc_in;
00159 pcl::fromROSMsg(pcmsg_in,pc_in);
00160 filter_cloud(&pc_in, scan_in->header.frame_id);
00161
00162 laserscan_1_arrived=true;
00163 }
00164
00165 int main(int argc, char **argv)
00166 {
00167 ros::init(argc, argv, "simple_planar_pc_generator_node");
00168 ros::NodeHandle n("~");
00169 tf::TransformListener listener(n,ros::Duration(10));
00170 p_listener=&listener;
00171 p_n=&n;
00172
00173 n.param("output_frequency", output_freq, 200.0);
00174 n.param("perpendicular_treshold", perpendicular_treshold, 0.1);
00175
00176
00177 if (ros::names::remap("/tracking_frame")=="/tracking_frame")
00178 {
00179 ROS_ERROR("/tracking_frame was not remapped. Aborting program.");
00180 ros::shutdown();
00181 }
00182
00183 pc_accumulated.header.frame_id = ros::names::remap("/tracking_frame");
00184
00185 ros::Subscriber sub_0 = n.subscribe ("/laserscan0", 1, scan_0_cb);
00186 ros::Subscriber sub_1 = n.subscribe ("/laserscan1", 1, scan_1_cb);
00187
00188
00189 ros::Publisher pub = n.advertise<sensor_msgs::PointCloud2>("/pc_out", 1);
00190
00191
00192
00193 convex_hull.header.frame_id = ros::names::remap("/tracking_frame");
00194 pcl::PointXYZ pt;
00195 pt.x = -500; pt.y=-500; pt.z=0;
00196 convex_hull.points.push_back(pt);
00197
00198 pt.x = 500; pt.y=-500; pt.z=0;
00199 convex_hull.points.push_back(pt);
00200
00201 pt.x = 500; pt.y= 500; pt.z=0;
00202 convex_hull.points.push_back(pt);
00203
00204 pt.x = -500; pt.y=500; pt.z=0;
00205 convex_hull.points.push_back(pt);
00206
00207 ros::Rate loop_rate(output_freq);
00208
00209 while (n.ok())
00210 {
00211 ros::spinOnce();
00212
00213 if (laserscan_0_arrived && laserscan_1_arrived)
00214 {
00215 laserscan_0_arrived=false;
00216 laserscan_1_arrived=false;
00217
00218 sensor_msgs::PointCloud2 pcmsg_out;
00219 pcl::toROSMsg(pc_accumulated, pcmsg_out);
00220 pcmsg_out.header.stamp = ros::Time::now();
00221 #if _USE_DEBUG_
00222 ROS_INFO("Publishing pc_accumulated with %d points", (int)pc_accumulated.size());
00223 #endif
00224 pub.publish(pcmsg_out);
00225 pc_accumulated.erase(pc_accumulated.begin(), pc_accumulated.end());
00226 }
00227
00228
00229 loop_rate.sleep();
00230 }
00231 }