Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | Friends
ContinualPlanning Class Reference

The continual planning loop. More...

#include <continualPlanning.h>

List of all members.

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)

Detailed Description

The continual planning loop.

Definition at line 32 of file continualPlanning.h.


Member Enumeration Documentation

Enumerator:
Running 
FinishedNoPlanToGoal 
FinishedAtGoal 

Definition at line 41 of file continualPlanning.h.

Enumerator:
ReplanAlways 
ReplanIfLogicalStateChanged 
ReplanByMonitoring 

Definition at line 47 of file continualPlanning.h.


Constructor & Destructor Documentation

Definition at line 6 of file continualPlanning.cpp.

Definition at line 13 of file continualPlanning.cpp.


Member Function Documentation

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.

Force replanning in the next loop.

Definition at line 73 of file continualPlanning.h.

Does _currentState match _goal?

Definition at line 100 of file continualPlanning.cpp.

Execute one loop step.

Returns:
Running, if the planning loop should continue

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.

Parameters:
[out]atGoalif the empty plan was successfully monitored, the atGoal flag is set to true
Returns:
a new plan that reaches _goal or an empty plan, if no plan could be found

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.

Parameters:
[out]atGoalif the empty plan was successfully monitored, the atGoal flag is set to true

Definition at line 149 of file continualPlanning.cpp.


Friends And Related Function Documentation

bool loadActionExecutors ( ros::NodeHandle nh) [friend]

Definition at line 153 of file main.cpp.

bool loadGoalCreators ( ros::NodeHandle nh) [friend]

Definition at line 96 of file main.cpp.

bool loadPlanner ( ros::NodeHandle nh) [friend]

Definition at line 206 of file main.cpp.

bool loadStateCreators ( ros::NodeHandle nh) [friend]

Definition at line 43 of file main.cpp.

void signal_handler ( int  signal) [friend]

Definition at line 339 of file main.cpp.


Member Data Documentation

Allow to check reached goal by using the _goal instead of monitoring.

Definition at line 104 of file continualPlanning.h.

Definition at line 99 of file continualPlanning.h.

Definition at line 97 of file continualPlanning.h.

If true, someone want to hard trigger replanning in the next step.

Definition at line 101 of file continualPlanning.h.

Definition at line 98 of file continualPlanning.h.

Definition at line 95 of file continualPlanning.h.

Definition at line 94 of file continualPlanning.h.

Definition at line 102 of file continualPlanning.h.

Definition at line 93 of file continualPlanning.h.

Definition at line 106 of file continualPlanning.h.


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


continual_planning_executive
Author(s): Christian Dornhege
autogenerated on Mon Oct 6 2014 07:51:56