Classes | Public Member Functions | Private Member Functions | Private Attributes | List of all members
amcl3d::Grid3d Class Reference

#include <Grid3d.h>

Classes

struct  GridCell
 3D probabilistic grid cell More...
 

Public Member Functions

void buildGrid3d2WorldTf (const std::string &global_frame_id, tf::StampedTransform &tf) const
 
bool buildGridSliceMsg (const float z, nav_msgs::OccupancyGrid &msg) const
 
bool buildMapPointCloudMsg (sensor_msgs::PointCloud2 &msg) const
 
float computeCloudWeight (const std::vector< pcl::PointXYZ > &points, const float tx, const float ty, const float tz, const float a) const
 
void getMinOctomap (float &x, float &y, float &z) const
 
 Grid3d (const double sensor_dev)
 
bool isIntoMap (const float x, const float y, const float z) const
 
bool open (const std::string &map_path)
 
virtual ~Grid3d ()
 

Private Member Functions

void computeGrid ()
 
void computePointCloud ()
 
bool loadGrid (const std::string &grid_path)
 
bool loadOctomap (const std::string &map_path)
 
uint32_t point2grid (const float x, const float y, const float z) const
 
bool saveGrid (const std::string &grid_path)
 

Private Attributes

pcl::PointCloud< pcl::PointXYZ >::Ptr cloud_
 3D point cloud representation of the map More...
 
std::unique_ptr< GridCell[]> grid_
 
uint32_t grid_size_
 
uint32_t grid_size_x_
 
uint32_t grid_size_y_
 
uint32_t grid_size_z_
 
uint32_t grid_step_y_
 
uint32_t grid_step_z_
 
float max_x_
 
float max_y_
 
float max_z_
 
float min_oct_x_
 
float min_oct_y_
 
float min_oct_z_
 
std::unique_ptr< octomap::OcTreeoctomap_
 Octomap parameters. More...
 
float one_div_res_
 
float resolution_
 
double sensor_dev_
 Init parameter. More...
 

Detailed Description

Definition at line 29 of file Grid3d.h.

Constructor & Destructor Documentation

amcl3d::Grid3d::Grid3d ( const double  sensor_dev)
explicit

Definition at line 25 of file Grid3d.cpp.

amcl3d::Grid3d::~Grid3d ( )
virtual

Definition at line 29 of file Grid3d.cpp.

Member Function Documentation

void amcl3d::Grid3d::buildGrid3d2WorldTf ( const std::string &  global_frame_id,
tf::StampedTransform tf 
) const

Definition at line 113 of file Grid3d.cpp.

bool amcl3d::Grid3d::buildGridSliceMsg ( const float  z,
nav_msgs::OccupancyGrid &  msg 
) const

Extract max probability

Copy data into grid msg and scale the probability to [0, 100]

Definition at line 61 of file Grid3d.cpp.

bool amcl3d::Grid3d::buildMapPointCloudMsg ( sensor_msgs::PointCloud2 &  msg) const

Definition at line 101 of file Grid3d.cpp.

float amcl3d::Grid3d::computeCloudWeight ( const std::vector< pcl::PointXYZ > &  points,
const float  tx,
const float  ty,
const float  tz,
const float  a 
) const

Definition at line 122 of file Grid3d.cpp.

void amcl3d::Grid3d::computeGrid ( )
private

Alloc the 3D grid

Setup kdtree

Compute the distance to the closest point of the grid

Definition at line 302 of file Grid3d.cpp.

void amcl3d::Grid3d::computePointCloud ( )
private

Load the octomap in PCL for easy nearest neighborhood computation The point-cloud is shifted to have (0,0,0) as min values

Definition at line 215 of file Grid3d.cpp.

void amcl3d::Grid3d::getMinOctomap ( float &  x,
float &  y,
float &  z 
) const

Definition at line 159 of file Grid3d.cpp.

bool amcl3d::Grid3d::isIntoMap ( const float  x,
const float  y,
const float  z 
) const

Definition at line 154 of file Grid3d.cpp.

bool amcl3d::Grid3d::loadGrid ( const std::string &  grid_path)
private

Read grid general info

Read grid cells

Definition at line 265 of file Grid3d.cpp.

bool amcl3d::Grid3d::loadOctomap ( const std::string &  map_path)
private

Definition at line 166 of file Grid3d.cpp.

bool amcl3d::Grid3d::open ( const std::string &  map_path)

Load octomap

Compute the point-cloud associated to the octomap

Try to load the associated grid-map from file

Compute the gridMap using kdtree search over the point-cloud

Save grid on file

Definition at line 33 of file Grid3d.cpp.

uint32_t amcl3d::Grid3d::point2grid ( const float  x,
const float  y,
const float  z 
) const
inlineprivate

Definition at line 353 of file Grid3d.cpp.

bool amcl3d::Grid3d::saveGrid ( const std::string &  grid_path)
private

Write grid general info

Write grid cells

Definition at line 239 of file Grid3d.cpp.

Member Data Documentation

pcl::PointCloud<pcl::PointXYZ>::Ptr amcl3d::Grid3d::cloud_
private

3D point cloud representation of the map

Definition at line 66 of file Grid3d.h.

std::unique_ptr<GridCell[]> amcl3d::Grid3d::grid_
private

Definition at line 76 of file Grid3d.h.

uint32_t amcl3d::Grid3d::grid_size_
private

Definition at line 77 of file Grid3d.h.

uint32_t amcl3d::Grid3d::grid_size_x_
private

Definition at line 77 of file Grid3d.h.

uint32_t amcl3d::Grid3d::grid_size_y_
private

Definition at line 77 of file Grid3d.h.

uint32_t amcl3d::Grid3d::grid_size_z_
private

Definition at line 77 of file Grid3d.h.

uint32_t amcl3d::Grid3d::grid_step_y_
private

Definition at line 78 of file Grid3d.h.

uint32_t amcl3d::Grid3d::grid_step_z_
private

Definition at line 78 of file Grid3d.h.

float amcl3d::Grid3d::max_x_
private

Definition at line 61 of file Grid3d.h.

float amcl3d::Grid3d::max_y_
private

Definition at line 61 of file Grid3d.h.

float amcl3d::Grid3d::max_z_
private

Definition at line 61 of file Grid3d.h.

float amcl3d::Grid3d::min_oct_x_
private

Definition at line 62 of file Grid3d.h.

float amcl3d::Grid3d::min_oct_y_
private

Definition at line 62 of file Grid3d.h.

float amcl3d::Grid3d::min_oct_z_
private

Definition at line 62 of file Grid3d.h.

std::unique_ptr<octomap::OcTree> amcl3d::Grid3d::octomap_
private

Octomap parameters.

Definition at line 60 of file Grid3d.h.

float amcl3d::Grid3d::one_div_res_
private

Definition at line 63 of file Grid3d.h.

float amcl3d::Grid3d::resolution_
private

Definition at line 63 of file Grid3d.h.

double amcl3d::Grid3d::sensor_dev_
private

Init parameter.

Definition at line 57 of file Grid3d.h.


The documentation for this class was generated from the following files:


amcl3d
Author(s): Francisco J.Perez-Grau
autogenerated on Sun Sep 15 2019 04:08:05