#include <Grid3d.h>
|
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 () |
|
Definition at line 29 of file Grid3d.h.
amcl3d::Grid3d::Grid3d |
( |
const double |
sensor_dev | ) |
|
|
explicit |
amcl3d::Grid3d::~Grid3d |
( |
| ) |
|
|
virtual |
void amcl3d::Grid3d::buildGrid3d2WorldTf |
( |
const std::string & |
global_frame_id, |
|
|
tf::StampedTransform & |
tf |
|
) |
| const |
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 |
float amcl3d::Grid3d::computeCloudWeight |
( |
const std::vector< pcl::PointXYZ > & |
points, |
|
|
const float |
tx, |
|
|
const float |
ty, |
|
|
const float |
tz, |
|
|
const float |
a |
|
) |
| const |
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 |
bool amcl3d::Grid3d::isIntoMap |
( |
const float |
x, |
|
|
const float |
y, |
|
|
const float |
z |
|
) |
| const |
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 |
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 |
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.
3D point cloud representation of the map
Definition at line 66 of file Grid3d.h.
std::unique_ptr<GridCell[]> amcl3d::Grid3d::grid_ |
|
private |
uint32_t amcl3d::Grid3d::grid_size_ |
|
private |
uint32_t amcl3d::Grid3d::grid_size_x_ |
|
private |
uint32_t amcl3d::Grid3d::grid_size_y_ |
|
private |
uint32_t amcl3d::Grid3d::grid_size_z_ |
|
private |
uint32_t amcl3d::Grid3d::grid_step_y_ |
|
private |
uint32_t amcl3d::Grid3d::grid_step_z_ |
|
private |
float amcl3d::Grid3d::max_x_ |
|
private |
float amcl3d::Grid3d::max_y_ |
|
private |
float amcl3d::Grid3d::max_z_ |
|
private |
float amcl3d::Grid3d::min_oct_x_ |
|
private |
float amcl3d::Grid3d::min_oct_y_ |
|
private |
float amcl3d::Grid3d::min_oct_z_ |
|
private |
Octomap parameters.
Definition at line 60 of file Grid3d.h.
float amcl3d::Grid3d::one_div_res_ |
|
private |
float amcl3d::Grid3d::resolution_ |
|
private |
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: