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

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

#include <client_helpers.h>

List of all members.

Public Member Functions

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


Member Typedef Documentation

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

Definition at line 203 of file client_helpers.h.

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

Definition at line 204 of file client_helpers.h.


Constructor & Destructor Documentation

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 43 of file client_goal_handle_imp.h.

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

Definition at line 50 of file client_goal_handle_imp.h.

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

Definition at line 56 of file client_goal_handle_imp.h.


Member Function Documentation

template<class ActionSpec>
actionlib::ClientGoalHandle< ActionSpec >::ACTION_DEFINITION ( ActionSpec  ) [private]
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 205 of file client_goal_handle_imp.h.

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

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 92 of file client_goal_handle_imp.h.

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

Get result associated with this goal.

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

Definition at line 161 of file client_goal_handle_imp.h.

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

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 114 of file client_goal_handle_imp.h.

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 85 of file client_goal_handle_imp.h.

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

!(operator==())

Definition at line 275 of file client_goal_handle_imp.h.

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

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 254 of file client_goal_handle_imp.h.

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 179 of file client_goal_handle_imp.h.

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 66 of file client_goal_handle_imp.h.


Friends And Related Function Documentation

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

Definition at line 201 of file client_helpers.h.


Member Data Documentation

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

Definition at line 209 of file client_helpers.h.

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

Definition at line 208 of file client_helpers.h.

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

Definition at line 211 of file client_helpers.h.

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

Definition at line 212 of file client_helpers.h.


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


actionlib
Author(s): Eitan Marder-Eppstein, Vijay Pradeep
autogenerated on Sun Oct 5 2014 22:02:55