Templated base class for creating action executors that call a service for execution. More...
#include <actionExecutorService.hpp>
Public Member Functions | |
ActionExecutorService () | |
virtual void | cancelAction () |
can't really do anything here | |
virtual bool | canExecute (const DurativeAction &a, const SymbolicState ¤t) const |
Determine if the action can be executed by this implementation. | |
virtual bool | executeBlocking (const DurativeAction &a, SymbolicState ¤t) |
Executes the action using SimpleActionClient. | |
virtual bool | fillGoal (typename Service::Request &goal, const DurativeAction &a, const SymbolicState ¤t)=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 ¤t) |
Update the state after an action was executed. | |
~ActionExecutorService () | |
Protected Attributes | |
std::string | _actionName |
ros::NodeHandle * | _nh |
ros::ServiceClient | _serviceClient |
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.
ActionExecutorService< Service >::ActionExecutorService | ( | ) |
Definition at line 73 of file actionExecutorService.hpp.
ActionExecutorService< Service >::~ActionExecutorService | ( | ) |
Definition at line 78 of file actionExecutorService.hpp.
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.
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.
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.
virtual bool ActionExecutorService< Service >::fillGoal | ( | typename Service::Request & | goal, |
const DurativeAction & | a, | ||
const SymbolicState & | current | ||
) | [pure virtual] |
Fill the goal to execute this action.
[out] | goal | the goal to be filled (i.e. the service's request part). |
[in] | a | the DurativeAction that is to be executed. |
[in] | current | the current state where a should be executd. |
void ActionExecutorService< Service >::initialize | ( | const std::deque< std::string > & | arguments | ) | [virtual] |
Initialize the executor by creating the ServiceClient.
[in] | arguments | should 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.
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.
[in] | success | the return value of the service call |
[in] | response | what the call returned |
[in] | a | the action that was executed |
[in,out] | current | the current planner state to be updated |
Definition at line 58 of file actionExecutorService.hpp.
std::string ActionExecutorService< Service >::_actionName [protected] |
Definition at line 68 of file actionExecutorService.hpp.
ros::NodeHandle* ActionExecutorService< Service >::_nh [protected] |
Definition at line 65 of file actionExecutorService.hpp.
ros::ServiceClient ActionExecutorService< Service >::_serviceClient [protected] |
Definition at line 66 of file actionExecutorService.hpp.