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
00033 #include <pointcloud_segmentation/plane_road_extraction.h>
00034
00035 int main(int argc, char **argv)
00036 {
00037
00038 ros::init(argc, argv, "plane_road_extraction_nodelet");
00039 ros::NodeHandle n;
00040
00041
00042 string pointcloud_input;
00043 string pointcloud_road;
00044 string pointcloud_clusters;
00045 string pointcloud_road_perimeter;
00046 double threshold;
00047
00048
00049 plane_road_extraction<PointXYZRGB> * extraction = new plane_road_extraction<PointXYZRGB>();
00050
00051
00052 ros::NodeHandle private_node_handle_("~");
00053 private_node_handle_.param("pointcloud_input", pointcloud_input, string("pointcloud_input"));
00054 private_node_handle_.param("pointcloud_road", pointcloud_road, string("pointcloud_road"));
00055 private_node_handle_.param("pointcloud_clusters", pointcloud_clusters, string("pointcloud_clusters"));
00056 private_node_handle_.param("pointcloud_road_perimeter", pointcloud_road_perimeter, string("pointcloud_road_perimeter"));
00057 private_node_handle_.param("z_min", extraction->z_min, double(extraction->z_min));
00058 private_node_handle_.param("z_max", extraction->z_max, double(extraction->z_max));
00059 private_node_handle_.param("threshold", threshold, double(threshold));
00060
00061
00062 ros::Subscriber sub_cloud = n.subscribe(pointcloud_input.c_str(), 1000, &plane_road_extraction<PointXYZRGB>::filter, extraction);
00063
00064
00065 ros::Publisher pub_road = n.advertise<sensor_msgs::PointCloud2>(pointcloud_road.c_str(), 10);
00066 ros::Publisher pub_clusters = n.advertise<sensor_msgs::PointCloud2>(pointcloud_clusters.c_str(), 10);
00067 ros::Publisher pub_road_perimeter= n.advertise<sensor_msgs::PointCloud2>(pointcloud_road_perimeter.c_str(), 10);
00068
00069
00070 extraction->pub_road_ptr=&pub_road;
00071 extraction->pub_clusters_ptr=&pub_clusters;
00072 extraction->pub_road_perimeter_ptr=&pub_road_perimeter;
00073
00074
00075 tf::TransformListener listener;
00076 tf::TransformBroadcaster br;
00077
00078 extraction->pms.listener_atc_ground_ptr=&listener;
00079 extraction->pms.broadcast_ptr=&br;
00080
00081
00082 extraction->pms.reference_ground_frame=(char *)(ros::names::remap("/atc/vehicle/ground")).c_str();
00083 extraction->pms.pub_frame_name=(char *)(ros::names::remap("/environment/road_frame")).c_str();
00084 extraction->pms.threshold=(float)(threshold);
00085 extraction->pms.debug=false;
00086
00087
00088 while (n.ok())
00089 {
00090 ros::spinOnce();
00091 }
00092
00093 return 0;
00094 }