Go to the documentation of this file.00001 #ifndef OCCUPANCY_GRID_OCCUPANCY_GRID_
00002 #define OCCUPANCY_GRID_OCCUPANCY_GRID_
00003
00004 #include <pcl/point_cloud.h>
00005 #include <pcl/point_types.h>
00006 #include <sensor_msgs/PointCloud.h>
00007
00012 namespace occupancy_grid
00013 {
00014 class OccupancyGrid
00015 {
00016 public:
00023 OccupancyGrid(float center_x, float center_y, float center_z,
00024 float size_x, float size_y, float size_z,
00025 float res_x, float res_y, float res_z);
00026
00027 ~OccupancyGrid();
00028
00029 void fillOccupancyGrid(const sensor_msgs::PointCloud cloud);
00030
00031 sensor_msgs::PointCloud gridToPoints();
00032
00033 unsigned int nX();
00034 unsigned int nY();
00035 unsigned int nZ();
00036
00037 uint32_t* getData();
00038
00039 private:
00040 unsigned int nx_, ny_, nz_;
00041 float size_x_, size_y_, size_z_;
00042 float center_x_, center_y_, center_z_;
00043 float res_x_, res_y_, res_z_;
00044 uint32_t *data_;
00045 };
00046 };
00047
00048 #endif
00049
00050