Public Types | Public Member Functions | Private Member Functions | Private Attributes
IriActionServer< ActionSpec > Class Template Reference

IRI ROS Action Server. More...

#include <iri_action_server.h>

List of all members.

Public Types

typedef boost::shared_ptr
< Feedback > 
FeedbackPtr
 Result Pointer type definition.
typedef boost::shared_ptr< Result > ResultPtr
 Result Pointer type definition.

Public Member Functions

 ACTION_DEFINITION (ActionSpec)
 Action definitions macro.
 IriActionServer (ros::NodeHandle &nh, const std::string &action_name)
 Constructor.
bool isActive (void)
 Action is Active.
bool isStarted (void) const
 Server has been started?
void registerGetFeedbackCallback (boost::function< void(FeedbackPtr &)> cb)
 Register Get Feedback Callback.
void registerGetResultCallback (boost::function< void(ResultPtr &)> cb)
 Register Get Result Callback.
void registerHasSucceedCallback (boost::function< bool()> cb)
 Register Has Succeed Callback.
void registerIsFinishedCallback (boost::function< bool()> cb)
 Register Is Finished Callback.
void registerStartCallback (boost::function< void(const GoalConstPtr &)> cb)
 Register Start Callback.
void registerStopCallback (boost::function< void()> cb)
 Register Stop Callback.
void setAborted (const Result &result=Result(), const std::string &text=std::string(""))
 Abort Action.
void setLoopRate (ros::Rate r)
 Set Loop Rate.
void setPreempted (const Result &result=Result(), const std::string &text=std::string(""))
 Preempt Action.
void shutdown (void)
 Stop Action.
void start (void)
 Start Action.
 ~IriActionServer (void)
 Destructor.

Private Member Functions

void executeCallback (const GoalConstPtr &goal)
 Execute Callback.

Private Attributes

std::string action_name_
 Action Name.
actionlib::SimpleActionServer
< ActionSpec > 
as_
 Simple Action Server.
boost::function< void(FeedbackPtr &)> get_feedback_callback_
 Get Feedback Callback object.
boost::function< void(ResultPtr &)> get_result_callback_
 Get Result Callback object.
boost::function< bool()> has_succeed_callback_
 Has Succeed Callback object.
boost::function< bool()> is_finished_callback_
 Is Finished Callback object.
bool is_started
 Is Started.
ros::Rate loop_rate_
 Loop Rate.
boost::function< void(const
GoalConstPtr &)> 
start_action_callback_
 Start Callback object.
boost::function< void()> stop_action_callback_
 Stop Callback object.

Detailed Description

template<class ActionSpec>
class IriActionServer< ActionSpec >

IRI ROS Action Server.

This class is a wrapper for the ROS Simple Action Server, thus their policies are adquired. The action server logic for receiving new goals, controlling client preemption and dealing with goal status has been implemented on top of the simple action server. Instead of working straight with the provided execute callback, this class defines additional callbacks to the user with a more reduced scope. By using this class, the final user just needs to worry about executing and cancelling the action and filling up feedback and result messages.

This is a template class, where ActionSpec must be a class generated from an action message. Goal, Result and Feedback objects are assumed to exist.

Definition at line 48 of file iri_action_server.h.


Member Typedef Documentation

template<class ActionSpec >
typedef boost::shared_ptr<Feedback> IriActionServer< ActionSpec >::FeedbackPtr

Result Pointer type definition.

Additional definition for non-constant feedback pointers

Definition at line 71 of file iri_action_server.h.

template<class ActionSpec >
typedef boost::shared_ptr<Result> IriActionServer< ActionSpec >::ResultPtr

Result Pointer type definition.

Additional definition for non-constant result pointers

Definition at line 64 of file iri_action_server.h.


Constructor & Destructor Documentation

template<class ActionSpec >
IriActionServer< ActionSpec >::IriActionServer ( ros::NodeHandle nh,
const std::string &  action_name 
)

Constructor.

This constructor mainly initializes the ROS simple action server object, as well as the action name and the execute loop rate frequency.

Parameters:
nha reference to the node handle object to manage all ROS topics.
action_namename of the action

Definition at line 329 of file iri_action_server.h.

template<class ActionSpec >
IriActionServer< ActionSpec >::~IriActionServer ( void  )

Destructor.

This destructor is called when the object is about to be destroyed.

Definition at line 339 of file iri_action_server.h.


Member Function Documentation

template<class ActionSpec >
IriActionServer< ActionSpec >::ACTION_DEFINITION ( ActionSpec  )

Action definitions macro.

This ROS defined macro includes convenient type definitions for Goal, Result and Feedback classes to ease developement.

template<class ActionSpec >
void IriActionServer< ActionSpec >::executeCallback ( const GoalConstPtr &  goal) [private]

Execute Callback.

This is the ROS simple action server execute callback which is called in a separate thread whenever a new goal is received. This function implements the IRI action server logic on top of the ROS simple action server policy.

This function controls the life-cycle of a single goal, since it is received until achieves a terminal state. User callbacks are triggered to monitor the goal state during the action execution.

Parameters:
GoalConstPtra const pointer to the received action goal

Definition at line 407 of file iri_action_server.h.

template<class ActionSpec >
bool IriActionServer< ActionSpec >::isActive ( void  )

Action is Active.

Allows polling implementations to query about the status of the current goal

Returns:
True if a goal is active, false otherwise

Definition at line 401 of file iri_action_server.h.

template<class ActionSpec >
bool IriActionServer< ActionSpec >::isStarted ( void  ) const

Server has been started?

This function returns true if start() has been previously called.

Definition at line 376 of file iri_action_server.h.

template<class ActionSpec >
void IriActionServer< ActionSpec >::registerGetFeedbackCallback ( boost::function< void(FeedbackPtr &)>  cb)

Register Get Feedback Callback.

This method let's the user register the get feedback callback method

Parameters:
cbuser callback function with input parameter FeedbackPtr

Definition at line 514 of file iri_action_server.h.

template<class ActionSpec >
void IriActionServer< ActionSpec >::registerGetResultCallback ( boost::function< void(ResultPtr &)>  cb)

Register Get Result Callback.

This method let's the user register the get result callback method

Parameters:
cbuser callback function with input parameter ResultPtr

Definition at line 508 of file iri_action_server.h.

template<class ActionSpec >
void IriActionServer< ActionSpec >::registerHasSucceedCallback ( boost::function< bool()>  cb)

Register Has Succeed Callback.

This method let's the user register the has succeed callback method

Parameters:
cbuser callback function with no input parameters, returns boolean

Definition at line 502 of file iri_action_server.h.

template<class ActionSpec >
void IriActionServer< ActionSpec >::registerIsFinishedCallback ( boost::function< bool()>  cb)

Register Is Finished Callback.

This method let's the user register the is finished callback method

Parameters:
cbuser callback function with no input parameters, returns boolean

Definition at line 496 of file iri_action_server.h.

template<class ActionSpec >
void IriActionServer< ActionSpec >::registerStartCallback ( boost::function< void(const GoalConstPtr &)>  cb)

Register Start Callback.

This method let's the user register the start callback method

Parameters:
cbuser callback function with input parameter GoalConstPtr

Definition at line 484 of file iri_action_server.h.

template<class ActionSpec >
void IriActionServer< ActionSpec >::registerStopCallback ( boost::function< void()>  cb)

Register Stop Callback.

This method let's the user register the stop callback method

Parameters:
cbuser callback function with no input parameters

Definition at line 490 of file iri_action_server.h.

template<class ActionSpec >
void IriActionServer< ActionSpec >::setAborted ( const Result &  result = Result(),
const std::string &  text = std::string("") 
)

Abort Action.

Calls the ROS simple action server to abort current action

Parameters:
resultAn optional result to send back to any clients of the goal
textAn optional text message to send back to any clients of the goal

Definition at line 389 of file iri_action_server.h.

template<class ActionSpec >
void IriActionServer< ActionSpec >::setLoopRate ( ros::Rate  r)

Set Loop Rate.

This function sets the loop rate for the execute callback

Definition at line 349 of file iri_action_server.h.

template<class ActionSpec >
void IriActionServer< ActionSpec >::setPreempted ( const Result &  result = Result(),
const std::string &  text = std::string("") 
)

Preempt Action.

Calls the ROS simple action server to preempt current action

Parameters:
resultAn optional result to send back to any clients of the goal
textAn optional text message to send back to any clients of the goal

Definition at line 395 of file iri_action_server.h.

template<class ActionSpec >
void IriActionServer< ActionSpec >::shutdown ( void  )

Stop Action.

Calls the ROS simple action server to shutdown the current action

Definition at line 382 of file iri_action_server.h.

template<class ActionSpec >
void IriActionServer< ActionSpec >::start ( void  )

Start Action.

This function checks whether all user callbacks have been registered and then starts the simple action server.

Definition at line 355 of file iri_action_server.h.


Member Data Documentation

template<class ActionSpec >
std::string IriActionServer< ActionSpec >::action_name_ [private]

Action Name.

This string stores the action name used to request actions.

Definition at line 167 of file iri_action_server.h.

template<class ActionSpec >
actionlib::SimpleActionServer<ActionSpec> IriActionServer< ActionSpec >::as_ [private]

Simple Action Server.

The ROS simple action server is used to handle action requests. For complete information on its behaviour please refer to: http://www.ros.org/wiki/actionlib/DetailedDescription

Definition at line 176 of file iri_action_server.h.

template<class ActionSpec >
boost::function<void (FeedbackPtr&)> IriActionServer< ActionSpec >::get_feedback_callback_ [private]

Get Feedback Callback object.

Boost function object to bind user callback. The get result callback is called on each iteration of the simple action server execute callback while the action is active. User must fill up the feedback object to leave it ready to be published.

The user defined function must receive a FeedbackPtr and return void.

Definition at line 145 of file iri_action_server.h.

template<class ActionSpec >
boost::function<void (ResultPtr&)> IriActionServer< ActionSpec >::get_result_callback_ [private]

Get Result Callback object.

Boost function object to bind user callback. The get result callback is called from the simple action server execute callback when the action has finished. User must fill up the result object with the convenient data depending on wether the action accomplished its goal or was aborted.

The user defined function must receive a ResultPtr and return void.

Definition at line 133 of file iri_action_server.h.

template<class ActionSpec >
boost::function<bool ()> IriActionServer< ActionSpec >::has_succeed_callback_ [private]

Has Succeed Callback object.

Boost function object to bind user callback. The has succeeded callback is called from the simple action server execute callback when the action has finished.

The user defined function takes no parameters and returns a boolean indicating if the action successfully accomplished its goal (true) or if it was aborted (false).

Definition at line 121 of file iri_action_server.h.

template<class ActionSpec >
boost::function<bool ()> IriActionServer< ActionSpec >::is_finished_callback_ [private]

Is Finished Callback object.

Boost function object to bind user callback. The is finished callback is called from the simple action server execute callback to check whether the action has been finished or not. An action can finish either because it accomplished its goal or because it has been aborted.

The user defined function takes no parameters and returns a boolean indicating if the action is finished or not.

Definition at line 108 of file iri_action_server.h.

template<class ActionSpec >
bool IriActionServer< ActionSpec >::is_started [private]

Is Started.

This variable is set to true when start() is called and to false when calling shutdown().

Definition at line 192 of file iri_action_server.h.

template<class ActionSpec >
ros::Rate IriActionServer< ActionSpec >::loop_rate_ [private]

Loop Rate.

This object controls the frequency of the execution callback loop. The value can be updated by calling the member method setLoopRate.

Definition at line 184 of file iri_action_server.h.

template<class ActionSpec >
boost::function<void (const GoalConstPtr&)> IriActionServer< ActionSpec >::start_action_callback_ [private]

Start Callback object.

Boost function object to bind user callback. The start callback is called once at the beginning of the simple action server execute callback. User may use the Goal object to start the action within this callback.

The user defined function must receive a GoalConstPtr and return void.

Definition at line 84 of file iri_action_server.h.

template<class ActionSpec >
boost::function<void ()> IriActionServer< ActionSpec >::stop_action_callback_ [private]

Stop Callback object.

Boost function object to bind user callback. The stop callback is called whenever the client requests a preempt or the action fails for some other reason. User may stop the action and get ready to receieve another goal.

The user defined function takes no parameters and returns void.

Definition at line 95 of file iri_action_server.h.


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


iri_action_server
Author(s): Joan Perez, jnperez at iri.upc.edu
autogenerated on Fri Dec 6 2013 19:58:20