Namespaces |
namespace | footstep_planner |
Defines |
#define | DEBUG_HASH 0 |
#define | DEBUG_TIME 0 |
Enumerations |
enum | footstep_planner::Leg { footstep_planner::RIGHT = 0,
footstep_planner::LEFT = 1,
footstep_planner::NOLEG = 2
} |
Functions |
double | footstep_planner::angle_cell_2_state (int angle, int angle_bin_num) |
| Calculate the respective (continuous) angle for a bin.
|
int | footstep_planner::angle_state_2_cell (double angle, int angle_bin_num) |
| Discretize a (continuous) angle into a bin.
|
unsigned int | footstep_planner::calc_hash_tag (int x, int y, int theta, int leg, int max_hash_size) |
double | footstep_planner::cell_2_state (int value, double cell_size) |
| Calculate the respective (continuous) state value for a cell. (Should be used to get a State from a discretized PlanningState.)
|
bool | footstep_planner::collision_check (double x, double y, double theta, double height, double width, int accuracy, const gridmap_2d::GridMap2D &distance_map) |
| 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.
|
double | footstep_planner::cont_val (int length, double cell_size) |
| Calculates the continuous value for a length discretized in cell size.
|
int | footstep_planner::disc_val (double length, double cell_size) |
| Discretize a (continuous) value into cell size.
|
double | footstep_planner::euclidean_distance (int x1, int y1, int x2, int y2) |
double | footstep_planner::euclidean_distance (double x1, double y1, double x2, double y2) |
double | footstep_planner::euclidean_distance_sq (int x1, int y1, int x2, int y2) |
double | footstep_planner::euclidean_distance_sq (double x1, double y1, double x2, double y2) |
double | footstep_planner::grid_cost (int x1, int y1, int x2, int y2, float cell_size) |
unsigned int | footstep_planner::int_hash (int key) |
bool | footstep_planner::pointWithinPolygon (int x, int y, const std::vector< std::pair< int, int > > &edges) |
| Crossing number method to determine whether a point lies within a polygon or not.
|
int | footstep_planner::round (double r) |
| Rounding half towards zero.
|
int | footstep_planner::state_2_cell (float value, float cell_size) |
| Discretize a (continuous) state value into a cell. (Should be used to discretize a State to a PlanningState.)
|
Variables |
static const double | footstep_planner::FLOAT_CMP_THR = 0.0001 |
static const double | footstep_planner::TWO_PI = 2 * M_PI |