PPCP planner in explanations, S signifies a fully observable part of the state space H signifies hidden variables. More...
#include <ppcpplanner.h>
Public Member Functions | |
void | costs_changed (StateChangeQuery const &stateChange) |
Notifies the planner that costs have changed. May need to be specialized for different subclasses in terms of what to do here. | |
void | costs_changed () |
notifies the planner that costs have changed | |
int | force_planning_from_scratch () |
forgets previous planning efforts and starts planning from scratch next time replan is called | |
PPCPPlanner (DiscreteSpaceInformation *environment, int sizeofS, int sizeofH) | |
constructors | |
int | replan (double allocated_time_secs, vector< sbpl_PolicyStatewithBinaryh_t > *SolutionPolicy, float *ExpectedCost, float *ProbofReachGoal) |
planning (replanning) function. Takes in time available for planning returns policy, expected cost of the solution policy, and probability of successfully reaching the goal (it is < 1, whenever PPCP ran out of time before full convergence | |
int | replan (double allocated_time_sec, vector< int > *solution_stateIDs_V) |
not supported version of replan | |
int | replan (double allocated_time_sec, vector< int > *solution_stateIDs_V, int *solcost) |
not supported version of replan | |
int | set_goal (int goal_stateID) |
setting goal state in S | |
int | set_search_mode (bool bSearchUntilFirstSolution) |
sets how to search - not supported in PPCP | |
int | set_start (int start_stateID) |
setting start state in S | |
~PPCPPlanner () | |
destructor | |
Private Member Functions | |
int | CreateSearchStateSpace (PPCPStateSpace_t *pStateSpace) |
void | DeleteStateSpace (PPCPStateSpace_t *pStateSpace) |
Private Attributes | |
FILE * | fDeb |
PPCPStateSpace_t * | pStateSpace |
PPCP planner in explanations, S signifies a fully observable part of the state space H signifies hidden variables.
Definition at line 108 of file ppcpplanner.h.
PPCPPlanner::PPCPPlanner | ( | DiscreteSpaceInformation * | environment, |
int | sizeofS, | ||
int | sizeofH | ||
) |
constructors
Definition at line 37 of file ppcpplanner.cpp.
destructor
Definition at line 58 of file ppcpplanner.cpp.
void PPCPPlanner::costs_changed | ( | StateChangeQuery const & | stateChange | ) | [virtual] |
Notifies the planner that costs have changed. May need to be specialized for different subclasses in terms of what to do here.
Implements SBPLPlanner.
Definition at line 124 of file ppcpplanner.cpp.
void PPCPPlanner::costs_changed | ( | ) |
notifies the planner that costs have changed
Definition at line 133 of file ppcpplanner.cpp.
int PPCPPlanner::CreateSearchStateSpace | ( | PPCPStateSpace_t * | pStateSpace | ) | [private] |
Definition at line 81 of file ppcpplanner.cpp.
void PPCPPlanner::DeleteStateSpace | ( | PPCPStateSpace_t * | pStateSpace | ) | [private] |
Definition at line 71 of file ppcpplanner.cpp.
int PPCPPlanner::force_planning_from_scratch | ( | ) | [virtual] |
forgets previous planning efforts and starts planning from scratch next time replan is called
Implements SBPLPlanner.
Definition at line 143 of file ppcpplanner.cpp.
int PPCPPlanner::replan | ( | double | allocated_time_secs, |
vector< sbpl_PolicyStatewithBinaryh_t > * | SolutionPolicy, | ||
float * | ExpectedCost, | ||
float * | ProbofReachGoal | ||
) |
planning (replanning) function. Takes in time available for planning returns policy, expected cost of the solution policy, and probability of successfully reaching the goal (it is < 1, whenever PPCP ran out of time before full convergence
Definition at line 153 of file ppcpplanner.cpp.
int PPCPPlanner::replan | ( | double | allocated_time_sec, |
vector< int > * | solution_stateIDs_V | ||
) | [inline] |
not supported version of replan
Definition at line 135 of file ppcpplanner.h.
int PPCPPlanner::replan | ( | double | allocated_time_sec, |
vector< int > * | solution_stateIDs_V, | ||
int * | solcost | ||
) | [inline] |
not supported version of replan
Definition at line 142 of file ppcpplanner.h.
int PPCPPlanner::set_goal | ( | int | goal_stateID | ) | [virtual] |
int PPCPPlanner::set_search_mode | ( | bool | bSearchUntilFirstSolution | ) | [inline, virtual] |
sets how to search - not supported in PPCP
Implements SBPLPlanner.
Definition at line 154 of file ppcpplanner.h.
int PPCPPlanner::set_start | ( | int | start_stateID | ) | [virtual] |
FILE* PPCPPlanner::fDeb [private] |
Definition at line 173 of file ppcpplanner.h.
PPCPStateSpace_t* PPCPPlanner::pStateSpace [private] |
Definition at line 172 of file ppcpplanner.h.