#include <grid_map_model.h>
Public Member Functions | |
GridMapModel (const std::string &name) | |
bool | loadParams (const vigir_generic_params::ParameterSet ¶ms=vigir_generic_params::ParameterSet()) override |
Protected Member Functions | |
bool | collision_check (double x, double y, double cos_theta, double sin_theta, double height, double width) const |
Checks if a footstep (represented by its center and orientation) collides with an obstacle. The check is done by recursively testing if either the circumcircle of the foot, the inner circle of the foot or the area in between has an appropriate distance to the nearest obstacle. | |
void | mapCallback (const nav_msgs::OccupancyGridConstPtr &occupancy_grid_map_) |
Protected Attributes | |
int | collision_check_accuracy |
vigir_gridmap_2d::GridMap2D | distance_map |
Definition at line 45 of file grid_map_model.h.
vigir_footstep_planning::GridMapModel::GridMapModel | ( | const std::string & | name | ) |
Definition at line 7 of file grid_map_model.cpp.
bool vigir_footstep_planning::GridMapModel::collision_check | ( | double | x, |
double | y, | ||
double | cos_theta, | ||
double | sin_theta, | ||
double | height, | ||
double | width | ||
) | const [protected] |
Checks if a footstep (represented by its center and orientation) collides with an obstacle. The check is done by recursively testing if either the circumcircle of the foot, the inner circle of the foot or the area in between has an appropriate distance to the nearest obstacle.
x | Global position of the foot in x direction. |
y | Global position of the foot in y direction. |
theta | Global orientation of the foot. |
height | Size of the foot in x direction. |
width | Size of the foot in y direction. obstacle. |
Definition at line 29 of file grid_map_model.cpp.
bool vigir_footstep_planning::GridMapModel::loadParams | ( | const vigir_generic_params::ParameterSet & | params = vigir_generic_params::ParameterSet() | ) | [override] |
Definition at line 12 of file grid_map_model.cpp.
void vigir_footstep_planning::GridMapModel::mapCallback | ( | const nav_msgs::OccupancyGridConstPtr & | occupancy_grid_map_ | ) | [protected] |
Definition at line 21 of file grid_map_model.cpp.
int vigir_footstep_planning::GridMapModel::collision_check_accuracy [protected] |
accuracy: (0) circumcircle of the foot; (1) incircle of the foot; (2) circumcircle and incircle recursivly checked for the whole foot
Definition at line 81 of file grid_map_model.h.
Definition at line 75 of file grid_map_model.h.