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>
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 | isValid () const |
Determine if the goal handle is valid (tracking a valid goal, and associated with a valid action server). If the handle is valid, it means that the accessors getGoal, getGoalID, etc, can be called without generating errors. | |
bool | operator!= (const ServerGoalHandle &other) const |
!= operator for ServerGoalHandles | |
ServerGoalHandle & | operator= (const ServerGoalHandle &gh) |
Equals operator for a ServerGoalHandle. | |
bool | operator== (const ServerGoalHandle &other) const |
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, ActionServerBase< 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 | |
ActionServerBase< 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 | ActionServerBase< 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.
actionlib::ServerGoalHandle< ActionSpec >::ServerGoalHandle | ( | ) |
Default constructor for a ServerGoalHandle.
Definition at line 41 of file server_goal_handle_imp.h.
actionlib::ServerGoalHandle< ActionSpec >::ServerGoalHandle | ( | const ServerGoalHandle< ActionSpec > & | gh | ) |
Copy constructor for a ServerGoalHandle.
gh | The goal handle to copy |
Definition at line 44 of file server_goal_handle_imp.h.
actionlib::ServerGoalHandle< ActionSpec >::ServerGoalHandle | ( | typename std::list< StatusTracker< ActionSpec > >::iterator | status_it, |
ActionServerBase< 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 317 of file server_goal_handle_imp.h.
actionlib::ServerGoalHandle< ActionSpec >::ACTION_DEFINITION | ( | ActionSpec | ) | [private] |
boost::shared_ptr< const typename ServerGoalHandle< ActionSpec >::Goal > actionlib::ServerGoalHandle< ActionSpec >::getGoal | ( | ) | const |
Accessor for the goal associated with the ServerGoalHandle.
Definition at line 244 of file server_goal_handle_imp.h.
actionlib_msgs::GoalID actionlib::ServerGoalHandle< ActionSpec >::getGoalID | ( | ) | const |
Accessor for the goal id associated with the ServerGoalHandle.
Definition at line 255 of file server_goal_handle_imp.h.
actionlib_msgs::GoalStatus actionlib::ServerGoalHandle< ActionSpec >::getGoalStatus | ( | ) | const |
Accessor for the status associated with the ServerGoalHandle.
Definition at line 272 of file server_goal_handle_imp.h.
bool actionlib::ServerGoalHandle< ActionSpec >::isValid | ( | ) | const |
Determine if the goal handle is valid (tracking a valid goal, and associated with a valid action server). If the handle is valid, it means that the accessors getGoal, getGoalID, etc, can be called without generating errors.
Definition at line 239 of file server_goal_handle_imp.h.
bool actionlib::ServerGoalHandle< ActionSpec >::operator!= | ( | const ServerGoalHandle< ActionSpec > & | other | ) | const |
!= operator for ServerGoalHandles
other | The ServerGoalHandle to compare to |
Definition at line 312 of file server_goal_handle_imp.h.
ServerGoalHandle< ActionSpec > & actionlib::ServerGoalHandle< ActionSpec >::operator= | ( | const ServerGoalHandle< ActionSpec > & | gh | ) |
Equals operator for a ServerGoalHandle.
gh | The goal handle to copy |
Definition at line 289 of file server_goal_handle_imp.h.
bool actionlib::ServerGoalHandle< ActionSpec >::operator== | ( | const ServerGoalHandle< ActionSpec > & | other | ) | const |
Equals operator for ServerGoalHandles.
other | The ServerGoalHandle to compare to |
Definition at line 299 of file server_goal_handle_imp.h.
void actionlib::ServerGoalHandle< ActionSpec >::publishFeedback | ( | const Feedback & | feedback | ) |
Send feedback to any clients of the goal associated with this ServerGoalHandle.
feedback | The feedback to send to the client |
Definition at line 216 of file server_goal_handle_imp.h.
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.
result | Optionally, the user can pass in a result to be sent to any clients of the goal |
text | Optionally, 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.
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.
text | Optionally, 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.
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.
result | Optionally, the user can pass in a result to be sent to any clients of the goal |
text | Optionally, 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.
bool actionlib::ServerGoalHandle< ActionSpec >::setCancelRequested | ( | ) | [private] |
A private method to set status to PENDING or RECALLING.
Definition at line 323 of file server_goal_handle_imp.h.
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.
result | Optionally, the user can pass in a result to be sent to any clients of the goal |
text | Optionally, 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.
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.
result | Optionally, the user can pass in a result to be sent to any clients of the goal |
text | Optionally, 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.
friend class ActionServerBase< ActionSpec > [friend] |
Definition at line 184 of file server_goal_handle.h.
ActionServerBase<ActionSpec>* actionlib::ServerGoalHandle< ActionSpec >::as_ [private] |
Definition at line 181 of file server_goal_handle.h.
boost::shared_ptr<const ActionGoal> actionlib::ServerGoalHandle< ActionSpec >::goal_ [private] |
Definition at line 180 of file server_goal_handle.h.
boost::shared_ptr<DestructionGuard> actionlib::ServerGoalHandle< ActionSpec >::guard_ [private] |
Definition at line 183 of file server_goal_handle.h.
boost::shared_ptr<void> actionlib::ServerGoalHandle< ActionSpec >::handle_tracker_ [private] |
Definition at line 182 of file server_goal_handle.h.
std::list<StatusTracker<ActionSpec> >::iterator actionlib::ServerGoalHandle< ActionSpec >::status_it_ [private] |
Definition at line 179 of file server_goal_handle.h.