main.cpp
Go to the documentation of this file.
1 /**************************************************************************************************
2  Software License Agreement (BSD License)
3 
4  Copyright (c) 2011-2013, LAR toolkit developers - University of Aveiro - http://lars.mec.ua.pt
5  All rights reserved.
6 
7  Redistribution and use in source and binary forms, with or without modification, are permitted
8  provided that the following conditions are met:
9 
10  *Redistributions of source code must retain the above copyright notice, this list of
11  conditions and the following disclaimer.
12  *Redistributions in binary form must reproduce the above copyright notice, this list of
13  conditions and the following disclaimer in the documentation and/or other materials provided
14  with the distribution.
15  *Neither the name of the University of Aveiro nor the names of its contributors may be used to
16  endorse or promote products derived from this software without specific prior written permission.
17 
18  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR
19  IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND
20  FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
21  CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
22  DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
23  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER
24  IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT
25  OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 ***************************************************************************************************/
28 #include "representation_rviz.h"
29 #include <pcl_conversions/pcl_conversions.h>
30 
42 //GLOBAL VARIABLES
44 bool cloud_arrived=false;
45 
46 ros::Publisher elevation_map_pub;
47 ros::Publisher normals_pub;
48 ros::Publisher accessibility_map_pub;
49 ros::Publisher polygon_pub;
50 ros::Publisher obstacle_pub;
51 
52 pcl::PointCloud<pcl::PointXYZ>::Ptr pc_filter (new pcl::PointCloud<pcl::PointXYZ>);
53 
54 tf::TransformListener *p_listener;
55 
62 void pointcloud_cb (sensor_msgs::PointCloud2 pcmsg_in)
63 {
64  visualization_msgs::MarkerArray grid_markers_elavationmap, accessibility_markers;
65  visualization_msgs::Marker marker_normals;
66  visualization_msgs::Marker marker_polygon;
67  visualization_msgs::Marker marker_obstacle;
68 
69  //Cloud received
70  pcl::PointCloud<pcl::PointXYZ> pc_in;
71  pcl::fromROSMsg(pcmsg_in,pc_in);
72  pcl::PCLPointCloud2 pcl_pc;
73  pcl_conversions::toPCL(pcmsg_in, pcl_pc);
74  pcl::fromPCLPointCloud2(pcl_pc, pc_in);
75 
76 
77  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_in (new pcl::PointCloud<pcl::PointXYZ>);
78  *cloud_in=pc_in;
79 
80  //filter cloud
81  g_NavMap->Filter_PointCloud(cloud_in,pc_filter);
82 
83  //Normal Estimation
84  std::cout<<"Normal Estimation"<<std::endl;
85  g_NavMap->Normal_Estimation(pc_filter);
86 
87  double max_Xval=g_NavMap->Xmax_filter; //X max range value
88  double max_Yval=max(abs(g_NavMap->Ymin_filter),g_NavMap->Ymax_filter); //y max range value
89 
90  //seting the grid parameter
91  g_NavMap->setGrid_parameter(max_Xval,max_Yval);
92 
93  //inicialize grid
94  g_NavMap->inicialize_grid();
95 
96  //seting grid data
97  g_NavMap->setGrid_data(*pc_filter);
98 
99  //calc grid data
100  g_NavMap->calcGrid_data();
101 
102  //fill empty cells
103  g_NavMap->fill_data_cells();
104 
105  //calc Cells_accessibility
106  g_NavMap->set_Cells_accessibility();
107 
108  //_______________
109  // |
110  // markers |
111  //_______________|
112 
113  //elevation map;
114  grid_markers_elavationmap.markers=create_Markers_ElavationMap(*g_NavMap, pc_filter->header.frame_id );
115  //normals
116  marker_normals=create_Markers_Normals(*g_NavMap, pc_filter->header.frame_id);
117  //accessibility
118  accessibility_markers.markers=create_Markers_AccessibilityMap(*g_NavMap, pc_filter->header.frame_id);
119 
120 // publish
121  elevation_map_pub.publish(grid_markers_elavationmap);
122  normals_pub.publish(marker_normals);
123  accessibility_map_pub.publish(accessibility_markers);
124 
125 
126  //_______________
127  // |
128  // Ground truth |
129  //_______________|
130 // g_NavMap->polygon_groundtruth();
131 // g_NavMap->getCell_inpolygon();
132 // g_NavMap->dataCell_inpolygon();
133 //
134 // marker_polygon=create_Markers_Polygon(*g_NavMap, pc_filter->header.frame_id);
135 // marker_obstacle=create_Markers_Obstacle(*g_NavMap, pc_filter->header.frame_id);
136 // polygon_pub.publish(marker_polygon);
137 // obstacle_pub.publish(marker_obstacle);
138 
139 
140 
141  cloud_arrived=true;
142 }
143 
144 int main(int argc, char **argv)
145 {
146  ros::init(argc, argv, "navigability_map");
147  ros::NodeHandle n("~");
148 
149  tf::TransformListener listener(n,ros::Duration(1000));
150  p_listener=&listener;
151 
152 // Declare the class
153  Navigability_Map navmap;
154  g_NavMap=&navmap;
155 
156  double output_freq;
157 
158  //Seting Param
159  n.param("output_frequency", output_freq, 200.0);
160  n.param("PointCLoud_Xmin_filter",g_NavMap->Xmin_filter,0.0);
161  n.param("PointCLoud_Xmax_filter",g_NavMap->Xmax_filter,22.5);
162  n.param("PointCLoud_Ymax_filter",g_NavMap->Ymax_filter,22.5);
163  n.param("PointCLoud_Ymin_filter",g_NavMap->Ymin_filter,-22.5);
164  n.param("PointCLoud_Zmin_filter",g_NavMap->Zmin_filter,-15.0);
165  n.param("PointCLoud_Zmax_filter",g_NavMap->Zmax_filter,2.0);
166  n.param("Grid_Sx",g_NavMap->Sx,0.2);
167  n.param("Grid_Sy",g_NavMap->Sy,0.2);
168  n.param("Radius_neighbors",g_NavMap->Radius_neighbors,0.3);
169  n.param("K_neighbors",g_NavMap->K_neighbors,10);
170  n.param("Use_Radius_Search",g_NavMap->Use_Radius_Search,1);
171  n.param("Zmax_heigh_difference",g_NavMap->Zmax_heigh_difference,0.1);
172  n.param("angleX_max_difference",g_NavMap->angleX_max_difference,0.1);
173  n.param("angleY_max_difference",g_NavMap->angleY_max_difference,0.1);
174  n.param("angleZ_max_difference",g_NavMap->angleZ_max_difference,0.1);
175  n.param("debug_accessibility",g_NavMap->debug_accessibility,1);
176  n.param("default_confidence",g_NavMap->default_confidence,0.5);
177  n.param("fator_confidence_neighbour_limit",g_NavMap->fator_confidence_neighbour_limit,1.5);
178  n.param("Standard_Deviation_max_confidence",g_NavMap->Standard_Deviation_max,0.2);
179  n.param("Standard_Deviation_anglex_max_confidence",g_NavMap->Standard_Deviation_anglex_max_confidence,0.2);
180  n.param("Standard_Deviation_angley_max_confidence",g_NavMap->Standard_Deviation_angley_max_confidence,0.2);
181  n.param("Standard_Deviation_anglez_max_confidence",g_NavMap->Standard_Deviation_anglez_max_confidence,0.2);
182 
183  // declare the subsriber
184  ros::Subscriber sub_phiversion = n.subscribe ("/pointcloud0", 1, pointcloud_cb);
185 
186 // declare advertiser
187  //normals
188  normals_pub = n.advertise<visualization_msgs::Marker>("/normals", 1);
189  //pointcloud filter
190  ros::Publisher pub = n.advertise<sensor_msgs::PointCloud2>("/pc_filter_navmap", 1);
191  //maps
192  elevation_map_pub = n.advertise<visualization_msgs::MarkerArray>("/elevation_map", 1);
193  accessibility_map_pub = n.advertise<visualization_msgs::MarkerArray>("/accessibility_map", 1);
194 
195  //ground truth
196  polygon_pub = n.advertise<visualization_msgs::Marker>("/polygon", 1);
197  obstacle_pub = n.advertise<visualization_msgs::Marker>("/obstacle", 1);
198 
199  ros::Rate loop_rate(output_freq);
200 
201  while (n.ok())
202  {
203  ros::spinOnce();
204 
205  if (cloud_arrived)
206  {
207  sensor_msgs::PointCloud2 pcmsg_out;
208  pcl::toROSMsg(*pc_filter, pcmsg_out);
209  pcmsg_out.header.stamp = ros::Time::now();
210  //publish the pointcloud
211  pub.publish(pcmsg_out);
212 
213  cloud_arrived=false;
214  }
215  loop_rate.sleep();
216  }
217 }
int debug_accessibility
Which accessibility map should be draw.
int Use_Radius_Search
1 - to use the radius search ; 0 - to use the number of neighbours search
visualization_msgs::Marker create_Markers_Normals(Navigability_Map &nav_map, std::string grid_frame)
Function to generate marker for the visualization of the Normals on the Class Navigability_Map.
double Ymin_filter
Min distance to be consider in the Y direction of the PointCloud.
double Sx
The X dimension of the cell.
Navigability_Map * g_NavMap
Definition: main.cpp:43
ros::Publisher normals_pub
Definition: main.cpp:47
pcl::PointCloud< pcl::PointXYZ >::Ptr pc_filter(new pcl::PointCloud< pcl::PointXYZ >)
double Standard_Deviation_anglez_max_confidence
Normalization constant for the Angle Z confidence value.
void inicialize_grid(void)
Function that inicialize the Grid with default data.
int main(int argc, char **argv)
Definition: main.cpp:144
double angleX_max_difference
Threshold for the Angle X difference between cells.
void Filter_PointCloud(pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud_in, pcl::PointCloud< pcl::PointXYZ >::Ptr &pc_filter)
Function that filters the PointCloud. Filters the point cloud receiveid, the filtered PointCloud is s...
double Xmax_filter
Max distance to be consider in the X direction of the PointCloud.
void calcGrid_data(void)
Function that calculates mean values and confidence of the x,y,z points and normals of the PointCloud...
ros::Publisher accessibility_map_pub
Definition: main.cpp:48
double angleZ_max_difference
Threshold for the Angle Z difference between cells.
tf::TransformListener * p_listener
Definition: main.cpp:54
double Standard_Deviation_max
Normalization constant for the Z confidence value.
double Zmax_heigh_difference
Threshold for the Z difference between cells.
double Sy
The Y dimension of the cell.
ros::Publisher polygon_pub
Definition: main.cpp:49
double Radius_neighbors
The radius of the neighbours search to estimate the normals in the PointCloud.
double Standard_Deviation_anglex_max_confidence
Normalization constant for the Angle X confidence value.
void fill_data_cells(void)
Function that interpolates data to empty cells.
double default_confidence
Default confidence for a cell with one point.
void pointcloud_cb(sensor_msgs::PointCloud2 pcmsg_in)
Callback from the Pointcloud subscribed topic This calback filter the pointcloud uses de Navigability...
Definition: main.cpp:62
bool cloud_arrived
Definition: main.cpp:44
vector< visualization_msgs::Marker > create_Markers_AccessibilityMap(Navigability_Map &nav_map, std::string grid_frame)
Function to generate marker for the visualization of the Accessibility Map on the Class Navigability_...
double Zmin_filter
Max distance to be consider in the Z direction of the PointCloud.
double Standard_Deviation_angley_max_confidence
Normalization constant for the Angle Y confidence value.
void setGrid_data(pcl::PointCloud< pcl::PointXYZ > &cloud)
Function that sets the data to the grid based on the PointCloud information. Saves the x...
int K_neighbors
The number of neighbours search to estimate the normals in the PointCloud.
double Ymax_filter
Max distance to be consider in the Y direction of the PointCloud.
double Zmax_filter
Min distance to be consider in the Z direction of the PointCloud.
void set_Cells_accessibility(void)
Function that sets the accessibility of the cells.
ros::Publisher obstacle_pub
Definition: main.cpp:50
void setGrid_parameter(double max_Xval, double max_Yval)
Function that sets the parameters to generate the grid. Grid Parameter: Total of row, cols and the center col.
double angleY_max_difference
Threshold for the Angle Y difference between cells.
ros::Publisher elevation_map_pub
Definition: main.cpp:46
double Xmin_filter
Min distance to be consider in the X direction of the PointCloud.
void Normal_Estimation(pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud)
Computes the normal estimation for a PointCloud.
vector< visualization_msgs::Marker > create_Markers_ElavationMap(Navigability_Map &nav_map, std::string grid_frame)
Function to generate marker for the visualization of the Elevation Map on the Class Navigability_Map...
Declarion functions and class to handle the visualization markers of the Class Navigability_Map.
double fator_confidence_neighbour_limit
Limit of the max difference between a cell and a neighbour cell.


navigability_map
Author(s): Diogo Matos
autogenerated on Mon Mar 2 2015 01:32:29