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 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 
00036 
00037 #ifndef TRAJECTORY_ROLLOUT_VOXEL_WORLD_MODEL_H_
00038 #define TRAJECTORY_ROLLOUT_VOXEL_WORLD_MODEL_H_
00039 #include <vector>
00040 #include <list>
00041 #include <cfloat>
00042 #include <geometry_msgs/Point32.h>
00043 #include <costmap_2d/observation.h>
00044 #include <world_model.h>
00045 
00046 #include <pcl/point_types.h>
00047 #include <pcl/point_cloud.h>
00048 
00049 
00050 #include <voxel_grid/voxel_grid.h>
00051 
00052 namespace iri_ackermann_local_planner {
00058   class VoxelGridModel : public WorldModel {
00059     public:
00073       VoxelGridModel(double size_x, double size_y, double size_z, double xy_resolution, double z_resolution,
00074           double origin_x, double origin_y, double origin_z, double max_z, double obstacle_range);
00075 
00079       virtual ~VoxelGridModel(){}
00080 
00089       virtual double footprintCost(const geometry_msgs::Point& position, const std::vector<geometry_msgs::Point>& footprint,
00090           double inscribed_radius, double circumscribed_radius);
00091 
00098       void updateWorld(const std::vector<geometry_msgs::Point>& footprint,
00099           const std::vector<costmap_2d::Observation>& observations, const std::vector<PlanarLaserScan>& laser_scans);
00100 
00101       void getPoints(pcl::PointCloud<pcl::PointXYZ>& cloud);
00102 
00103     private:
00112       double lineCost(int x0, int x1, int y0, int y1);
00113 
00120       double pointCost(int x, int y);
00121 
00122       void removePointsInScanBoundry(const PlanarLaserScan& laser_scan, double raytrace_range);
00123 
00124       inline bool worldToMap3D(double wx, double wy, double wz, unsigned int& mx, unsigned int& my, unsigned int& mz){
00125         if(wx < origin_x_ || wy < origin_y_ || wz < origin_z_)
00126           return false;
00127         mx = (int) ((wx - origin_x_) / xy_resolution_);
00128         my = (int) ((wy - origin_y_) / xy_resolution_);
00129         mz = (int) ((wz - origin_z_) / z_resolution_);
00130         return true;
00131       }
00132 
00133       inline bool worldToMap2D(double wx, double wy, unsigned int& mx, unsigned int& my){
00134         if(wx < origin_x_ || wy < origin_y_)
00135           return false;
00136         mx = (int) ((wx - origin_x_) / xy_resolution_);
00137         my = (int) ((wy - origin_y_) / xy_resolution_);
00138         return true;
00139       }
00140 
00141       inline void mapToWorld3D(unsigned int mx, unsigned int my, unsigned int mz, double& wx, double& wy, double& wz){
00142         
00143         wx = origin_x_ + (mx + 0.5) * xy_resolution_;
00144         wy = origin_y_ + (my + 0.5) * xy_resolution_;
00145         wz = origin_z_ + (mz + 0.5) * z_resolution_;
00146       }
00147 
00148       inline void mapToWorld2D(unsigned int mx, unsigned int my, double& wx, double& wy){
00149         
00150         wx = origin_x_ + (mx + 0.5) * xy_resolution_;
00151         wy = origin_y_ + (my + 0.5) * xy_resolution_;
00152       }
00153 
00154       inline double dist(double x0, double y0, double z0, double x1, double y1, double z1){
00155         return sqrt((x1 - x0) * (x1 - x0) + (y1 - y0) * (y1 - y0) + (z1 - z0) * (z1 - z0));
00156       }
00157 
00158       inline void insert(pcl::PointXYZ pt){
00159         unsigned int cell_x, cell_y, cell_z;
00160         if(!worldToMap3D(pt.x, pt.y, pt.z, cell_x, cell_y, cell_z))
00161           return;
00162         obstacle_grid_.markVoxel(cell_x, cell_y, cell_z);
00163       }
00164 
00165       voxel_grid::VoxelGrid obstacle_grid_;
00166       double xy_resolution_;
00167       double z_resolution_;
00168       double origin_x_;
00169       double origin_y_;
00170       double origin_z_;
00171       double max_z_;  
00172       double sq_obstacle_range_;  
00173 
00174   };
00175 };
00176 #endif