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
00050 #define PFLN printf("file %s line %d\n",__FILE__,__LINE__);
00051
00052 #define _USE_DEBUG_ 0
00053
00054 ros::NodeHandle* p_n;
00055 tf::TransformListener *p_listener;
00056 bool process_laser_scan[5]={false,false,false,false,false};
00057 bool process_point_cloud[5]={false,false,false,false,false};
00058 pcl::PointCloud<pcl::PointXYZ> pc_accumulated;
00059 pcl::PointCloud<pcl::PointXYZ> convex_hull;
00060 double perpendicular_treshold = 0.2;
00061 double output_freq;
00062
00063 void filter_cloud(pcl::PointCloud<pcl::PointXYZ>* pc_in, std::string pc_frame_id)
00064 {
00065 pcl::PointCloud<pcl::PointXYZ> pc_transformed;
00066 pcl::PointCloud<pcl::PointXYZ> pc_filtered;
00067 pcl::PointCloud<pcl::PointXYZ> pc_projected;
00068 tf::StampedTransform transform;
00069
00070
00071 try
00072 {
00073 p_listener->lookupTransform(pc_frame_id, ros::names::remap("/tracking_frame"), ros::Time(0), transform);
00074
00075 }
00076 catch (tf::TransformException ex)
00077 {
00078 ROS_ERROR("%s",ex.what());
00079 }
00080
00081
00082 pcl_ros::transformPointCloud(*pc_in,pc_transformed,transform.inverse());
00083 pc_transformed.header.frame_id = ros::names::remap("/tracking_frame");
00084
00085
00086 pcl::ExtractPolygonalPrismData<pcl::PointXYZ> epp;
00087 pcl::PointCloud<pcl::PointXYZ>::ConstPtr input_cloud_constptr;
00088 input_cloud_constptr.reset (new pcl::PointCloud<pcl::PointXYZ> (pc_transformed));
00089 pcl::PointCloud<pcl::PointXYZ>::ConstPtr convex_hull_constptr;
00090 convex_hull_constptr.reset (new pcl::PointCloud<pcl::PointXYZ> (convex_hull));
00091
00092
00093 pcl::ExtractIndices<pcl::PointXYZ> extract;
00094 pcl::PointIndices::Ptr indices;
00095 indices.reset();
00096 indices = pcl::PointIndices::Ptr(new pcl::PointIndices);
00097
00098
00099 epp.setInputCloud(input_cloud_constptr);
00100 epp.setInputPlanarHull(convex_hull_constptr);
00101 epp.setHeightLimits(-perpendicular_treshold, perpendicular_treshold);
00102 epp.setViewPoint(0,0,0);
00103 epp.segment(*indices);
00104
00105 extract.setInputCloud(pc_transformed.makeShared());
00106 extract.setIndices(indices);
00107 extract.setNegative(false);
00108 extract.filter(pc_filtered);
00109
00110 pcl::ProjectInliers<pcl::PointXYZ> projection;
00111 projection.setModelType(pcl::SACMODEL_PLANE);
00112 pcl::ModelCoefficients::Ptr coeff(new pcl::ModelCoefficients);
00113 coeff->values.resize(4);
00114 coeff->values[0] = 0;
00115 coeff->values[1] = 0;
00116 coeff->values[2] = 1;
00117 coeff->values[3] = 0;
00118
00119 projection.setInputCloud(pc_filtered.makeShared());
00120 projection.setModelCoefficients(coeff);
00121 projection.filter(pc_projected);
00122
00123 coeff.reset();
00124 input_cloud_constptr.reset();
00125 convex_hull_constptr.reset();
00126 indices.reset();
00127
00128 pc_accumulated += pc_projected;
00129
00130 #if _USE_DEBUG_
00131 ROS_INFO("pc_transformed has %d points", (int)pc_transformed.size());
00132 ROS_INFO("pc_filtered has %d points", (int)pc_filtered.size());
00133 ROS_INFO("pc_accumulated now has %d points", (int)pc_accumulated.size());
00134 #endif
00135 }
00136
00137 void cloud_cb (const sensor_msgs::PointCloud2ConstPtr & pcmsg_in)
00138 {
00139
00140 #if _USE_DEBUG_
00141 ROS_INFO("Received point cloud");
00142 #endif
00143 pcl::PointCloud<pcl::PointXYZ> pc_in;
00144 pcl::fromROSMsg(*pcmsg_in,pc_in);
00145 filter_cloud(&pc_in, pcmsg_in->header.frame_id);
00146 }
00147
00148 void scan_cb (const sensor_msgs::LaserScan::ConstPtr& scan_in)
00149 {
00150 #if _USE_DEBUG_
00151 ROS_INFO("Received laser scan");
00152 #endif
00153
00154 ROS_INFO("asdasd");
00155 laser_geometry::LaserProjection projector;
00156 sensor_msgs::PointCloud2 pcmsg_in;
00157
00158 projector.transformLaserScanToPointCloud(scan_in->header.frame_id, *scan_in,pcmsg_in,*p_listener);
00159 pcmsg_in.header.stamp=ros::Time();
00160 pcmsg_in.header.frame_id=scan_in->header.frame_id;
00161
00162 pcl::PointCloud<pcl::PointXYZ> pc_in;
00163 pcl::fromROSMsg(pcmsg_in,pc_in);
00164 filter_cloud(&pc_in, scan_in->header.frame_id);
00165 }
00166
00167
00168
00169 int main(int argc, char **argv)
00170 {
00171
00172 ros::init(argc, argv, "planar_pc_generator_node");
00173 ros::NodeHandle n("~");
00174 tf::TransformListener listener(n,ros::Duration(10));
00175 p_listener=&listener;
00176 p_n=&n;
00177 n.param("output_frequency", output_freq, 30.0);
00178 n.param("perpendicular_treshold", perpendicular_treshold, 0.1);
00179
00180
00181 if (ros::names::remap("/tracking_frame")=="/tracking_frame")
00182 {
00183 ROS_ERROR("/tracking_frame was not remapped. Aborting program.");
00184 ros::shutdown();
00185 }
00186 pc_accumulated.header.frame_id = ros::names::remap("/tracking_frame");
00187
00188
00189 for (int i=0; i<5; i++)
00190 {
00191 char str[1024];
00192 sprintf(str,"/laserscan%d", i);
00193 if (ros::names::remap(str)!=str)
00194 {
00195 process_laser_scan[i] = true;
00196 }
00197 }
00198
00199
00200 for (int i=0; i<5; i++)
00201 {
00202 char str[1024];
00203 sprintf(str,"/pointcloud%d", i);
00204 if (ros::names::remap(str)!=str)
00205 {
00206 process_point_cloud[i] = true;
00207 }
00208 }
00209
00210 std::vector<ros::Subscriber> sub;
00211
00212
00213 for (int i=0; i<5; i++)
00214 {
00215 if (process_laser_scan[i]==true)
00216 {
00217 char str[1024];
00218 sprintf(str,"/laserscan%d", i);
00219 ros::Subscriber sub_ = n.subscribe (str, 1, scan_cb);
00220 ROS_INFO("Subscribing to %s", (ros::names::remap(str)).c_str());
00221 sub.push_back(sub_);
00222 }
00223 }
00224
00225
00226 for (int i=0; i<5; i++)
00227 {
00228 if (process_point_cloud[i]==true)
00229 {
00230 char str[1024];
00231 sprintf(str,"/pointcloud%d", i);
00232 ros::Subscriber sub_ = n.subscribe (str, 1, cloud_cb);
00233 ROS_INFO("Subscribing to %s", (ros::names::remap(str)).c_str());
00234 sub.push_back(sub_);
00235 }
00236 }
00237
00238 if (sub.size()==0)
00239 {
00240 ROS_ERROR("No /laserscan[0 4] or /pointcloud[0 4] where remapped. Aborting...");
00241 ros::shutdown();
00242 }
00243
00244
00245 ros::Publisher pub = n.advertise<sensor_msgs::PointCloud2>("/pc_out", 1);
00246
00247
00248
00249 convex_hull.header.frame_id = ros::names::remap("/tracking_frame");
00250 pcl::PointXYZ pt;
00251 pt.x = -500; pt.y=-500; pt.z=0;
00252 convex_hull.points.push_back(pt);
00253
00254 pt.x = 500; pt.y=-500; pt.z=0;
00255 convex_hull.points.push_back(pt);
00256
00257 pt.x = 500; pt.y= 500; pt.z=0;
00258 convex_hull.points.push_back(pt);
00259
00260 pt.x = -500; pt.y=500; pt.z=0;
00261 convex_hull.points.push_back(pt);
00262
00263
00264
00265
00266
00267
00268 ros::Rate loop_rate(output_freq);
00269 while (n.ok())
00270 {
00271
00272
00273
00274
00275 ros::spinOnce();
00276
00277 if (pc_accumulated.points.size()!=0)
00278 {
00279 sensor_msgs::PointCloud2 pcmsg_out;
00280 pcl::toROSMsg(pc_accumulated, pcmsg_out);
00281 pcmsg_out.header.stamp = ros::Time::now();
00282 #if _USE_DEBUG_
00283 ROS_INFO("Publishing pc_accumulated with %d points", (int)pc_accumulated.size());
00284 #endif
00285 pub.publish(pcmsg_out);
00286 pc_accumulated.erase(pc_accumulated.begin(), pc_accumulated.end());
00287 }
00288
00289 loop_rate.sleep();
00290 }
00291 }