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

Encapsulates a state machine for a given goal that the user can trigger transitions 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. More...
 
actionlib_msgs::GoalID getGoalID () const
 Accessor for the goal id associated with the ServerGoalHandle. More...
 
actionlib_msgs::GoalStatus getGoalStatus () const
 Accessor for the status associated with the ServerGoalHandle. More...
 
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. More...
 
bool operator!= (const ServerGoalHandle &other) const
 != operator for ServerGoalHandles More...
 
ServerGoalHandleoperator= (const ServerGoalHandle &gh)
 Equals operator for a ServerGoalHandle. More...
 
bool operator== (const ServerGoalHandle &other) const
 Equals operator for ServerGoalHandles. More...
 
void publishFeedback (const Feedback &feedback)
 Send feedback to any clients of the goal associated with this ServerGoalHandle. More...
 
 ServerGoalHandle ()
 Default constructor for a ServerGoalHandle. More...
 
 ServerGoalHandle (const ServerGoalHandle &gh)
 Copy constructor for a ServerGoalHandle. More...
 
void setAborted (const Result &result=Result(), const std::string &text=std::string(""))
 Set the status of the goal associated with the ServerGoalHandle to aborted. More...
 
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. More...
 
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. More...
 
void setRejected (const Result &result=Result(), const std::string &text=std::string(""))
 Set the status of the goal associated with the ServerGoalHandle to rejected. More...
 
void setSucceeded (const Result &result=Result(), const std::string &text=std::string(""))
 Set the status of the goal associated with the ServerGoalHandle to succeeded. More...
 

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. More...
 
bool setCancelRequested ()
 A private method to set status to PENDING or RECALLING. More...
 

Private Attributes

ActionServerBase< ActionSpec > * as_
 
boost::shared_ptr< const ActionGoal > goal_
 
boost::shared_ptr< DestructionGuardguard_
 
boost::shared_ptr< void > handle_tracker_
 
std::list< StatusTracker< ActionSpec > >::iterator status_it_
 

Friends

class ActionServerBase< ActionSpec >
 

Detailed Description

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

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

Definition at line 63 of file server_goal_handle.h.

Constructor & Destructor Documentation

◆ ServerGoalHandle() [1/3]

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

Default constructor for a ServerGoalHandle.

Definition at line 48 of file server_goal_handle_imp.h.

◆ ServerGoalHandle() [2/3]

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 52 of file server_goal_handle_imp.h.

◆ ServerGoalHandle() [3/3]

template<class ActionSpec >
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 373 of file server_goal_handle_imp.h.

Member Function Documentation

◆ ACTION_DEFINITION()

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

◆ getGoal()

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 292 of file server_goal_handle_imp.h.

◆ getGoalID()

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 304 of file server_goal_handle_imp.h.

◆ getGoalStatus()

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 322 of file server_goal_handle_imp.h.

◆ isValid()

template<class ActionSpec >
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.

Returns
True if valid, False if invalid

Definition at line 285 of file server_goal_handle_imp.h.

◆ operator!=()

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

!= operator for ServerGoalHandles

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

Definition at line 367 of file server_goal_handle_imp.h.

◆ operator=()

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 340 of file server_goal_handle_imp.h.

◆ operator==()

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

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 351 of file server_goal_handle_imp.h.

◆ publishFeedback()

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 257 of file server_goal_handle_imp.h.

◆ setAborted()

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 181 of file server_goal_handle_imp.h.

◆ setAccepted()

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 57 of file server_goal_handle_imp.h.

◆ setCanceled()

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 100 of file server_goal_handle_imp.h.

◆ setCancelRequested()

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 381 of file server_goal_handle_imp.h.

◆ setRejected()

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 143 of file server_goal_handle_imp.h.

◆ setSucceeded()

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 219 of file server_goal_handle_imp.h.

Friends And Related Function Documentation

◆ ActionServerBase< ActionSpec >

template<class ActionSpec >
friend class ActionServerBase< ActionSpec >
friend

Definition at line 190 of file server_goal_handle.h.

Member Data Documentation

◆ as_

template<class ActionSpec >
ActionServerBase<ActionSpec>* actionlib::ServerGoalHandle< ActionSpec >::as_
private

Definition at line 187 of file server_goal_handle.h.

◆ goal_

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

Definition at line 186 of file server_goal_handle.h.

◆ guard_

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

Definition at line 189 of file server_goal_handle.h.

◆ handle_tracker_

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

Definition at line 188 of file server_goal_handle.h.

◆ status_it_

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

Definition at line 185 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, Mikael Arguedas
autogenerated on Mon Feb 28 2022 21:34:39