Public Types | Public Member Functions | Private Attributes | List of all members
vigir_footstep_planning::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 <planning_state.h>

Public Types

typedef boost::shared_ptr< const PlanningStateConstPtr
 
typedef boost::shared_ptr< PlanningStatePtr
 

Public Member Functions

unsigned int getHashTag () const
 
int getId () const
 
Leg getLeg () const
 
const PlanningStategetPredState () const
 
const StategetState () const
 gets the continuous State the PlanningState represents. More...
 
StategetState ()
 
double getStepDuration () const
 
const PlanningStategetSuccState () const
 
double getSwayDuration () const
 
double getSwingHeight () const
 
int getX () const
 
int getY () const
 
int getYaw () 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 z, double roll, double pitch, double yaw, Leg leg, double cell_size, double angle_bin_size, int max_hash_size, const PlanningState *pred_state=nullptr, const PlanningState *succ_state=nullptr)
 x, y and theta represent the global (continuous) position and orientation of the robot's support leg. More...
 
 PlanningState (int x, int y, double z, double roll, double pitch, int yaw, Leg leg, double cell_size, double angle_bin_size, int max_hash_size, const PlanningState *pred_state=nullptr, const PlanningState *succ_state=nullptr)
 x, y and theta as discrete bin values (as used internally by the planner). More...
 
 PlanningState (const geometry_msgs::Pose &pose, Leg leg, double cell_size, double angle_bin_size, int max_hash_size, const PlanningState *pred_state=nullptr, const PlanningState *succ_state=nullptr)
 
 PlanningState (const State &s, double cell_size, double angle_bin_size, int max_hash_size, const PlanningState *pred_state=nullptr, const PlanningState *succ_state=nullptr)
 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...
 
void setPredState (const PlanningState *pred_state)
 
void setSuccState (const PlanningState *succ_state)
 
 ~PlanningState ()
 

Private Attributes

unsigned int ivHashTag
 
int ivId
 The (unique) ID of the planning state. More...
 
const PlanningStateivpPredState
 
const PlanningStateivpSuccState
 
State ivState
 pointer to original state 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...
 
int ivYaw
 The robot's orientation. 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 49 of file planning_state.h.

Member Typedef Documentation

Definition at line 54 of file planning_state.h.

Definition at line 53 of file planning_state.h.

Constructor & Destructor Documentation

vigir_footstep_planning::PlanningState::PlanningState ( double  x,
double  y,
double  z,
double  roll,
double  pitch,
double  yaw,
Leg  leg,
double  cell_size,
double  angle_bin_size,
int  max_hash_size,
const PlanningState pred_state = nullptr,
const PlanningState succ_state = nullptr 
)

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 33 of file planning_state.cpp.

vigir_footstep_planning::PlanningState::PlanningState ( int  x,
int  y,
double  z,
double  roll,
double  pitch,
int  yaw,
Leg  leg,
double  cell_size,
double  angle_bin_size,
int  max_hash_size,
const PlanningState pred_state = nullptr,
const PlanningState succ_state = nullptr 
)

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

Definition at line 49 of file planning_state.cpp.

vigir_footstep_planning::PlanningState::PlanningState ( const geometry_msgs::Pose pose,
Leg  leg,
double  cell_size,
double  angle_bin_size,
int  max_hash_size,
const PlanningState pred_state = nullptr,
const PlanningState succ_state = nullptr 
)

Definition at line 64 of file planning_state.cpp.

vigir_footstep_planning::PlanningState::PlanningState ( const State s,
double  cell_size,
double  angle_bin_size,
int  max_hash_size,
const PlanningState pred_state = nullptr,
const PlanningState succ_state = nullptr 
)

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

Definition at line 80 of file planning_state.cpp.

vigir_footstep_planning::PlanningState::PlanningState ( const PlanningState s)

Copy constructor.

Definition at line 94 of file planning_state.cpp.

vigir_footstep_planning::PlanningState::~PlanningState ( )

Definition at line 105 of file planning_state.cpp.

Member Function Documentation

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

Definition at line 127 of file planning_state.h.

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

Definition at line 133 of file planning_state.h.

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

Definition at line 115 of file planning_state.h.

const PlanningState* vigir_footstep_planning::PlanningState::getPredState ( ) const
inline

Definition at line 118 of file planning_state.h.

const State & vigir_footstep_planning::PlanningState::getState ( ) const

gets the continuous State the PlanningState represents.

Definition at line 133 of file planning_state.cpp.

State & vigir_footstep_planning::PlanningState::getState ( )

Definition at line 138 of file planning_state.cpp.

double vigir_footstep_planning::PlanningState::getStepDuration ( ) const
inline

Definition at line 113 of file planning_state.h.

const PlanningState* vigir_footstep_planning::PlanningState::getSuccState ( ) const
inline

Definition at line 121 of file planning_state.h.

double vigir_footstep_planning::PlanningState::getSwayDuration ( ) const
inline

Definition at line 112 of file planning_state.h.

double vigir_footstep_planning::PlanningState::getSwingHeight ( ) const
inline

Definition at line 110 of file planning_state.h.

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

Definition at line 106 of file planning_state.h.

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

Definition at line 107 of file planning_state.h.

int vigir_footstep_planning::PlanningState::getYaw ( ) const
inline

Definition at line 108 of file planning_state.h.

bool vigir_footstep_planning::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 128 of file planning_state.cpp.

bool vigir_footstep_planning::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.

TODO: Comment this in to plan with full steps (slower)! Check hashtag for performance improvements!

Definition at line 108 of file planning_state.cpp.

void vigir_footstep_planning::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 104 of file planning_state.h.

void vigir_footstep_planning::PlanningState::setPredState ( const PlanningState pred_state)
inline

Definition at line 117 of file planning_state.h.

void vigir_footstep_planning::PlanningState::setSuccState ( const PlanningState succ_state)
inline

Definition at line 120 of file planning_state.h.

Member Data Documentation

unsigned int vigir_footstep_planning::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 160 of file planning_state.h.

int vigir_footstep_planning::PlanningState::ivId
private

The (unique) ID of the planning state.

Definition at line 154 of file planning_state.h.

const PlanningState* vigir_footstep_planning::PlanningState::ivpPredState
private

Definition at line 150 of file planning_state.h.

const PlanningState* vigir_footstep_planning::PlanningState::ivpSuccState
private

Definition at line 151 of file planning_state.h.

State vigir_footstep_planning::PlanningState::ivState
private

pointer to original state

Definition at line 141 of file planning_state.h.

int vigir_footstep_planning::PlanningState::ivX
private

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

Definition at line 144 of file planning_state.h.

int vigir_footstep_planning::PlanningState::ivY
private

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

Definition at line 146 of file planning_state.h.

int vigir_footstep_planning::PlanningState::ivYaw
private

The robot's orientation.

Definition at line 148 of file planning_state.h.


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


vigir_footstep_planning_lib
Author(s): Alexander Stumpf
autogenerated on Mon Jun 10 2019 15:47:33