Public Member Functions | Private Member Functions | Private Attributes | Friends
actionlib::ServerGoalHandle< ActionSpec > Class Template Reference

Encapsulates a state machine for a given goal that the user can trigger transisions on. All ROS interfaces for the goal are managed by the ActionServer to lessen the burden on the user. More...

#include <server_goal_handle.h>

List of all members.

Public Member Functions

boost::shared_ptr< const Goal > getGoal () const
 Accessor for the goal associated with the ServerGoalHandle.
actionlib_msgs::GoalID getGoalID () const
 Accessor for the goal id associated with the ServerGoalHandle.
actionlib_msgs::GoalStatus getGoalStatus () const
 Accessor for the status associated with the ServerGoalHandle.
bool operator!= (const ServerGoalHandle &other)
 != operator for ServerGoalHandles
ServerGoalHandleoperator= (const ServerGoalHandle &gh)
 Equals operator for a ServerGoalHandle.
bool operator== (const ServerGoalHandle &other)
 Equals operator for ServerGoalHandles.
void publishFeedback (const Feedback &feedback)
 Send feedback to any clients of the goal associated with this ServerGoalHandle.
 ServerGoalHandle ()
 Default constructor for a ServerGoalHandle.
 ServerGoalHandle (const ServerGoalHandle &gh)
 Copy constructor for a ServerGoalHandle.
void setAborted (const Result &result=Result(), const std::string &text=std::string(""))
 Set the status of the goal associated with the ServerGoalHandle to aborted.
void setAccepted (const std::string &text=std::string(""))
 Accept the goal referenced by the goal handle. This will transition to the ACTIVE state or the PREEMPTING state depending on whether a cancel request has been received for the goal.
void setCanceled (const Result &result=Result(), const std::string &text=std::string(""))
 Set the status of the goal associated with the ServerGoalHandle to RECALLED or PREEMPTED depending on what the current status of the goal is.
void setRejected (const Result &result=Result(), const std::string &text=std::string(""))
 Set the status of the goal associated with the ServerGoalHandle to rejected.
void setSucceeded (const Result &result=Result(), const std::string &text=std::string(""))
 Set the status of the goal associated with the ServerGoalHandle to succeeded.

Private Member Functions

 ACTION_DEFINITION (ActionSpec)
 ServerGoalHandle (typename std::list< StatusTracker< ActionSpec > >::iterator status_it, ActionServer< ActionSpec > *as, boost::shared_ptr< void > handle_tracker, boost::shared_ptr< DestructionGuard > guard)
 A private constructor used by the ActionServer to initialize a ServerGoalHandle.
bool setCancelRequested ()
 A private method to set status to PENDING or RECALLING.

Private Attributes

ActionServer< ActionSpec > * as_
boost::shared_ptr< const
ActionGoal > 
goal_
boost::shared_ptr
< DestructionGuard
guard_
boost::shared_ptr< void > handle_tracker_
std::list< StatusTracker
< ActionSpec > >::iterator 
status_it_

Friends

class ActionServer< ActionSpec >

Detailed Description

template<class ActionSpec>
class actionlib::ServerGoalHandle< ActionSpec >

Encapsulates a state machine for a given goal that the user can trigger transisions on. All ROS interfaces for the goal are managed by the ActionServer to lessen the burden on the user.

Definition at line 59 of file server_goal_handle.h.


Constructor & Destructor Documentation

template<class ActionSpec >
actionlib::ServerGoalHandle< ActionSpec >::ServerGoalHandle ( )

Default constructor for a ServerGoalHandle.

Definition at line 41 of file server_goal_handle_imp.h.

template<class ActionSpec >
actionlib::ServerGoalHandle< ActionSpec >::ServerGoalHandle ( const ServerGoalHandle< ActionSpec > &  gh)

Copy constructor for a ServerGoalHandle.

Parameters:
ghThe goal handle to copy

Definition at line 44 of file server_goal_handle_imp.h.

template<class ActionSpec >
actionlib::ServerGoalHandle< ActionSpec >::ServerGoalHandle ( typename std::list< StatusTracker< ActionSpec > >::iterator  status_it,
ActionServer< ActionSpec > *  as,
boost::shared_ptr< void >  handle_tracker,
boost::shared_ptr< DestructionGuard guard 
) [private]

A private constructor used by the ActionServer to initialize a ServerGoalHandle.

Definition at line 312 of file server_goal_handle_imp.h.


Member Function Documentation

template<class ActionSpec >
actionlib::ServerGoalHandle< ActionSpec >::ACTION_DEFINITION ( ActionSpec  ) [private]
template<class ActionSpec >
boost::shared_ptr< const typename ServerGoalHandle< ActionSpec >::Goal > actionlib::ServerGoalHandle< ActionSpec >::getGoal ( ) const

Accessor for the goal associated with the ServerGoalHandle.

Returns:
A shared_ptr to the goal object

Definition at line 239 of file server_goal_handle_imp.h.

template<class ActionSpec >
actionlib_msgs::GoalID actionlib::ServerGoalHandle< ActionSpec >::getGoalID ( ) const

Accessor for the goal id associated with the ServerGoalHandle.

Returns:
The goal id

Definition at line 250 of file server_goal_handle_imp.h.

template<class ActionSpec >
actionlib_msgs::GoalStatus actionlib::ServerGoalHandle< ActionSpec >::getGoalStatus ( ) const

Accessor for the status associated with the ServerGoalHandle.

Returns:
The goal status

Definition at line 267 of file server_goal_handle_imp.h.

template<class ActionSpec >
bool actionlib::ServerGoalHandle< ActionSpec >::operator!= ( const ServerGoalHandle< ActionSpec > &  other)

!= operator for ServerGoalHandles

Parameters:
otherThe ServerGoalHandle to compare to
Returns:
True if the ServerGoalHandles refer to different goals, false otherwise

Definition at line 307 of file server_goal_handle_imp.h.

template<class ActionSpec >
ServerGoalHandle< ActionSpec > & actionlib::ServerGoalHandle< ActionSpec >::operator= ( const ServerGoalHandle< ActionSpec > &  gh)

Equals operator for a ServerGoalHandle.

Parameters:
ghThe goal handle to copy

Definition at line 284 of file server_goal_handle_imp.h.

template<class ActionSpec >
bool actionlib::ServerGoalHandle< ActionSpec >::operator== ( const ServerGoalHandle< ActionSpec > &  other)

Equals operator for ServerGoalHandles.

Parameters:
otherThe ServerGoalHandle to compare to
Returns:
True if the ServerGoalHandles refer to the same goal, false otherwise

Definition at line 294 of file server_goal_handle_imp.h.

template<class ActionSpec >
void actionlib::ServerGoalHandle< ActionSpec >::publishFeedback ( const Feedback &  feedback)

Send feedback to any clients of the goal associated with this ServerGoalHandle.

Parameters:
feedbackThe feedback to send to the client

Definition at line 216 of file server_goal_handle_imp.h.

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

Set the status of the goal associated with the ServerGoalHandle to aborted.

Parameters:
resultOptionally, the user can pass in a result to be sent to any clients of the goal
textOptionally, any text message about the status change being made that should be passed to the client

Definition at line 154 of file server_goal_handle_imp.h.

template<class ActionSpec >
void actionlib::ServerGoalHandle< ActionSpec >::setAccepted ( const std::string &  text = std::string(""))

Accept the goal referenced by the goal handle. This will transition to the ACTIVE state or the PREEMPTING state depending on whether a cancel request has been received for the goal.

Parameters:
textOptionally, any text message about the status change being made that should be passed to the client

Definition at line 48 of file server_goal_handle_imp.h.

template<class ActionSpec >
void actionlib::ServerGoalHandle< ActionSpec >::setCanceled ( const Result &  result = Result(),
const std::string &  text = std::string("") 
)

Set the status of the goal associated with the ServerGoalHandle to RECALLED or PREEMPTED depending on what the current status of the goal is.

Parameters:
resultOptionally, the user can pass in a result to be sent to any clients of the goal
textOptionally, any text message about the status change being made that should be passed to the client

Definition at line 87 of file server_goal_handle_imp.h.

template<class ActionSpec >
bool actionlib::ServerGoalHandle< ActionSpec >::setCancelRequested ( ) [private]

A private method to set status to PENDING or RECALLING.

Returns:
True if the cancel request should be passed on to the user, false otherwise

Definition at line 318 of file server_goal_handle_imp.h.

template<class ActionSpec >
void actionlib::ServerGoalHandle< ActionSpec >::setRejected ( const Result &  result = Result(),
const std::string &  text = std::string("") 
)

Set the status of the goal associated with the ServerGoalHandle to rejected.

Parameters:
resultOptionally, the user can pass in a result to be sent to any clients of the goal
textOptionally, any text message about the status change being made that should be passed to the client

Definition at line 123 of file server_goal_handle_imp.h.

template<class ActionSpec >
void actionlib::ServerGoalHandle< ActionSpec >::setSucceeded ( const Result &  result = Result(),
const std::string &  text = std::string("") 
)

Set the status of the goal associated with the ServerGoalHandle to succeeded.

Parameters:
resultOptionally, the user can pass in a result to be sent to any clients of the goal
textOptionally, any text message about the status change being made that should be passed to the client

Definition at line 185 of file server_goal_handle_imp.h.


Friends And Related Function Documentation

template<class ActionSpec >
friend class ActionServer< ActionSpec > [friend]

Definition at line 174 of file server_goal_handle.h.


Member Data Documentation

template<class ActionSpec >
ActionServer<ActionSpec>* actionlib::ServerGoalHandle< ActionSpec >::as_ [private]

Definition at line 171 of file server_goal_handle.h.

template<class ActionSpec >
boost::shared_ptr<const ActionGoal> actionlib::ServerGoalHandle< ActionSpec >::goal_ [private]

Definition at line 170 of file server_goal_handle.h.

template<class ActionSpec >
boost::shared_ptr<DestructionGuard> actionlib::ServerGoalHandle< ActionSpec >::guard_ [private]

Definition at line 173 of file server_goal_handle.h.

template<class ActionSpec >
boost::shared_ptr<void> actionlib::ServerGoalHandle< ActionSpec >::handle_tracker_ [private]

Definition at line 172 of file server_goal_handle.h.

template<class ActionSpec >
std::list<StatusTracker<ActionSpec> >::iterator actionlib::ServerGoalHandle< ActionSpec >::status_it_ [private]

Definition at line 169 of file server_goal_handle.h.


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


actionlib
Author(s): Eitan Marder-Eppstein, Vijay Pradeep
autogenerated on Thu Jan 2 2014 11:03:50