#include <intervalPlanner.h>
Public Member Functions | |
void | costs_changed () |
void | costs_changed (StateChangeQuery const &stateChange) |
int | force_planning_from_scratch () |
Makes the planner start from scratch. This should be called before each replan. | |
virtual int | get_n_expands () const |
Returns the number of expansions from the last replan. | |
virtual double | get_solution_eps () const |
Returns the epsilon sub-optimality bound of the solution from the last replan. | |
void | getSearchStats (bool *solutionFound, vector< int > *numExpands, vector< int > *solutionCost, vector< double > *searchTime, vector< double > *searchEps) |
Returns all the search statistics from the last replan. | |
IntervalPlanner (DiscreteSpaceTimeIntervalInformation *environment) | |
Constructor. | |
void | print_searchpath (FILE *fOut) |
int | replan (double allocated_time_sec, vector< int > *solution_stateIDs_V, int *solcost) |
Runs the planner. | |
int | replan (double allocated_time_secs, vector< int > *solution_stateIDs_V) |
Runs the planner. | |
virtual void | set_decrease_eps_step (double dec_eps) |
Sets the decrement step size for epsilon. | |
void | set_finalsolution_eps (double finalsolution_eps) |
Sets the final epsilon that the planner will work down to. | |
int | set_goal (int goal_stateID) |
Sets the goal state. | |
virtual void | set_initialsolution_eps (double initialsolution_eps) |
Sets the initial epsilon that the planner starts at. | |
int | set_search_mode (bool bSearchUntilFirstSolution) |
This determines whether the planner improves the solution until time expires, or if it returns the first solution it finds. | |
int | set_start (int start_stateID) |
Sets the start state. | |
~IntervalPlanner () | |
Destructor. | |
Private Member Functions | |
void | BuildNewOPENList (IntervalPlannerSearchStateSpace_t *pSearchStateSpace) |
int | ComputeHeuristic (CMDPSTATE *MDPstate, IntervalPlannerSearchStateSpace_t *pSearchStateSpace) |
int | CreateSearchStateSpace (IntervalPlannerSearchStateSpace_t *pSearchStateSpace) |
CMDPSTATE * | CreateState (int stateID, IntervalPlannerSearchStateSpace_t *pSearchStateSpace) |
void | DeleteSearchStateData (IntervalPlannerState *state) |
void | DeleteSearchStateSpace (IntervalPlannerSearchStateSpace_t *pSearchStateSpace) |
int | GetGVal (int StateID, IntervalPlannerSearchStateSpace_t *pSearchStateSpace) |
int | getHeurValue (IntervalPlannerSearchStateSpace_t *pSearchStateSpace, int StateID) |
vector< int > | GetSearchPath (IntervalPlannerSearchStateSpace_t *pSearchStateSpace, int &solcost) |
CMDPSTATE * | GetState (int stateID, IntervalPlannerSearchStateSpace_t *pSearchStateSpace) |
int | ImprovePath (IntervalPlannerSearchStateSpace_t *pSearchStateSpace, double MaxNumofSecs) |
void | Initialize_searchinfo (CMDPSTATE *state, IntervalPlannerSearchStateSpace_t *pSearchStateSpace) |
void | InitializeSearchStateInfo (IntervalPlannerState *state, IntervalPlannerSearchStateSpace_t *pSearchStateSpace) |
int | InitializeSearchStateSpace (IntervalPlannerSearchStateSpace_t *pSearchStateSpace) |
void | PrintSearchPath (IntervalPlannerSearchStateSpace_t *pSearchStateSpace, FILE *fOut) |
void | PrintSearchState (IntervalPlannerState *state, FILE *fOut) |
int | ReconstructPath (IntervalPlannerSearchStateSpace_t *pSearchStateSpace) |
void | Reevaluatefvals (IntervalPlannerSearchStateSpace_t *pSearchStateSpace) |
void | ReInitializeSearchStateInfo (IntervalPlannerState *state, IntervalPlannerSearchStateSpace_t *pSearchStateSpace) |
void | ReInitializeSearchStateSpace (IntervalPlannerSearchStateSpace_t *pSearchStateSpace) |
int | ResetSearchStateSpace (IntervalPlannerSearchStateSpace_t *pSearchStateSpace) |
bool | Search (IntervalPlannerSearchStateSpace_t *pSearchStateSpace, vector< int > &pathIds, int &PathCost, bool bFirstSolution, bool bOptimalSolution, double MaxNumofSecs) |
int | SetSearchGoalState (int SearchGoalStateID, IntervalPlannerSearchStateSpace_t *pSearchStateSpace) |
int | SetSearchStartState (int SearchStartStateID, IntervalPlannerSearchStateSpace_t *pSearchStateSpace) |
void | UpdatePreds (IntervalPlannerState *state, IntervalPlannerSearchStateSpace_t *pSearchStateSpace) |
void | UpdateSuccs (IntervalPlannerState *state, IntervalPlannerSearchStateSpace_t *pSearchStateSpace) |
Private Attributes | |
bool | bforwardsearch |
bool | bsearchuntilfirstsolution |
double | decrease_eps |
DiscreteSpaceTimeIntervalInformation * | environment_ |
vector< double > | epsV |
vector< unsigned int > | expandsV |
FILE * | fDeb |
int | finalsolcost |
double | finitial_eps |
double | IntervalPlanner_FINAL_EPS |
int | MaxMemoryCounter |
MDPConfig * | MDPCfg_ |
int | numOptStates |
int | numSubOptStates |
IntervalPlannerSearchStateSpace_t * | pSearchStateSpace_ |
unsigned int | searchexpands |
double | searchtime |
vector< double > | searchTimeV |
vector< unsigned int > | solcostV |
bool | solfound |
clock_t | TimeStarted |
int | totalNumOptStates |
int | totalNumSubOptStates |
Definition at line 110 of file intervalPlanner.h.
IntervalPlanner::IntervalPlanner | ( | DiscreteSpaceTimeIntervalInformation * | environment | ) |
Constructor.
environment | A pointer to the environment (already initialized) |
Definition at line 38 of file intervalPlanner.cpp.
IntervalPlanner::~IntervalPlanner | ( | ) |
Destructor.
Definition at line 72 of file intervalPlanner.cpp.
void IntervalPlanner::BuildNewOPENList | ( | IntervalPlannerSearchStateSpace_t * | pSearchStateSpace | ) | [private] |
Definition at line 464 of file intervalPlanner.cpp.
int IntervalPlanner::ComputeHeuristic | ( | CMDPSTATE * | MDPstate, | |
IntervalPlannerSearchStateSpace_t * | pSearchStateSpace | |||
) | [private] |
Definition at line 140 of file intervalPlanner.cpp.
void IntervalPlanner::costs_changed | ( | ) |
Definition at line 1097 of file intervalPlanner.cpp.
void IntervalPlanner::costs_changed | ( | StateChangeQuery const & | stateChange | ) |
Definition at line 1093 of file intervalPlanner.cpp.
int IntervalPlanner::CreateSearchStateSpace | ( | IntervalPlannerSearchStateSpace_t * | pSearchStateSpace | ) | [private] |
Definition at line 516 of file intervalPlanner.cpp.
CMDPSTATE * IntervalPlanner::CreateState | ( | int | stateID, | |
IntervalPlannerSearchStateSpace_t * | pSearchStateSpace | |||
) | [private] |
Definition at line 90 of file intervalPlanner.cpp.
void IntervalPlanner::DeleteSearchStateData | ( | IntervalPlannerState * | state | ) | [private] |
Definition at line 227 of file intervalPlanner.cpp.
void IntervalPlanner::DeleteSearchStateSpace | ( | IntervalPlannerSearchStateSpace_t * | pSearchStateSpace | ) | [private] |
Definition at line 535 of file intervalPlanner.cpp.
int IntervalPlanner::force_planning_from_scratch | ( | ) |
Makes the planner start from scratch. This should be called before each replan.
Definition at line 1103 of file intervalPlanner.cpp.
virtual int IntervalPlanner::get_n_expands | ( | ) | const [inline, virtual] |
Returns the number of expansions from the last replan.
Definition at line 175 of file intervalPlanner.h.
virtual double IntervalPlanner::get_solution_eps | ( | ) | const [inline, virtual] |
Returns the epsilon sub-optimality bound of the solution from the last replan.
Definition at line 170 of file intervalPlanner.h.
int IntervalPlanner::GetGVal | ( | int | StateID, | |
IntervalPlannerSearchStateSpace_t * | pSearchStateSpace | |||
) | [private] |
Definition at line 336 of file intervalPlanner.cpp.
int IntervalPlanner::getHeurValue | ( | IntervalPlannerSearchStateSpace_t * | pSearchStateSpace, | |
int | StateID | |||
) | [private] |
Definition at line 802 of file intervalPlanner.cpp.
vector< int > IntervalPlanner::GetSearchPath | ( | IntervalPlannerSearchStateSpace_t * | pSearchStateSpace, | |
int & | solcost | |||
) | [private] |
Definition at line 809 of file intervalPlanner.cpp.
void IntervalPlanner::getSearchStats | ( | bool * | solutionFound, | |
vector< int > * | numExpands, | |||
vector< int > * | solutionCost, | |||
vector< double > * | searchTime, | |||
vector< double > * | searchEps | |||
) |
Returns all the search statistics from the last replan.
solutionFound | True if a solution was found | |
numExpands | The number of expansions for each epsilon | |
solutionCost | The solution cost for each epsilon | |
searchTime | The planning time for each epsilon | |
searchEps | The epsilons |
Definition at line 1125 of file intervalPlanner.cpp.
CMDPSTATE * IntervalPlanner::GetState | ( | int | stateID, | |
IntervalPlannerSearchStateSpace_t * | pSearchStateSpace | |||
) | [private] |
Definition at line 121 of file intervalPlanner.cpp.
int IntervalPlanner::ImprovePath | ( | IntervalPlannerSearchStateSpace_t * | pSearchStateSpace, | |
double | MaxNumofSecs | |||
) | [private] |
Definition at line 343 of file intervalPlanner.cpp.
void IntervalPlanner::Initialize_searchinfo | ( | CMDPSTATE * | state, | |
IntervalPlannerSearchStateSpace_t * | pSearchStateSpace | |||
) | [private] |
Definition at line 82 of file intervalPlanner.cpp.
void IntervalPlanner::InitializeSearchStateInfo | ( | IntervalPlannerState * | state, | |
IntervalPlannerSearchStateSpace_t * | pSearchStateSpace | |||
) | [private] |
Definition at line 167 of file intervalPlanner.cpp.
int IntervalPlanner::InitializeSearchStateSpace | ( | IntervalPlannerSearchStateSpace_t * | pSearchStateSpace | ) | [private] |
Definition at line 614 of file intervalPlanner.cpp.
void IntervalPlanner::print_searchpath | ( | FILE * | fOut | ) |
Definition at line 1117 of file intervalPlanner.cpp.
void IntervalPlanner::PrintSearchPath | ( | IntervalPlannerSearchStateSpace_t * | pSearchStateSpace, | |
FILE * | fOut | |||
) | [private] |
Definition at line 732 of file intervalPlanner.cpp.
void IntervalPlanner::PrintSearchState | ( | IntervalPlannerState * | state, | |
FILE * | fOut | |||
) | [private] |
Definition at line 793 of file intervalPlanner.cpp.
int IntervalPlanner::ReconstructPath | ( | IntervalPlannerSearchStateSpace_t * | pSearchStateSpace | ) | [private] |
Definition at line 679 of file intervalPlanner.cpp.
void IntervalPlanner::Reevaluatefvals | ( | IntervalPlannerSearchStateSpace_t * | pSearchStateSpace | ) | [private] |
Definition at line 493 of file intervalPlanner.cpp.
void IntervalPlanner::ReInitializeSearchStateInfo | ( | IntervalPlannerState * | state, | |
IntervalPlannerSearchStateSpace_t * | pSearchStateSpace | |||
) | [private] |
Definition at line 196 of file intervalPlanner.cpp.
void IntervalPlanner::ReInitializeSearchStateSpace | ( | IntervalPlannerSearchStateSpace_t * | pSearchStateSpace | ) | [private] |
Definition at line 573 of file intervalPlanner.cpp.
int IntervalPlanner::replan | ( | double | allocated_time_sec, | |
vector< int > * | solution_stateIDs_V, | |||
int * | solcost | |||
) |
Runs the planner.
allocated_time_secs | The amount of time the planner can run (and try to improve the solution) | |
solution_stateIDs_V | The path of state IDs from the start to goal (the environment's ConvertStateIDPathintoXYThetaPath can change a state ID path into a path of points) | |
solcost | The cost of the solution |
Definition at line 1027 of file intervalPlanner.cpp.
int IntervalPlanner::replan | ( | double | allocated_time_secs, | |
vector< int > * | solution_stateIDs_V | |||
) |
Runs the planner.
allocated_time_secs | The amount of time the planner can run (and try to improve the solution) | |
solution_stateIDs_V | The path of state IDs from the start to goal (the environment's ConvertStateIDPathintoXYThetaPath can change a state ID path into a path of points) |
Definition at line 1021 of file intervalPlanner.cpp.
int IntervalPlanner::ResetSearchStateSpace | ( | IntervalPlannerSearchStateSpace_t * | pSearchStateSpace | ) | [private] |
Definition at line 565 of file intervalPlanner.cpp.
bool IntervalPlanner::Search | ( | IntervalPlannerSearchStateSpace_t * | pSearchStateSpace, | |
vector< int > & | pathIds, | |||
int & | PathCost, | |||
bool | bFirstSolution, | |||
bool | bOptimalSolution, | |||
double | MaxNumofSecs | |||
) | [private] |
Definition at line 893 of file intervalPlanner.cpp.
virtual void IntervalPlanner::set_decrease_eps_step | ( | double | dec_eps | ) | [inline, virtual] |
Sets the decrement step size for epsilon.
Definition at line 190 of file intervalPlanner.h.
void IntervalPlanner::set_finalsolution_eps | ( | double | finalsolution_eps | ) | [inline] |
Sets the final epsilon that the planner will work down to.
Definition at line 180 of file intervalPlanner.h.
int IntervalPlanner::set_goal | ( | int | goal_stateID | ) |
Sets the goal state.
goal_stateID | The state ID of the goal state (from the environment) |
Definition at line 1052 of file intervalPlanner.cpp.
virtual void IntervalPlanner::set_initialsolution_eps | ( | double | initialsolution_eps | ) | [inline, virtual] |
Sets the initial epsilon that the planner starts at.
Definition at line 185 of file intervalPlanner.h.
int IntervalPlanner::set_search_mode | ( | bool | bSearchUntilFirstSolution | ) |
This determines whether the planner improves the solution until time expires, or if it returns the first solution it finds.
bSearchUntilFirstSolution | If this is true the planner will return the first solution found. (it also ignores the allocated time if this is true) |
Definition at line 1110 of file intervalPlanner.cpp.
int IntervalPlanner::set_start | ( | int | start_stateID | ) |
Sets the start state.
start_stateID | The state ID of the start state (from the environment) |
Definition at line 1072 of file intervalPlanner.cpp.
int IntervalPlanner::SetSearchGoalState | ( | int | SearchGoalStateID, | |
IntervalPlannerSearchStateSpace_t * | pSearchStateSpace | |||
) | [private] |
Definition at line 639 of file intervalPlanner.cpp.
int IntervalPlanner::SetSearchStartState | ( | int | SearchStartStateID, | |
IntervalPlannerSearchStateSpace_t * | pSearchStateSpace | |||
) | [private] |
Definition at line 666 of file intervalPlanner.cpp.
void IntervalPlanner::UpdatePreds | ( | IntervalPlannerState * | state, | |
IntervalPlannerSearchStateSpace_t * | pSearchStateSpace | |||
) | [private] |
Definition at line 236 of file intervalPlanner.cpp.
void IntervalPlanner::UpdateSuccs | ( | IntervalPlannerState * | state, | |
IntervalPlannerSearchStateSpace_t * | pSearchStateSpace | |||
) | [private] |
Definition at line 275 of file intervalPlanner.cpp.
bool IntervalPlanner::bforwardsearch [private] |
Definition at line 220 of file intervalPlanner.h.
bool IntervalPlanner::bsearchuntilfirstsolution [private] |
Definition at line 222 of file intervalPlanner.h.
double IntervalPlanner::decrease_eps [private] |
Definition at line 217 of file intervalPlanner.h.
Definition at line 212 of file intervalPlanner.h.
vector<double> IntervalPlanner::epsV [private] |
Definition at line 234 of file intervalPlanner.h.
vector<unsigned int> IntervalPlanner::expandsV [private] |
Definition at line 235 of file intervalPlanner.h.
FILE* IntervalPlanner::fDeb [private] |
Definition at line 229 of file intervalPlanner.h.
int IntervalPlanner::finalsolcost [private] |
Definition at line 232 of file intervalPlanner.h.
double IntervalPlanner::finitial_eps [private] |
Definition at line 216 of file intervalPlanner.h.
double IntervalPlanner::IntervalPlanner_FINAL_EPS [private] |
Definition at line 213 of file intervalPlanner.h.
int IntervalPlanner::MaxMemoryCounter [private] |
Definition at line 227 of file intervalPlanner.h.
MDPConfig* IntervalPlanner::MDPCfg_ [private] |
Definition at line 218 of file intervalPlanner.h.
int IntervalPlanner::numOptStates [private] |
Definition at line 207 of file intervalPlanner.h.
int IntervalPlanner::numSubOptStates [private] |
Definition at line 208 of file intervalPlanner.h.
Definition at line 224 of file intervalPlanner.h.
unsigned int IntervalPlanner::searchexpands [private] |
Definition at line 226 of file intervalPlanner.h.
double IntervalPlanner::searchtime [private] |
Definition at line 231 of file intervalPlanner.h.
vector<double> IntervalPlanner::searchTimeV [private] |
Definition at line 237 of file intervalPlanner.h.
vector<unsigned int> IntervalPlanner::solcostV [private] |
Definition at line 236 of file intervalPlanner.h.
bool IntervalPlanner::solfound [private] |
Definition at line 230 of file intervalPlanner.h.
clock_t IntervalPlanner::TimeStarted [private] |
Definition at line 228 of file intervalPlanner.h.
int IntervalPlanner::totalNumOptStates [private] |
Definition at line 209 of file intervalPlanner.h.
int IntervalPlanner::totalNumSubOptStates [private] |
Definition at line 210 of file intervalPlanner.h.