Classes | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
vigir_footstep_planning::FootstepPlannerEnvironment Class Reference

A class defining a footstep planner environment for humanoid robots used by the SBPL to perform planning tasks. More...

#include <footstep_planner_environment.h>

Inheritance diagram for vigir_footstep_planning::FootstepPlannerEnvironment:
Inheritance graph
[legend]

Classes

struct  less
 < operator for planning states. More...
 

Public Member Functions

bool AreEquivalent (int StateID1, int StateID2)
 
 FootstepPlannerEnvironment (const EnvironmentParameters &params, const FootPoseTransformer &foot_pose_transformer, boost::function< void(msgs::PlanningFeedback)> &feedback_cb)
 
exp_states_2d_iter_t getExpandedStatesEnd ()
 
exp_states_2d_iter_t getExpandedStatesStart ()
 
int GetFromToHeuristic (int FromStateID, int ToStateID)
 
int GetGoalHeuristic (int stateID)
 
int getNumExpandedStates ()
 
void GetPreds (int TargetStateID, std::vector< int > *PredIDV, std::vector< int > *CostV)
 Calculates the predecessor states and the corresponding costs when reversing the footstep set on the planning state TargetStateID. (Used for backward planning.) More...
 
virtual void GetRandomPredsatDistance (int TargetStateID, std::vector< int > *PredIDV, std::vector< int > *CLowV)
 Used for RStar: generate succs/preds at some domain-dependent distance. The number of generated succs/preds is up to the environment. More...
 
virtual void GetRandomSuccsatDistance (int SourceStateID, std::vector< int > *SuccIDV, std::vector< int > *CLowV)
 Used for RStar: generate succs/preds at some domain-dependent distance. The number of generated succs/preds is up to the environment. More...
 
int GetStartHeuristic (int stateID)
 
const StateSpace::PtrgetStateSpace ()
 
void GetSuccs (int SourceStateID, std::vector< int > *SuccIDV, std::vector< int > *CostV)
 Calculates the successor states and the corresponding costs when performing the footstep set on the planning state SourceStateID. (Used for forward planning.) More...
 
bool InitializeEnv (const char *sEnvFile)
 
bool InitializeMDPCfg (MDPConfig *MDPCfg)
 
void PrintEnv_Config (FILE *fOut)
 
void PrintState (int stateID, bool bVerbose, FILE *fOut)
 
void reset ()
 Resets the current planning task (i.e. the start and goal poses). More...
 
void SetAllActionsandAllOutcomes (CMDPSTATE *state)
 
void SetAllPreds (CMDPSTATE *state)
 
void setFrameId (const std::string &frame_id)
 
int SizeofCreatedEnv ()
 
void stateExpanded (const PlanningState &s)
 
void stateVisited (const PlanningState &s)
 
void updateHeuristicValues ()
 Update the heuristic values (e.g. after the map has changed). The environment takes care that the update is only done when it is necessary. More...
 
virtual ~FootstepPlannerEnvironment ()
 

Protected Member Functions

int GetFromToHeuristic (const PlanningState &from, const PlanningState &to, const PlanningState &start, const PlanningState &goal)
 

Protected Attributes

boost::function< void(msgs::PlanningFeedback)> & feedback_cb
 
const FootPoseTransformerfoot_pose_transformer
 
std::string frame_id
 
exp_states_2d_t ivExpandedStates
 
size_t ivNumExpandedStates
 
ros::Time last_feedback_flush
 
const EnvironmentParametersparams
 Parameters. More...
 
StateSpace::Ptr state_space
 
std::vector< msgs::Step > visited_steps
 

Detailed Description

A class defining a footstep planner environment for humanoid robots used by the SBPL to perform planning tasks.

The environment keeps track of all the planning states expanded during the search. Each planning state can be accessed via its ID. Furthermore

Definition at line 65 of file footstep_planner_environment.h.

Constructor & Destructor Documentation

vigir_footstep_planning::FootstepPlannerEnvironment::FootstepPlannerEnvironment ( const EnvironmentParameters params,
const FootPoseTransformer foot_pose_transformer,
boost::function< void(msgs::PlanningFeedback)> &  feedback_cb 
)

Definition at line 9 of file footstep_planner_environment.cpp.

vigir_footstep_planning::FootstepPlannerEnvironment::~FootstepPlannerEnvironment ( )
virtual

Definition at line 21 of file footstep_planner_environment.cpp.

Member Function Documentation

bool vigir_footstep_planning::FootstepPlannerEnvironment::AreEquivalent ( int  StateID1,
int  StateID2 
)
Returns
True if two states meet the same condition. Used for R*.

Definition at line 406 of file footstep_planner_environment.cpp.

exp_states_2d_iter_t vigir_footstep_planning::FootstepPlannerEnvironment::getExpandedStatesEnd ( )
inline

Definition at line 94 of file footstep_planner_environment.h.

exp_states_2d_iter_t vigir_footstep_planning::FootstepPlannerEnvironment::getExpandedStatesStart ( )
inline

Definition at line 89 of file footstep_planner_environment.h.

int vigir_footstep_planning::FootstepPlannerEnvironment::GetFromToHeuristic ( int  FromStateID,
int  ToStateID 
)
Returns
The costs (in mm, truncated as int) to reach the planning state ToStateID from within planning state FromStateID.

Definition at line 146 of file footstep_planner_environment.cpp.

int vigir_footstep_planning::FootstepPlannerEnvironment::GetFromToHeuristic ( const PlanningState &  from,
const PlanningState &  to,
const PlanningState &  start,
const PlanningState &  goal 
)
protected
Returns
The costs (in mm, truncated as int) to reach the planning state ToStateID from within planning state FromStateID.

Definition at line 160 of file footstep_planner_environment.cpp.

int vigir_footstep_planning::FootstepPlannerEnvironment::GetGoalHeuristic ( int  stateID)
Returns
The heuristic value to reach the goal from within the planning state stateID (used for forward planning).

Definition at line 165 of file footstep_planner_environment.cpp.

int vigir_footstep_planning::FootstepPlannerEnvironment::getNumExpandedStates ( )
inline
Returns
The number of expanded states during the search.

Definition at line 78 of file footstep_planner_environment.h.

void vigir_footstep_planning::FootstepPlannerEnvironment::GetPreds ( int  TargetStateID,
std::vector< int > *  PredIDV,
std::vector< int > *  CostV 
)

Calculates the predecessor states and the corresponding costs when reversing the footstep set on the planning state TargetStateID. (Used for backward planning.)

Definition at line 175 of file footstep_planner_environment.cpp.

void vigir_footstep_planning::FootstepPlannerEnvironment::GetRandomPredsatDistance ( int  TargetStateID,
std::vector< int > *  PredIDV,
std::vector< int > *  CLowV 
)
virtual

Used for RStar: generate succs/preds at some domain-dependent distance. The number of generated succs/preds is up to the environment.

Definition at line 386 of file footstep_planner_environment.cpp.

void vigir_footstep_planning::FootstepPlannerEnvironment::GetRandomSuccsatDistance ( int  SourceStateID,
std::vector< int > *  SuccIDV,
std::vector< int > *  CLowV 
)
virtual

Used for RStar: generate succs/preds at some domain-dependent distance. The number of generated succs/preds is up to the environment.

Definition at line 366 of file footstep_planner_environment.cpp.

int vigir_footstep_planning::FootstepPlannerEnvironment::GetStartHeuristic ( int  stateID)
Returns
The heuristic value to reach the start from within the planning state stateID. (Used for backward planning.)

Definition at line 265 of file footstep_planner_environment.cpp.

const StateSpace::Ptr& vigir_footstep_planning::FootstepPlannerEnvironment::getStateSpace ( )
inline

Definition at line 75 of file footstep_planner_environment.h.

void vigir_footstep_planning::FootstepPlannerEnvironment::GetSuccs ( int  SourceStateID,
std::vector< int > *  SuccIDV,
std::vector< int > *  CostV 
)

Calculates the successor states and the corresponding costs when performing the footstep set on the planning state SourceStateID. (Used for forward planning.)

Definition at line 276 of file footstep_planner_environment.cpp.

bool vigir_footstep_planning::FootstepPlannerEnvironment::InitializeEnv ( const char *  sEnvFile)

Definition at line 419 of file footstep_planner_environment.cpp.

bool vigir_footstep_planning::FootstepPlannerEnvironment::InitializeMDPCfg ( MDPConfig *  MDPCfg)

Definition at line 426 of file footstep_planner_environment.cpp.

void vigir_footstep_planning::FootstepPlannerEnvironment::PrintEnv_Config ( FILE *  fOut)

Definition at line 439 of file footstep_planner_environment.cpp.

void vigir_footstep_planning::FootstepPlannerEnvironment::PrintState ( int  stateID,
bool  bVerbose,
FILE *  fOut 
)

Definition at line 446 of file footstep_planner_environment.cpp.

void vigir_footstep_planning::FootstepPlannerEnvironment::reset ( )

Resets the current planning task (i.e. the start and goal poses).

Definition at line 68 of file footstep_planner_environment.cpp.

void vigir_footstep_planning::FootstepPlannerEnvironment::SetAllActionsandAllOutcomes ( CMDPSTATE *  state)

Definition at line 472 of file footstep_planner_environment.cpp.

void vigir_footstep_planning::FootstepPlannerEnvironment::SetAllPreds ( CMDPSTATE *  state)

Definition at line 484 of file footstep_planner_environment.cpp.

void vigir_footstep_planning::FootstepPlannerEnvironment::setFrameId ( const std::string &  frame_id)

Definition at line 25 of file footstep_planner_environment.cpp.

int vigir_footstep_planning::FootstepPlannerEnvironment::SizeofCreatedEnv ( )

Definition at line 496 of file footstep_planner_environment.cpp.

void vigir_footstep_planning::FootstepPlannerEnvironment::stateExpanded ( const PlanningState &  s)

Definition at line 79 of file footstep_planner_environment.cpp.

void vigir_footstep_planning::FootstepPlannerEnvironment::stateVisited ( const PlanningState &  s)

TODO: resize is expensive!

Definition at line 133 of file footstep_planner_environment.cpp.

void vigir_footstep_planning::FootstepPlannerEnvironment::updateHeuristicValues ( )

Update the heuristic values (e.g. after the map has changed). The environment takes care that the update is only done when it is necessary.

Definition at line 30 of file footstep_planner_environment.cpp.

Member Data Documentation

boost::function<void (msgs::PlanningFeedback)>& vigir_footstep_planning::FootstepPlannerEnvironment::feedback_cb
protected

Definition at line 192 of file footstep_planner_environment.h.

const FootPoseTransformer& vigir_footstep_planning::FootstepPlannerEnvironment::foot_pose_transformer
protected

Definition at line 189 of file footstep_planner_environment.h.

std::string vigir_footstep_planning::FootstepPlannerEnvironment::frame_id
protected

Definition at line 200 of file footstep_planner_environment.h.

exp_states_2d_t vigir_footstep_planning::FootstepPlannerEnvironment::ivExpandedStates
protected

Definition at line 197 of file footstep_planner_environment.h.

size_t vigir_footstep_planning::FootstepPlannerEnvironment::ivNumExpandedStates
protected

Definition at line 198 of file footstep_planner_environment.h.

ros::Time vigir_footstep_planning::FootstepPlannerEnvironment::last_feedback_flush
protected

Definition at line 202 of file footstep_planner_environment.h.

const EnvironmentParameters& vigir_footstep_planning::FootstepPlannerEnvironment::params
protected

Parameters.

Definition at line 195 of file footstep_planner_environment.h.

StateSpace::Ptr vigir_footstep_planning::FootstepPlannerEnvironment::state_space
protected

Definition at line 186 of file footstep_planner_environment.h.

std::vector<msgs::Step> vigir_footstep_planning::FootstepPlannerEnvironment::visited_steps
protected

Definition at line 201 of file footstep_planner_environment.h.


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


vigir_footstep_planner
Author(s): Alexander Stumpf
autogenerated on Sun Nov 17 2019 03:29:59