#include <occupancy_grid.h>
Public Member Functions | |
void | addCollisionCuboid (double origin_x, double origin_y, double origin_z, double size_x, double size_y, double size_z) |
manually add a cuboid to the collision map | |
void | addPointsToField (const std::vector< btVector3 > &points) |
double | getCell (int *xyz) |
get the cell's distance to the nearest obstacle in meters | |
unsigned char | getCell (int x, int y, int z) |
get the cell's distance to the nearest obstacle in cells | |
const distance_field::PropagationDistanceField * | getDistanceFieldPtr () |
return a pointer to the distance field | |
void | getGridSize (short unsigned int *dims) |
get the dimensions of the grid | |
void | getGridSize (int &dim_x, int &dim_y, int &dim_z) |
get the dimensions of the grid | |
void | getOrigin (double &wx, double &wy, double &wz) |
get the origin of the world (meters) | |
std::string | getReferenceFrame () |
double | getResolution () |
get the resolution of the world (meters) | |
void | getVoxelsInBox (const geometry_msgs::Pose &pose, const std::vector< double > &dim, std::vector< btVector3 > &voxels) |
void | getWorldSize (double &dim_x, double &dim_y, double &dim_z) |
get the dimensions of the world (meters) | |
void | gridToWorld (int x, int y, int z, double &wx, double &wy, double &wz) |
convert grid cell coords into world coords | |
bool | isInBounds (int x, int y, int z) |
check if {x,y,z} is in bounds of the grid | |
OccupancyGrid (double dim_x, double dim_y, double dim_z, double resolution, double origin_x, double origin_y, double origin_z) | |
Constructor. | |
OccupancyGrid () | |
Default constructor - sets default values. | |
void | printGridFromBinaryFile (std::string filename) |
bool | saveGridToBinaryFile (std::string filename) |
void | setOrigin (double wx, double wy, double wz) |
set the origin of the world (meters) | |
void | setResolution (double resolution_m) |
set the resolution of the world (meters) | |
void | setWorldSize (double dim_x, double dim_y, double dim_z) |
set the dimensions of the world (meters) | |
void | updateFromCollisionMap (const mapping_msgs::CollisionMap &collision_map) |
update the distance field from the collision_map | |
void | visualize () |
display distance field visualizations to rviz | |
void | worldToGrid (double wx, double wy, double wz, int &x, int &y, int &z) |
convert world coords into grid cell coords | |
~OccupancyGrid () | |
destructor | |
Private Attributes | |
std::vector< btVector3 > | cuboid_points_ |
distance_field::PropagationDistanceField * | grid_ |
double | grid_resolution_ |
int | grid_size_ [3] |
double | origin_ [3] |
double | prop_distance_ |
std::string | reference_frame_ |
double | world_size_ [3] |
Definition at line 45 of file occupancy_grid.h.
OccupancyGrid::OccupancyGrid | ( | ) |
Default constructor - sets default values.
Definition at line 38 of file occupancy_grid.cpp.
OccupancyGrid::OccupancyGrid | ( | double | dim_x, | |
double | dim_y, | |||
double | dim_z, | |||
double | resolution, | |||
double | origin_x, | |||
double | origin_y, | |||
double | origin_z | |||
) |
Constructor.
dimension | of grid along X | |
dimension | of grid along Y | |
dimension | of grid along Z | |
resolution | of grid (meters) | |
X | coordinate of origin (meters) | |
Y | coordinate of origin (meters) | |
Z | coordinate of origin (meters) |
Definition at line 63 of file occupancy_grid.cpp.
OccupancyGrid::~OccupancyGrid | ( | ) |
destructor
Definition at line 87 of file occupancy_grid.cpp.
void OccupancyGrid::addCollisionCuboid | ( | double | origin_x, | |
double | origin_y, | |||
double | origin_z, | |||
double | size_x, | |||
double | size_y, | |||
double | size_z | |||
) |
manually add a cuboid to the collision map
X_origin_of_cuboid | ||
Y_origin_of_cuboid | ||
Z_origin_of_cuboid | ||
size | along the X dimension (meters) | |
size | along the Y dimension (meters) | |
size | along the Z dimension (meters) |
Definition at line 155 of file occupancy_grid.cpp.
void OccupancyGrid::addPointsToField | ( | const std::vector< btVector3 > & | points | ) | [inline] |
Definition at line 182 of file occupancy_grid.h.
double OccupancyGrid::getCell | ( | int * | xyz | ) | [inline] |
get the cell's distance to the nearest obstacle in meters
Definition at line 164 of file occupancy_grid.h.
unsigned char OccupancyGrid::getCell | ( | int | x, | |
int | y, | |||
int | z | |||
) | [inline] |
get the cell's distance to the nearest obstacle in cells
Definition at line 159 of file occupancy_grid.h.
const distance_field::PropagationDistanceField * OccupancyGrid::getDistanceFieldPtr | ( | ) |
return a pointer to the distance field
Definition at line 207 of file occupancy_grid.cpp.
void OccupancyGrid::getGridSize | ( | short unsigned int * | dims | ) |
get the dimensions of the grid
void OccupancyGrid::getGridSize | ( | int & | dim_x, | |
int & | dim_y, | |||
int & | dim_z | |||
) |
get the dimensions of the grid
Definition at line 92 of file occupancy_grid.cpp.
void OccupancyGrid::getOrigin | ( | double & | wx, | |
double & | wy, | |||
double & | wz | |||
) |
get the origin of the world (meters)
Definition at line 122 of file occupancy_grid.cpp.
std::string OccupancyGrid::getReferenceFrame | ( | ) | [inline] |
Definition at line 177 of file occupancy_grid.h.
double OccupancyGrid::getResolution | ( | ) |
get the resolution of the world (meters)
Definition at line 134 of file occupancy_grid.cpp.
void OccupancyGrid::getVoxelsInBox | ( | const geometry_msgs::Pose & | pose, | |
const std::vector< double > & | dim, | |||
std::vector< btVector3 > & | voxels | |||
) |
Definition at line 177 of file occupancy_grid.cpp.
void OccupancyGrid::getWorldSize | ( | double & | dim_x, | |
double & | dim_y, | |||
double & | dim_z | |||
) |
get the dimensions of the world (meters)
Definition at line 108 of file occupancy_grid.cpp.
void OccupancyGrid::gridToWorld | ( | int | x, | |
int | y, | |||
int | z, | |||
double & | wx, | |||
double & | wy, | |||
double & | wz | |||
) | [inline] |
convert grid cell coords into world coords
Definition at line 149 of file occupancy_grid.h.
bool OccupancyGrid::isInBounds | ( | int | x, | |
int | y, | |||
int | z | |||
) | [inline] |
check if {x,y,z} is in bounds of the grid
Definition at line 169 of file occupancy_grid.h.
void OccupancyGrid::printGridFromBinaryFile | ( | std::string | filename | ) |
Definition at line 212 of file occupancy_grid.cpp.
bool OccupancyGrid::saveGridToBinaryFile | ( | std::string | filename | ) |
Definition at line 253 of file occupancy_grid.cpp.
void OccupancyGrid::setOrigin | ( | double | wx, | |
double | wy, | |||
double | wz | |||
) |
set the origin of the world (meters)
Definition at line 115 of file occupancy_grid.cpp.
void OccupancyGrid::setResolution | ( | double | resolution_m | ) |
set the resolution of the world (meters)
Definition at line 129 of file occupancy_grid.cpp.
void OccupancyGrid::setWorldSize | ( | double | dim_x, | |
double | dim_y, | |||
double | dim_z | |||
) |
set the dimensions of the world (meters)
Definition at line 99 of file occupancy_grid.cpp.
void OccupancyGrid::updateFromCollisionMap | ( | const mapping_msgs::CollisionMap & | collision_map | ) |
update the distance field from the collision_map
Definition at line 139 of file occupancy_grid.cpp.
void OccupancyGrid::visualize | ( | ) |
display distance field visualizations to rviz
Definition at line 200 of file occupancy_grid.cpp.
void OccupancyGrid::worldToGrid | ( | double | wx, | |
double | wy, | |||
double | wz, | |||
int & | x, | |||
int & | y, | |||
int & | z | |||
) | [inline] |
convert world coords into grid cell coords
Definition at line 154 of file occupancy_grid.h.
std::vector<btVector3> OccupancyGrid::cuboid_points_ [private] |
Definition at line 146 of file occupancy_grid.h.
distance_field::PropagationDistanceField* OccupancyGrid::grid_ [private] |
Definition at line 144 of file occupancy_grid.h.
double OccupancyGrid::grid_resolution_ [private] |
Definition at line 138 of file occupancy_grid.h.
int OccupancyGrid::grid_size_[3] [private] |
Definition at line 141 of file occupancy_grid.h.
double OccupancyGrid::origin_[3] [private] |
Definition at line 137 of file occupancy_grid.h.
double OccupancyGrid::prop_distance_ [private] |
Definition at line 140 of file occupancy_grid.h.
std::string OccupancyGrid::reference_frame_ [private] |
Definition at line 143 of file occupancy_grid.h.
double OccupancyGrid::world_size_[3] [private] |
Definition at line 139 of file occupancy_grid.h.