Public Member Functions | Private Attributes | List of all members
footstep_planner::PlanningState Class Reference

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...

#include <PlanningState.h>

Public Member Functions

unsigned int getHashTag () const
 
int getId () const
 
Leg getLeg () const
 
State getState (double cell_size, int num_angle_bins) const
 Computes the continuous State the PlanningState represents. More...
 
int getTheta () const
 
int getX () const
 
int getY () const
 
bool operator!= (const PlanningState &s2) const
 Compare two states on inequality of x, y, theta, leg by comparing the hash tags of the states. More...
 
bool operator== (const PlanningState &s2) const
 Compare two states on equality of x, y, theta, leg. Makes first use of the non-unique hash tag to rule out unequal states. More...
 
 PlanningState (double x, double y, double theta, Leg leg, double cell_size, int num_angle_bins, int max_hash_size)
 x, y and theta represent the global (continuous) position and orientation of the robot's support leg. More...
 
 PlanningState (int x, int y, int theta, Leg leg, int max_hash_size)
 x, y and theta as discrete bin values (as used internally by the planner). More...
 
 PlanningState (const State &s, double cell_size, int num_angle_bins, int max_hash_size)
 Create a (discrete) PlanningState from a (continuous) State. More...
 
 PlanningState (const PlanningState &s)
 Copy constructor. More...
 
void setId (unsigned int id)
 Used to attach such an unique ID to the planning state. (This cannot be done in the constructor since often such an ID is not known when the planning state is created.) More...
 
 ~PlanningState ()
 

Private Attributes

unsigned int ivHashTag
 
int ivId
 The (unique) ID of the planning state. More...
 
Leg ivLeg
 The supporting leg. More...
 
int ivTheta
 Number of the bin the orientation is fitted into. More...
 
int ivX
 Value of the grid cell the position's x value is fitted into. More...
 
int ivY
 Value of the grid cell the position's y value is fitted into. More...
 

Detailed Description

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.

Since SBPL is working on discretized states the planning states are also discretized positions and orientations. This is done by fitting the positions into a grid and the orientations into bins. (NOTE: the resolution of the planning cells is likely to differ from the resolution of the grid map.)

The SBPL can access each planning state via an unique ID. Furthermore each planning state can be identified by an (ununique) hash tag generated from its position, location and supporting leg.

Definition at line 45 of file PlanningState.h.

Constructor & Destructor Documentation

footstep_planner::PlanningState::PlanningState ( double  x,
double  y,
double  theta,
Leg  leg,
double  cell_size,
int  num_angle_bins,
int  max_hash_size 
)

x, y and theta represent the global (continuous) position and orientation of the robot's support leg.

Parameters
legThe supporting leg.
cell_sizeThe size of each grid cell discretizing the position.
num_angle_binsThe number of bins discretizing the orientation.
max_hash_size

Definition at line 29 of file PlanningState.cpp.

footstep_planner::PlanningState::PlanningState ( int  x,
int  y,
int  theta,
Leg  leg,
int  max_hash_size 
)

x, y and theta as discrete bin values (as used internally by the planner).

Definition at line 41 of file PlanningState.cpp.

footstep_planner::PlanningState::PlanningState ( const State s,
double  cell_size,
int  num_angle_bins,
int  max_hash_size 
)

Create a (discrete) PlanningState from a (continuous) State.

Definition at line 52 of file PlanningState.cpp.

footstep_planner::PlanningState::PlanningState ( const PlanningState s)

Copy constructor.

Definition at line 63 of file PlanningState.cpp.

footstep_planner::PlanningState::~PlanningState ( )

Definition at line 73 of file PlanningState.cpp.

Member Function Documentation

unsigned int footstep_planner::PlanningState::getHashTag ( ) const
inline
Returns
The (non-unique) hash tag used to identify the planning state.

Definition at line 105 of file PlanningState.h.

int footstep_planner::PlanningState::getId ( ) const
inline
Returns
The (unique) ID used within the SBPL to access the planning state.

Definition at line 111 of file PlanningState.h.

Leg footstep_planner::PlanningState::getLeg ( ) const
inline

Definition at line 96 of file PlanningState.h.

State footstep_planner::PlanningState::getState ( double  cell_size,
int  num_angle_bins 
) const

Computes the continuous State the PlanningState represents.

Definition at line 100 of file PlanningState.cpp.

int footstep_planner::PlanningState::getTheta ( ) const
inline

Definition at line 97 of file PlanningState.h.

int footstep_planner::PlanningState::getX ( ) const
inline

Definition at line 98 of file PlanningState.h.

int footstep_planner::PlanningState::getY ( ) const
inline

Definition at line 99 of file PlanningState.h.

bool footstep_planner::PlanningState::operator!= ( const PlanningState s2) const

Compare two states on inequality of x, y, theta, leg by comparing the hash tags of the states.

Definition at line 92 of file PlanningState.cpp.

bool footstep_planner::PlanningState::operator== ( const PlanningState s2) const

Compare two states on equality of x, y, theta, leg. Makes first use of the non-unique hash tag to rule out unequal states.

Definition at line 78 of file PlanningState.cpp.

void footstep_planner::PlanningState::setId ( unsigned int  id)
inline

Used to attach such an unique ID to the planning state. (This cannot be done in the constructor since often such an ID is not known when the planning state is created.)

Definition at line 94 of file PlanningState.h.

Member Data Documentation

unsigned int footstep_planner::PlanningState::ivHashTag
private

The (non-unique) hash tag of the planning state. Different hash tags imply that the states differ in x, y, theta, leg.

Definition at line 133 of file PlanningState.h.

int footstep_planner::PlanningState::ivId
private

The (unique) ID of the planning state.

Definition at line 127 of file PlanningState.h.

Leg footstep_planner::PlanningState::ivLeg
private

The supporting leg.

Definition at line 124 of file PlanningState.h.

int footstep_planner::PlanningState::ivTheta
private

Number of the bin the orientation is fitted into.

Definition at line 122 of file PlanningState.h.

int footstep_planner::PlanningState::ivX
private

Value of the grid cell the position's x value is fitted into.

Definition at line 118 of file PlanningState.h.

int footstep_planner::PlanningState::ivY
private

Value of the grid cell the position's y value is fitted into.

Definition at line 120 of file PlanningState.h.


The documentation for this class was generated from the following files:


footstep_planner
Author(s): Johannes Garimort, Armin Hornung
autogenerated on Mon Jun 10 2019 13:38:25