35 int main(
int argc, 
char **argv)
 
   38     ros::init(argc, argv, 
"plane_road_extraction_nodelet");
 
   42     string pointcloud_input;
 
   43     string pointcloud_road;
 
   44     string pointcloud_clusters;
 
   45     string pointcloud_road_perimeter;
 
   52     ros::NodeHandle private_node_handle_(
"~");
 
   53     private_node_handle_.param(
"pointcloud_input", pointcloud_input, 
string(
"pointcloud_input"));
 
   54     private_node_handle_.param(
"pointcloud_road", pointcloud_road, 
string(
"pointcloud_road"));
 
   55     private_node_handle_.param(
"pointcloud_clusters", pointcloud_clusters, 
string(
"pointcloud_clusters"));
 
   56     private_node_handle_.param(
"pointcloud_road_perimeter", pointcloud_road_perimeter, 
string(
"pointcloud_road_perimeter"));
 
   57     private_node_handle_.param(
"z_min", extraction->
z_min, 
double(extraction->
z_min));
 
   58     private_node_handle_.param(
"z_max", extraction->
z_max, 
double(extraction->
z_max));
 
   59     private_node_handle_.param(
"threshold", threshold, 
double(threshold));
 
   65     ros::Publisher pub_road = n.advertise<sensor_msgs::PointCloud2>(pointcloud_road.c_str(), 10);
 
   66     ros::Publisher pub_clusters = n.advertise<sensor_msgs::PointCloud2>(pointcloud_clusters.c_str(), 10);
 
   67     ros::Publisher pub_road_perimeter= n.advertise<sensor_msgs::PointCloud2>(pointcloud_road_perimeter.c_str(), 10);
 
   75     tf::TransformListener listener;      
 
   76     tf::TransformBroadcaster br;
 
   78     extraction->
pms.listener_atc_ground_ptr=&listener;
 
   79     extraction->
pms.broadcast_ptr=&br;
 
   82     extraction->
pms.reference_ground_frame=(
char *)(ros::names::remap(
"/atc/vehicle/ground")).c_str();
 
   83     extraction->
pms.pub_frame_name=(
char *)(ros::names::remap(
"/environment/road_frame")).c_str(); 
 
   84     extraction->
pms.threshold=(float)(threshold);
 
   85     extraction->
pms.debug=
false;