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

Client side handle to monitor goal progress. More...

#include <client_helpers.h>

Public Member Functions

void cancel ()
 Sends a cancel message for this specific goal to the ActionServer. More...
 
 ClientGoalHandle ()
 Create an empty goal handle. More...
 
CommState getCommState () const
 Get the state of this goal's communication state machine from interaction with the server. More...
 
ResultConstPtr getResult () const
 Get result associated with this goal. More...
 
TerminalState getTerminalState () const
 Get the terminal state information for this goal. More...
 
bool isExpired () const
 Checks if this goal handle is tracking a goal. More...
 
bool operator!= (const ClientGoalHandle< ActionSpec > &rhs) const
 !(operator==()) More...
 
bool operator== (const ClientGoalHandle< ActionSpec > &rhs) const
 Check if two goal handles point to the same goal. More...
 
void resend ()
 Resends this goal [with the same GoalID] to the ActionServer. More...
 
void reset ()
 Stops goal handle from tracking a goal. More...
 
 ~ClientGoalHandle ()
 

Private Types

typedef GoalManager< ActionSpec > GoalManagerT
 
typedef ManagedList< boost::shared_ptr< CommStateMachine< ActionSpec > > > ManagedListT
 

Private Member Functions

 ACTION_DEFINITION (ActionSpec)
 
 ClientGoalHandle (GoalManagerT *gm, typename ManagedListT::Handle handle, const boost::shared_ptr< DestructionGuard > &guard)
 

Private Attributes

bool active_
 
GoalManagerTgm_
 
boost::shared_ptr< DestructionGuardguard_
 
ManagedListT::Handle list_handle_
 

Friends

class GoalManager< ActionSpec >
 

Detailed Description

template<class ActionSpec>
class actionlib::ClientGoalHandle< ActionSpec >

Client side handle to monitor goal progress.

A ClientGoalHandle is a reference counted object that is used to manipulate and monitor the progress of an already dispatched goal. Once all the goal handles go out of scope (or are reset), an ActionClient stops maintaining state for that goal.

Definition at line 64 of file client_helpers.h.

Member Typedef Documentation

◆ GoalManagerT

template<class ActionSpec>
typedef GoalManager<ActionSpec> actionlib::ClientGoalHandle< ActionSpec >::GoalManagerT
private

Definition at line 207 of file client_helpers.h.

◆ ManagedListT

template<class ActionSpec>
typedef ManagedList<boost::shared_ptr<CommStateMachine<ActionSpec> > > actionlib::ClientGoalHandle< ActionSpec >::ManagedListT
private

Definition at line 208 of file client_helpers.h.

Constructor & Destructor Documentation

◆ ClientGoalHandle() [1/2]

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

Create an empty goal handle.

Constructs a goal handle that doesn't track any goal. Calling any method on an empty goal handle other than operator= will trigger an assertion.

Definition at line 47 of file client_goal_handle_imp.h.

◆ ~ClientGoalHandle()

template<class ActionSpec >
actionlib::ClientGoalHandle< ActionSpec >::~ClientGoalHandle ( )

Definition at line 54 of file client_goal_handle_imp.h.

◆ ClientGoalHandle() [2/2]

template<class ActionSpec >
actionlib::ClientGoalHandle< ActionSpec >::ClientGoalHandle ( GoalManagerT gm,
typename ManagedListT::Handle  handle,
const boost::shared_ptr< DestructionGuard > &  guard 
)
private

Definition at line 60 of file client_goal_handle_imp.h.

Member Function Documentation

◆ ACTION_DEFINITION()

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

◆ cancel()

template<class ActionSpec >
void actionlib::ClientGoalHandle< ActionSpec >::cancel ( )

Sends a cancel message for this specific goal to the ActionServer.

Also transitions the Communication State Machine to WAITING_FOR_CANCEL_ACK

Definition at line 242 of file client_goal_handle_imp.h.

◆ getCommState()

template<class ActionSpec >
CommState actionlib::ClientGoalHandle< ActionSpec >::getCommState ( ) const

Get the state of this goal's communication state machine from interaction with the server.

Possible States are: WAITING_FOR_GOAL_ACK, PENDING, ACTIVE, WAITING_FOR_RESULT, WAITING_FOR_CANCEL_ACK, RECALLING, PREEMPTING, DONE

Returns
The current goal's communication state with the server

Definition at line 96 of file client_goal_handle_imp.h.

◆ getResult()

template<class ActionSpec >
ClientGoalHandle< ActionSpec >::ResultConstPtr actionlib::ClientGoalHandle< ActionSpec >::getResult ( ) const

Get result associated with this goal.

Returns
NULL if no result received. Otherwise returns shared_ptr to result.

Definition at line 182 of file client_goal_handle_imp.h.

◆ getTerminalState()

template<class ActionSpec >
TerminalState actionlib::ClientGoalHandle< ActionSpec >::getTerminalState ( ) const

Get the terminal state information for this goal.

Possible States Are: RECALLED, REJECTED, PREEMPTED, ABORTED, SUCCEEDED, LOST This call only makes sense if CommState==DONE. This will send ROS_WARNs if we're not in DONE

Returns
The terminal state

Definition at line 122 of file client_goal_handle_imp.h.

◆ isExpired()

template<class ActionSpec >
bool actionlib::ClientGoalHandle< ActionSpec >::isExpired ( ) const
inline

Checks if this goal handle is tracking a goal.

Has pretty much the same semantics as boost::shared_ptr::expired()

Returns
True if this goal handle is not tracking a goal

Definition at line 89 of file client_goal_handle_imp.h.

◆ operator!=()

template<class ActionSpec>
bool actionlib::ClientGoalHandle< ActionSpec >::operator!= ( const ClientGoalHandle< ActionSpec > &  rhs) const

!(operator==())

Definition at line 322 of file client_goal_handle_imp.h.

◆ operator==()

template<class ActionSpec>
bool actionlib::ClientGoalHandle< ActionSpec >::operator== ( const ClientGoalHandle< ActionSpec > &  rhs) const

Check if two goal handles point to the same goal.

Returns
TRUE if both point to the same goal. Also returns TRUE if both handles are inactive.

Definition at line 299 of file client_goal_handle_imp.h.

◆ resend()

template<class ActionSpec >
void actionlib::ClientGoalHandle< ActionSpec >::resend ( )

Resends this goal [with the same GoalID] to the ActionServer.

Useful if the user thinks that the goal may have gotten lost in transit

Definition at line 207 of file client_goal_handle_imp.h.

◆ reset()

template<class ActionSpec >
void actionlib::ClientGoalHandle< ActionSpec >::reset ( )

Stops goal handle from tracking a goal.

Useful if you want to stop tracking the progress of a goal, but it is inconvenient to force the goal handle to go out of scope. Has pretty much the same semantics as boost::shared_ptr::reset()

Definition at line 71 of file client_goal_handle_imp.h.

Friends And Related Function Documentation

◆ GoalManager< ActionSpec >

template<class ActionSpec>
friend class GoalManager< ActionSpec >
friend

Definition at line 204 of file client_helpers.h.

Member Data Documentation

◆ active_

template<class ActionSpec>
bool actionlib::ClientGoalHandle< ActionSpec >::active_
private

Definition at line 214 of file client_helpers.h.

◆ gm_

template<class ActionSpec>
GoalManagerT* actionlib::ClientGoalHandle< ActionSpec >::gm_
private

Definition at line 213 of file client_helpers.h.

◆ guard_

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

Definition at line 216 of file client_helpers.h.

◆ list_handle_

template<class ActionSpec>
ManagedListT::Handle actionlib::ClientGoalHandle< ActionSpec >::list_handle_
private

Definition at line 217 of file client_helpers.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:38