#include <state_space.h>
Public Types | |
typedef boost::shared_ptr < StateSpace > | ConstPtr |
typedef boost::shared_ptr < StateSpace > | Ptr |
Public Member Functions | |
bool | closeToGoal (const PlanningState &from) const |
bool | closeToStart (const PlanningState &from) const |
PlanningState * | createHashEntryIfNotExists (const PlanningState &s) |
PlanningState * | createNewHashEntry (const State &s) |
Wrapper for footstep_planner_environment::createNewHashEntry(PlanningState). | |
PlanningState * | createNewHashEntry (const PlanningState &s) |
Creates a new planning state for 's' and inserts it into the maps (PlanningState::ivStateId2State, PlanningState::ivpStateHash2State) | |
bool | getGoalState (State &left, State &right) const |
bool | getGoalState (State &robot) const |
PlanningState * | getHashEntry (const State &s) |
Wrapper for footstep_planner_environment::getHashEntry(PlanningState). | |
PlanningState * | getHashEntry (const PlanningState &s) |
exp_states_iter_t | getRandomStatesEnd () |
exp_states_iter_t | getRandomStatesStart () |
bool | getStartState (State &left, State &right) const |
bool | getStartState (State &robot) const |
bool | getState (unsigned int id, State &s) const |
Try to receive a state with a certain ID. | |
bool | getStepCost (const State &stand_foot, const State &swing_foot_before, const State &swing_foot_after, double &cost, double &risk) const |
bool | getStepCost (const State &stand_foot, const State &swing_foot_before, const State &swing_foot_after, int &cost, int &risk) const |
bool | getStepCost (const State &stand_foot, const State &swing_foot_before, const State &swing_foot_after, int &cost) const |
void | reset () |
void | setFrameId (const std::string &frame_id) |
void | setPlannerStartAndGoal (unsigned int start_foot_selection) |
StateSpace (const EnvironmentParameters ¶ms, std::vector< int * > &state_ID2_index_mapping) | |
std::pair< int, int > | updateGoal (const State &foot_left, const State &foot_right) |
std::pair< int, int > | updateStart (const State &foot_left, const State &right_right) |
virtual | ~StateSpace () |
Public Attributes | |
std::string | frame_id |
PlanningState * | goal_foot_left |
PlanningState * | goal_foot_right |
boost::shared_mutex | hash_table_shared_mutex |
bool | ivHeuristicExpired |
The heuristic function used by the planner. | |
int | ivIdGoalFootLeft |
int | ivIdGoalFootRight |
int | ivIdPlanningGoal |
int | ivIdPlanningStart |
ID of Start and Goal foot chosen by planner. | |
int | ivIdStartFootLeft |
int | ivIdStartFootRight |
std::vector< PlanningState * > * | ivpStateHash2State |
Maps from a hash tag to a list of corresponding planning states. (Used in footstep_planner_environment to identify a certain PlanningState.) | |
const int | ivRandomNodeDist |
distance of random neighbors for R* (discretized in cells) | |
exp_states_t | ivRandomStates |
random intermediate states for R* | |
std::vector< int > | ivStateArea |
std::vector< const PlanningState * > | ivStateId2State |
Maps from an ID to the corresponding PlanningState. (Used in the SBPL to access a certain PlanningState.) | |
const EnvironmentParameters & | params |
PlanningState * | start_foot_left |
PlanningState * | start_foot_right |
std::vector< int * > & | state_ID2_index_mapping |
Definition at line 82 of file state_space.h.
typedef boost::shared_ptr<StateSpace> vigir_footstep_planning::StateSpace::ConstPtr |
Definition at line 93 of file state_space.h.
typedef boost::shared_ptr<StateSpace> vigir_footstep_planning::StateSpace::Ptr |
Definition at line 92 of file state_space.h.
vigir_footstep_planning::StateSpace::StateSpace | ( | const EnvironmentParameters & | params, |
std::vector< int * > & | state_ID2_index_mapping | ||
) |
Definition at line 14 of file state_space.cpp.
vigir_footstep_planning::StateSpace::~StateSpace | ( | ) | [virtual] |
Definition at line 30 of file state_space.cpp.
bool vigir_footstep_planning::StateSpace::closeToGoal | ( | const PlanningState & | from | ) | const |
Definition at line 345 of file state_space.cpp.
bool vigir_footstep_planning::StateSpace::closeToStart | ( | const PlanningState & | from | ) | const |
Definition at line 309 of file state_space.cpp.
PlanningState * vigir_footstep_planning::StateSpace::createHashEntryIfNotExists | ( | const PlanningState & | s | ) |
Definition at line 300 of file state_space.cpp.
PlanningState * vigir_footstep_planning::StateSpace::createNewHashEntry | ( | const State & | s | ) |
Wrapper for footstep_planner_environment::createNewHashEntry(PlanningState).
Definition at line 246 of file state_space.cpp.
PlanningState * vigir_footstep_planning::StateSpace::createNewHashEntry | ( | const PlanningState & | s | ) |
Creates a new planning state for 's' and inserts it into the maps (PlanningState::ivStateId2State, PlanningState::ivpStateHash2State)
Definition at line 252 of file state_space.cpp.
bool vigir_footstep_planning::StateSpace::getGoalState | ( | State & | left, |
State & | right | ||
) | const |
Definition at line 220 of file state_space.cpp.
bool vigir_footstep_planning::StateSpace::getGoalState | ( | State & | robot | ) | const |
Definition at line 229 of file state_space.cpp.
PlanningState * vigir_footstep_planning::StateSpace::getHashEntry | ( | const State & | s | ) |
Wrapper for footstep_planner_environment::getHashEntry(PlanningState).
Definition at line 280 of file state_space.cpp.
PlanningState * vigir_footstep_planning::StateSpace::getHashEntry | ( | const PlanningState & | s | ) |
Definition at line 286 of file state_space.cpp.
exp_states_iter_t vigir_footstep_planning::StateSpace::getRandomStatesEnd | ( | ) | [inline] |
Definition at line 118 of file state_space.h.
exp_states_iter_t vigir_footstep_planning::StateSpace::getRandomStatesStart | ( | ) | [inline] |
Definition at line 113 of file state_space.h.
bool vigir_footstep_planning::StateSpace::getStartState | ( | State & | left, |
State & | right | ||
) | const |
Definition at line 194 of file state_space.cpp.
bool vigir_footstep_planning::StateSpace::getStartState | ( | State & | robot | ) | const |
Definition at line 203 of file state_space.cpp.
bool vigir_footstep_planning::StateSpace::getState | ( | unsigned int | id, |
State & | s | ||
) | const |
Try to receive a state with a certain ID.
Definition at line 185 of file state_space.cpp.
bool vigir_footstep_planning::StateSpace::getStepCost | ( | const State & | stand_foot, |
const State & | swing_foot_before, | ||
const State & | swing_foot_after, | ||
double & | cost, | ||
double & | risk | ||
) | const |
Definition at line 381 of file state_space.cpp.
bool vigir_footstep_planning::StateSpace::getStepCost | ( | const State & | stand_foot, |
const State & | swing_foot_before, | ||
const State & | swing_foot_after, | ||
int & | cost, | ||
int & | risk | ||
) | const |
Definition at line 410 of file state_space.cpp.
bool vigir_footstep_planning::StateSpace::getStepCost | ( | const State & | stand_foot, |
const State & | swing_foot_before, | ||
const State & | swing_foot_after, | ||
int & | cost | ||
) | const |
Definition at line 422 of file state_space.cpp.
Definition at line 39 of file state_space.cpp.
void vigir_footstep_planning::StateSpace::setFrameId | ( | const std::string & | frame_id | ) |
Definition at line 71 of file state_space.cpp.
void vigir_footstep_planning::StateSpace::setPlannerStartAndGoal | ( | unsigned int | start_foot_selection | ) |
Definition at line 144 of file state_space.cpp.
std::pair< int, int > vigir_footstep_planning::StateSpace::updateGoal | ( | const State & | foot_left, |
const State & | foot_right | ||
) |
Definition at line 76 of file state_space.cpp.
std::pair< int, int > vigir_footstep_planning::StateSpace::updateStart | ( | const State & | foot_left, |
const State & | right_right | ||
) |
Definition at line 110 of file state_space.cpp.
std::string vigir_footstep_planning::StateSpace::frame_id |
Definition at line 166 of file state_space.h.
PlanningState* vigir_footstep_planning::StateSpace::goal_foot_left |
Definition at line 178 of file state_space.h.
PlanningState* vigir_footstep_planning::StateSpace::goal_foot_right |
Definition at line 179 of file state_space.h.
boost::shared_mutex vigir_footstep_planning::StateSpace::hash_table_shared_mutex [mutable] |
Definition at line 209 of file state_space.h.
The heuristic function used by the planner.
Definition at line 202 of file state_space.h.
Definition at line 181 of file state_space.h.
Definition at line 182 of file state_space.h.
Definition at line 170 of file state_space.h.
ID of Start and Goal foot chosen by planner.
Definition at line 169 of file state_space.h.
Definition at line 175 of file state_space.h.
Definition at line 176 of file state_space.h.
std::vector<PlanningState*>* vigir_footstep_planning::StateSpace::ivpStateHash2State |
Maps from a hash tag to a list of corresponding planning states. (Used in footstep_planner_environment to identify a certain PlanningState.)
Definition at line 199 of file state_space.h.
distance of random neighbors for R* (discretized in cells)
Definition at line 205 of file state_space.h.
exp_states_t vigir_footstep_planning::StateSpace::ivRandomStates |
random intermediate states for R*
Definition at line 207 of file state_space.h.
std::vector<int> vigir_footstep_planning::StateSpace::ivStateArea |
Definition at line 184 of file state_space.h.
std::vector<const PlanningState*> vigir_footstep_planning::StateSpace::ivStateId2State |
Maps from an ID to the corresponding PlanningState. (Used in the SBPL to access a certain PlanningState.)
Definition at line 192 of file state_space.h.
Definition at line 165 of file state_space.h.
PlanningState* vigir_footstep_planning::StateSpace::start_foot_left |
Definition at line 172 of file state_space.h.
PlanningState* vigir_footstep_planning::StateSpace::start_foot_right |
Definition at line 173 of file state_space.h.
std::vector<int*>& vigir_footstep_planning::StateSpace::state_ID2_index_mapping |
Definition at line 186 of file state_space.h.