The continual planning loop. More...
#include <continualPlanning.h>
Public Types | |
enum | ContinualPlanningState { Running, FinishedNoPlanToGoal, FinishedAtGoal } |
enum | ReplanningTriggerMethod { ReplanAlways, ReplanIfLogicalStateChanged, ReplanByMonitoring } |
Public Member Functions | |
ContinualPlanning () | |
bool | estimateCurrentState () |
Update _currentState from the world. | |
bool | executeActionDirectly (const DurativeAction &a, bool publishStatus) |
For debugging, just execute this action. | |
void | forceReplanning () |
Force replanning in the next loop. | |
bool | isGoalFulfilled () const |
Does _currentState match _goal? | |
ContinualPlanningState | loop () |
Execute one loop step. | |
~ContinualPlanning () | |
Protected Member Functions | |
Plan | monitorAndReplan (bool &atGoal) |
Return a plan that reaches the goal. | |
bool | needReplanning (bool &atGoal) const |
Returns true, if replanning needs to be done as _currentPlan in _currentState doesn't reach _goal. | |
Protected Attributes | |
bool | _allowDirectGoalCheck |
Allow to check reached goal by using the _goal instead of monitoring. | |
Plan | _currentPlan |
SymbolicState | _currentState |
bool | _forceReplan |
If true, someone want to hard trigger replanning in the next step. | |
SymbolicState | _goal |
PlanExecutor | _planExecutor |
continual_planning_executive::PlannerInterface * | _planner |
ReplanningTriggerMethod | _replanningTrigger |
std::vector < continual_planning_executive::StateCreator * > | _stateCreators |
StatusPublisher | _status |
Friends | |
bool | loadActionExecutors (ros::NodeHandle &nh) |
bool | loadGoalCreators (ros::NodeHandle &nh) |
bool | loadPlanner (ros::NodeHandle &nh) |
bool | loadStateCreators (ros::NodeHandle &nh) |
void | signal_handler (int) |
The continual planning loop.
Definition at line 32 of file continualPlanning.h.
Definition at line 41 of file continualPlanning.h.
Definition at line 47 of file continualPlanning.h.
Definition at line 6 of file continualPlanning.cpp.
Definition at line 13 of file continualPlanning.cpp.
Update _currentState from the world.
Definition at line 105 of file continualPlanning.cpp.
bool ContinualPlanning::executeActionDirectly | ( | const DurativeAction & | a, |
bool | publishStatus | ||
) |
For debugging, just execute this action.
Definition at line 71 of file continualPlanning.cpp.
void ContinualPlanning::forceReplanning | ( | ) | [inline] |
Force replanning in the next loop.
Definition at line 73 of file continualPlanning.h.
bool ContinualPlanning::isGoalFulfilled | ( | ) | const |
Does _currentState match _goal?
Definition at line 100 of file continualPlanning.cpp.
Execute one loop step.
Definition at line 17 of file continualPlanning.cpp.
Plan ContinualPlanning::monitorAndReplan | ( | bool & | atGoal | ) | [protected] |
Return a plan that reaches the goal.
This might either be a copy of the current plan if that reaches the goal or a new plan.
[out] | atGoal | if the empty plan was successfully monitored, the atGoal flag is set to true |
Definition at line 118 of file continualPlanning.cpp.
bool ContinualPlanning::needReplanning | ( | bool & | atGoal | ) | const [protected] |
Returns true, if replanning needs to be done as _currentPlan in _currentState doesn't reach _goal.
[out] | atGoal | if the empty plan was successfully monitored, the atGoal flag is set to true |
Definition at line 149 of file continualPlanning.cpp.
bool loadActionExecutors | ( | ros::NodeHandle & | nh | ) | [friend] |
bool loadGoalCreators | ( | ros::NodeHandle & | nh | ) | [friend] |
bool loadPlanner | ( | ros::NodeHandle & | nh | ) | [friend] |
bool loadStateCreators | ( | ros::NodeHandle & | nh | ) | [friend] |
void signal_handler | ( | int | signal | ) | [friend] |
bool ContinualPlanning::_allowDirectGoalCheck [protected] |
Allow to check reached goal by using the _goal instead of monitoring.
Definition at line 104 of file continualPlanning.h.
Plan ContinualPlanning::_currentPlan [protected] |
Definition at line 99 of file continualPlanning.h.
SymbolicState ContinualPlanning::_currentState [protected] |
Definition at line 97 of file continualPlanning.h.
bool ContinualPlanning::_forceReplan [protected] |
If true, someone want to hard trigger replanning in the next step.
Definition at line 101 of file continualPlanning.h.
SymbolicState ContinualPlanning::_goal [protected] |
Definition at line 98 of file continualPlanning.h.
PlanExecutor ContinualPlanning::_planExecutor [protected] |
Definition at line 95 of file continualPlanning.h.
Definition at line 94 of file continualPlanning.h.
Definition at line 102 of file continualPlanning.h.
std::vector<continual_planning_executive::StateCreator*> ContinualPlanning::_stateCreators [protected] |
Definition at line 93 of file continualPlanning.h.
StatusPublisher ContinualPlanning::_status [protected] |
Definition at line 106 of file continualPlanning.h.