00001 /************************************************************************************************** 00002 Software License Agreement (BSD License) 00003 00004 Copyright (c) 2011-2013, LAR toolkit developers - University of Aveiro - http://lars.mec.ua.pt 00005 All rights reserved. 00006 00007 Redistribution and use in source and binary forms, with or without modification, are permitted 00008 provided that the following conditions are met: 00009 00010 *Redistributions of source code must retain the above copyright notice, this list of 00011 conditions and the following disclaimer. 00012 *Redistributions in binary form must reproduce the above copyright notice, this list of 00013 conditions and the following disclaimer in the documentation and/or other materials provided 00014 with the distribution. 00015 *Neither the name of the University of Aveiro nor the names of its contributors may be used to 00016 endorse or promote products derived from this software without specific prior written permission. 00017 00018 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR 00019 IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND 00020 FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR 00021 CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 00022 DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, 00023 DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER 00024 IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT 00025 OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 00026 ***************************************************************************************************/ 00027 #ifndef _NAVIGABILITY_MAP_H_ 00028 #define _NAVIGABILITY_MAP_H_ 00029 00038 #include <stdio.h> 00039 #include <ros/ros.h> 00040 #include <sensor_msgs/PointCloud2.h> 00041 #include <boost/shared_ptr.hpp> 00042 #include <iostream> 00043 #include <Eigen/Core> 00044 00045 #include <algorithm> 00046 #include <stdlib.h> 00047 #include <math.h> 00048 00049 //PCL 00050 #include <pcl_ros/transforms.h> 00051 #include <pcl/ros/conversions.h> 00052 #include <pcl/point_cloud.h> 00053 #include <pcl/point_types.h> 00054 #include <pcl/features/normal_3d.h> 00055 #include <pcl/kdtree/kdtree_flann.h> 00056 #include <pcl/io/pcd_io.h> 00057 #include <pcl/surface/gp3.h> 00058 #include <pcl/filters/passthrough.h> 00059 // 00060 #include <vector> 00061 #include <visualization_msgs/Marker.h> 00062 #include <visualization_msgs/MarkerArray.h> 00063 00064 #include <colormap/colormap.h> 00065 00066 //opencv 00067 #include <cv.h> // open cv general include file 00068 #include <highgui.h> // open cv GUI include file 00069 #include <iostream> // standard C++ I/O 00070 00071 using namespace Eigen; 00072 using namespace std; 00073 00082 class grid_node 00083 { 00084 public: 00085 00087 MatrixXd Matrix_Points; 00088 00090 MatrixXd Angles; 00091 00093 bool has_normal; 00094 00096 double med_angle_X; 00097 00099 double med_angle_Y; 00100 00102 double med_angle_Z; 00103 00105 int num_points; 00106 00108 double Zmed; 00109 00111 double Standard_Deviation_Z; 00112 00114 double Z_confidence; 00115 00117 double angle_confidence_x; 00118 00120 double angle_confidence_y; 00121 00123 double angle_confidence_z; 00124 00126 bool interpolate_z_data; 00127 00129 bool interpolate_normal_data; 00130 00132 std::vector<double> z_difference_neighbours; 00133 00135 std::vector<double> z_confidence_neighbours; 00136 00138 std::vector<double> angleX_difference_neighbours; 00139 00141 std::vector<double> angleY_difference_neighbours; 00142 00144 std::vector<double> angleZ_difference_neighbours; 00145 00147 std::vector<double> angleX_confidence_neighbours; 00148 00150 std::vector<double> angleY_confidence_neighbours; 00151 00153 std::vector<double> angleZ_confidence_neighbours; 00154 00156 std::vector<bool> has_fulldata_direction; //N,NE,E,SE,S,SW,W,NW /only for cell fully data 00157 00159 double z_accessibility; 00160 00162 double angleX_accessibility; 00163 00165 double angleY_accessibility; 00166 00168 double angleZ_accessibility; 00169 00171 double total_accessibility; 00172 00173 00174 grid_node() 00175 { 00176 00177 z_accessibility=0; 00178 00179 angleX_accessibility=0; 00180 angleY_accessibility=0; 00181 angleZ_accessibility=0; 00182 00183 total_accessibility=0; 00184 00185 interpolate_z_data=false; 00186 interpolate_normal_data=false; 00187 has_normal=false; 00188 Z_confidence=0; 00189 00190 angle_confidence_x=0; 00191 angle_confidence_y=0; 00192 angle_confidence_z=0; 00193 00194 num_points=0; 00195 Zmed=-1000; 00196 } 00197 00198 ~grid_node() 00199 {} 00200 00201 private: 00202 00203 }; 00204 00205 //stores a pointer to a dynamically allocated object 00206 typedef boost::shared_ptr<grid_node> grid_nodePtr; 00207 00208 //stores a pointer to a dynamically allocated object 00209 typedef Matrix<grid_nodePtr, Dynamic, Dynamic> Grid; 00210 00211 00212 00221 class Navigability_Map 00222 { 00223 public: 00224 00226 pcl::PointCloud<pcl::Normal>::Ptr normals; 00227 00229 double Xmin_filter; 00230 00232 double Xmax_filter; 00233 00235 double Ymin_filter; 00236 00238 double Ymax_filter; 00239 00241 double Zmax_filter; 00242 00244 double Zmin_filter; 00245 00247 double Radius_neighbors; 00248 00250 int K_neighbors; 00251 00253 int Use_Radius_Search; 00254 00256 int colorrange; 00257 00259 Grid grid; 00260 00262 double Sx; 00263 00265 double Sy; 00266 00268 int total_row; 00269 00271 int total_col; 00272 00274 double default_confidence; 00275 00277 double fator_confidence_neighbour_limit; 00278 00280 int CARaxis_col; 00281 00283 double Zmax_heigh_difference; 00284 00286 double Standard_Deviation_max; 00287 00289 double angleX_max_difference; 00290 00292 double angleY_max_difference; 00293 00295 double angleZ_max_difference; 00296 00298 double Standard_Deviation_anglex_max_confidence; 00299 00301 double Standard_Deviation_angley_max_confidence; 00302 00304 double Standard_Deviation_anglez_max_confidence; 00305 00307 int debug_accessibility; 00308 00313 00314 std::vector<geometry_msgs::Point> polygon_points; 00315 std::vector<geometry_msgs::Point> obstacle_points; 00316 std::vector<cv::Point2f> xy_polygon; 00317 std::vector<cv::Point2f> obstacle_polygon; 00318 00319 MatrixXd Matrix_Cell_inpolygon_rowcol; 00320 MatrixXd Matrix_obstacle_inpolygon_rowcol; 00321 00322 Navigability_Map() 00323 { 00324 debug_accessibility=1; 00325 default_confidence=0.5; 00326 fator_confidence_neighbour_limit=1.5; 00327 00328 Zmax_heigh_difference=0.1; 00329 Standard_Deviation_max=0.2; 00330 00331 angleX_max_difference=0.1; 00332 angleY_max_difference=0.1; 00333 angleZ_max_difference=0.1; 00334 Standard_Deviation_anglex_max_confidence=0.2; 00335 Standard_Deviation_angley_max_confidence=0.2; 00336 Standard_Deviation_anglez_max_confidence=0.2; 00337 00338 Radius_neighbors=0.4; 00339 K_neighbors=10; 00340 Use_Radius_Search=1; 00341 00342 Xmin_filter=0; 00343 Xmax_filter=22.5; 00344 Ymin_filter=-22.5; 00345 Ymax_filter=22.5; 00346 Zmax_filter=2; 00347 Zmin_filter=-15; 00348 00349 Sx=0.2; 00350 Sy=0.2; 00351 colorrange=64; 00352 } 00353 00354 ~Navigability_Map() 00355 {} 00356 00364 void Filter_PointCloud(pcl::PointCloud<pcl::PointXYZ>::Ptr &cloud_in,pcl::PointCloud<pcl::PointXYZ>::Ptr &pc_filter); 00365 00370 void Normal_Estimation(pcl::PointCloud<pcl::PointXYZ>::Ptr &cloud); 00371 00376 void inicialize_grid(void); 00377 00385 void setGrid_parameter(double max_Xval,double max_Yval); 00386 00393 void setGrid_data(pcl::PointCloud<pcl::PointXYZ>& cloud); 00394 00395 00400 void calcGrid_data(void); 00401 00406 void fill_data_cells(void); 00407 00418 std::vector<grid_nodePtr> cell_neighbours(int row_pos, int col_pos, int &empty_neighbours, int &number_neighbours); 00419 00424 void set_Cells_accessibility(void); 00425 00430 void polygon_groundtruth(void); 00431 void getCell_inpolygon(void); 00432 void dataCell_inpolygon(void); 00433 00434 00435 00436 private: 00437 00438 }; 00439 00440 00441 #endif