Classes | Typedefs | Enumerations | Functions | Variables
footstep_planner Namespace Reference

Classes

struct  environment_params
class  EuclideanHeuristic
 Determining the heuristic value by the euclidean distance between two states. More...
class  EuclStepCostHeuristic
 Determining the heuristic value by the euclidean distance between two states, the expected step costs to get from one state to the other and the difference between the orientation of the two states multiplied by some cost factor. (NOTE: choosing this angular difference cost might overestimate the heuristic value.) More...
class  Footstep
 A class representing a footstep (i.e. a translation and rotation of a specific foot with respect to the supporting leg) that can be performed by a humanoid robot. More...
class  FootstepNavigation
 A class to control the performance of a planned footstep path on the NAO robot. More...
class  FootstepPlanner
 A class to control the interaction between ROS and the footstep planner. More...
class  FootstepPlannerEnvironment
 A class defining a footstep planner environment for humanoid robots used by the SBPL to perform planning tasks. More...
class  FootstepPlannerNode
 Wrapper class for FootstepPlanner, providing callbacks for the node functionality. More...
class  Heuristic
 An abstract super class providing methods necessary to be used as heuristic function within the FootstepPlanner. More...
class  PathCostHeuristic
 Determining the heuristic value by calculating a 2D path from each grid cell of the map to the goal and using the path length as expected distance. More...
class  PlanningState
 A class representing the robot's pose (i.e. position and orientation) in the underlying SBPL. More precisely a planning state is a discrete representation of the robot's supporting leg. More...
class  PlanningStateChangeQuery
class  State
 A class representing the robot's pose (i.e. position and orientation) in the (continuous) world view. More precisely a state points to the robot's supporting leg. More...

Typedefs

typedef std::vector< State >
::const_iterator 
state_iter_t

Enumerations

enum  Leg { RIGHT = 0, LEFT = 1, NOLEG = 2 }

Functions

double angle_cell_2_state (int angle, int angle_bin_num)
 Calculate the respective (continuous) angle for a bin.
int angle_state_2_cell (double angle, int angle_bin_num)
 Discretize a (continuous) angle into a bin.
unsigned int calc_hash_tag (int x, int y, int theta, int leg, int max_hash_size)
double 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 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 cont_val (int length, double cell_size)
 Calculates the continuous value for a length discretized in cell size.
int disc_val (double length, double cell_size)
 Discretize a (continuous) value into cell size.
double euclidean_distance (int x1, int y1, int x2, int y2)
double euclidean_distance (double x1, double y1, double x2, double y2)
double euclidean_distance_sq (int x1, int y1, int x2, int y2)
double euclidean_distance_sq (double x1, double y1, double x2, double y2)
double grid_cost (int x1, int y1, int x2, int y2, float cell_size)
unsigned int int_hash (int key)
bool 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 round (double r)
 Rounding half towards zero.
int 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 FLOAT_CMP_THR = 0.0001
static const double TWO_PI = 2 * M_PI

Typedef Documentation

typedef std::vector<State>::const_iterator footstep_planner::state_iter_t

Definition at line 51 of file FootstepPlanner.h.


Enumeration Type Documentation

Enumerator:
RIGHT 
LEFT 
NOLEG 

Definition at line 41 of file helper.h.


Function Documentation

double footstep_planner::angle_cell_2_state ( int  angle,
int  angle_bin_num 
) [inline]

Calculate the respective (continuous) angle for a bin.

Definition at line 101 of file helper.h.

int footstep_planner::angle_state_2_cell ( double  angle,
int  angle_bin_num 
) [inline]

Discretize a (continuous) angle into a bin.

Definition at line 92 of file helper.h.

unsigned int footstep_planner::calc_hash_tag ( int  x,
int  y,
int  theta,
int  leg,
int  max_hash_size 
) [inline]
Returns:
The hash tag for a PlanningState (represented by x, y, theta and leg).

Definition at line 166 of file helper.h.

double footstep_planner::cell_2_state ( int  value,
double  cell_size 
) [inline]

Calculate the respective (continuous) state value for a cell. (Should be used to get a State from a discretized PlanningState.)

Definition at line 122 of file helper.h.

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.

Parameters:
xGlobal position of the foot in x direction.
yGlobal position of the foot in y direction.
thetaGlobal orientation of the foot.
heightSize of the foot in x direction.
widthSize of the foot in y direction.
accuracy(0) circumcircle of the foot; (1) incircle of the foot; (2) circumcircle and incircle recursivly checked for the whole foot
distance_mapContains distance information to the nearest obstacle.
Returns:
True if the footstep collides with an obstacle.

Definition at line 26 of file helper.cpp.

double footstep_planner::cont_val ( int  length,
double  cell_size 
) [inline]

Calculates the continuous value for a length discretized in cell size.

Definition at line 141 of file helper.h.

int footstep_planner::disc_val ( double  length,
double  cell_size 
) [inline]

Discretize a (continuous) value into cell size.

Definition at line 130 of file helper.h.

double footstep_planner::euclidean_distance ( int  x1,
int  y1,
int  x2,
int  y2 
) [inline]
Returns:
Euclidean distance between two integer coordinates (cells).

Definition at line 56 of file helper.h.

double footstep_planner::euclidean_distance ( double  x1,
double  y1,
double  x2,
double  y2 
) [inline]
Returns:
Euclidean distance between two coordinates.

Definition at line 63 of file helper.h.

double footstep_planner::euclidean_distance_sq ( int  x1,
int  y1,
int  x2,
int  y2 
) [inline]
Returns:
Squared euclidean distance between two integer coordinates (cells).

Definition at line 48 of file helper.h.

double footstep_planner::euclidean_distance_sq ( double  x1,
double  y1,
double  x2,
double  y2 
) [inline]
Returns:
Squared euclidean distance between two coordinates.

Definition at line 70 of file helper.h.

double footstep_planner::grid_cost ( int  x1,
int  y1,
int  x2,
int  y2,
float  cell_size 
) [inline]
Returns:
The distance of two neighbored cell.

Definition at line 79 of file helper.h.

unsigned int footstep_planner::int_hash ( int  key) [inline]
Returns:
The hash value of the key.

Definition at line 148 of file helper.h.

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.

Parameters:
edges(x,y)-points defining the polygon.

Check http://geomalgorithms.com/a03-_inclusion.html for further details.

Definition at line 84 of file helper.cpp.

int footstep_planner::round ( double  r) [inline]

Rounding half towards zero.

Definition at line 176 of file helper.h.

int footstep_planner::state_2_cell ( float  value,
float  cell_size 
) [inline]

Discretize a (continuous) state value into a cell. (Should be used to discretize a State to a PlanningState.)

Definition at line 112 of file helper.h.


Variable Documentation

const double footstep_planner::FLOAT_CMP_THR = 0.0001 [static]

Definition at line 39 of file helper.h.

const double footstep_planner::TWO_PI = 2 * M_PI [static]

Definition at line 37 of file helper.h.



footstep_planner
Author(s): Johannes Garimort, Armin Hornung
autogenerated on Mon Oct 6 2014 00:41:41