Public Member Functions | Protected Attributes
ActionExecutorService< Service > Class Template Reference

Templated base class for creating action executors that call a service for execution. More...

#include <actionExecutorService.hpp>

Inheritance diagram for ActionExecutorService< Service >:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 ActionExecutorService ()
virtual void cancelAction ()
 can't really do anything here
virtual bool canExecute (const DurativeAction &a, const SymbolicState &current) const
 Determine if the action can be executed by this implementation.
virtual bool executeBlocking (const DurativeAction &a, SymbolicState &current)
 Executes the action using SimpleActionClient.
virtual bool fillGoal (typename Service::Request &goal, const DurativeAction &a, const SymbolicState &current)=0
 Fill the goal to execute this action.
virtual void initialize (const std::deque< std::string > &arguments)
 Initialize the executor by creating the ServiceClient.
virtual void updateState (bool success, typename Service::Response &response, const DurativeAction &a, SymbolicState &current)
 Update the state after an action was executed.
 ~ActionExecutorService ()

Protected Attributes

std::string _actionName
ros::NodeHandle_nh
ros::ServiceClient _serviceClient

Detailed Description

template<class Service>
class ActionExecutorService< Service >

Templated base class for creating action executors that call a service for execution.

The class is templated over the service.

A minimal implementation should derive from this class (instantiating the template properly) and implement fillGoal.

canExecute can be overridden to test more specific than just the name. updateState can be used to update the planner state upon execution depending on the result of the execution.

Definition at line 20 of file actionExecutorService.hpp.


Constructor & Destructor Documentation

template<class Service >
ActionExecutorService< Service >::ActionExecutorService ( )

Definition at line 73 of file actionExecutorService.hpp.

template<class Service >
ActionExecutorService< Service >::~ActionExecutorService ( )

Definition at line 78 of file actionExecutorService.hpp.


Member Function Documentation

template<class Service >
virtual void ActionExecutorService< Service >::cancelAction ( ) [inline, virtual]

can't really do anything here

Implements continual_planning_executive::ActionExecutorInterface.

Definition at line 62 of file actionExecutorService.hpp.

template<class Service >
bool ActionExecutorService< Service >::canExecute ( const DurativeAction a,
const SymbolicState current 
) const [virtual]

Determine if the action can be executed by this implementation.

Default implementation only compares _actionName with the name of the DurativeAction.

Implements continual_planning_executive::ActionExecutorInterface.

Definition at line 109 of file actionExecutorService.hpp.

template<class Service >
bool ActionExecutorService< Service >::executeBlocking ( const DurativeAction a,
SymbolicState current 
) [virtual]

Executes the action using SimpleActionClient.

Implements continual_planning_executive::ActionExecutorInterface.

Definition at line 116 of file actionExecutorService.hpp.

template<class Service >
virtual bool ActionExecutorService< Service >::fillGoal ( typename Service::Request &  goal,
const DurativeAction a,
const SymbolicState current 
) [pure virtual]

Fill the goal to execute this action.

Parameters:
[out]goalthe goal to be filled (i.e. the service's request part).
[in]athe DurativeAction that is to be executed.
[in]currentthe current state where a should be executd.
template<class Service >
void ActionExecutorService< Service >::initialize ( const std::deque< std::string > &  arguments) [virtual]

Initialize the executor by creating the ServiceClient.

Parameters:
[in]argumentsshould be name of action (as in the plan), and the name of the service to connect to.

Reimplemented from continual_planning_executive::ActionExecutorInterface.

Definition at line 85 of file actionExecutorService.hpp.

template<class Service >
virtual void ActionExecutorService< Service >::updateState ( bool  success,
typename Service::Response &  response,
const DurativeAction a,
SymbolicState current 
) [inline, virtual]

Update the state after an action was executed.

Parameters:
[in]successthe return value of the service call
[in]responsewhat the call returned
[in]athe action that was executed
[in,out]currentthe current planner state to be updated

Definition at line 58 of file actionExecutorService.hpp.


Member Data Documentation

template<class Service >
std::string ActionExecutorService< Service >::_actionName [protected]

Definition at line 68 of file actionExecutorService.hpp.

template<class Service >
ros::NodeHandle* ActionExecutorService< Service >::_nh [protected]

Definition at line 65 of file actionExecutorService.hpp.

template<class Service >
ros::ServiceClient ActionExecutorService< Service >::_serviceClient [protected]

Definition at line 66 of file actionExecutorService.hpp.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


continual_planning_executive
Author(s): Christian Dornhege
autogenerated on Tue Jan 22 2013 12:24:43