Go to the documentation of this file.
35 #ifndef ACTIONLIB__CLIENT__CLIENT_HELPERS_H_
36 #define ACTIONLIB__CLIENT__CLIENT_HELPERS_H_
38 #include <boost/thread/recursive_mutex.hpp>
39 #include <boost/interprocess/sync/scoped_lock.hpp>
40 #include <boost/shared_ptr.hpp>
41 #include <boost/weak_ptr.hpp>
57 #include "actionlib_msgs/GoalID.h"
58 #include "actionlib_msgs/GoalStatusArray.h"
63 template<
class ActionSpec>
64 class ClientGoalHandle;
66 template<
class ActionSpec>
67 class CommStateMachine;
69 template<
class ActionSpec>
78 typedef boost::function<void (
const ActionGoalConstPtr)>
SendGoalFunc;
79 typedef boost::function<void (
const actionlib_msgs::GoalID &)>
CancelFunc;
91 void updateStatuses(
const actionlib_msgs::GoalStatusArrayConstPtr & status_array);
93 void updateResults(
const ActionResultConstPtr & action_result);
95 friend class ClientGoalHandle<ActionSpec>;
121 template<
class ActionSpec>
220 template<class ActionSpec>
237 ActionGoalConstPtr getActionGoal()
const;
239 actionlib_msgs::GoalStatus getGoalStatus()
const;
243 void updateStatus(GoalHandleT & gh,
const actionlib_msgs::GoalStatusArrayConstPtr & status_array);
244 void updateFeedback(GoalHandleT & gh,
const ActionFeedbackConstPtr & action_feedback);
245 void updateResult(GoalHandleT & gh,
const ActionResultConstPtr & action_result);
249 void transitionToState(GoalHandleT & gh,
const CommState & next_state);
250 void processLost(GoalHandleT & gh);
257 ActionGoalConstPtr action_goal_;
258 actionlib_msgs::GoalStatus latest_goal_status_;
259 ActionResultConstPtr latest_result_;
267 void setCommState(
const CommState & state);
269 const actionlib_msgs::GoalStatus * findGoalStatus(
270 const std::vector<actionlib_msgs::GoalStatus> & status_vec)
const;
279 #endif // ACTIONLIB__CLIENT__CLIENT_HELPERS_H_
ManagedListT::Handle list_handle_
boost::function< void(const actionlib_msgs::GoalID &)> CancelFunc
ClientGoalHandle< ActionSpec > GoalHandleT
boost::function< void(GoalHandleT)> TransitionCallback
void updateStatuses(const actionlib_msgs::GoalStatusArrayConstPtr &status_array)
#define ACTION_DEFINITION(ActionSpec)
boost::function< void(GoalHandleT, const FeedbackConstPtr &)> FeedbackCallback
StateEnum
Defines the various states the Communication State Machine can be in.
void updateFeedbacks(const ActionFeedbackConstPtr &action_feedback)
void resend()
Resends this goal [with the same GoalID] to the ActionServer.
boost::function< void(const ActionGoalConstPtr)> SendGoalFunc
wrapper around an STL list to help with reference counting Provides handles elements in an STL list....
ManagedList< boost::shared_ptr< CommStateMachine< ActionSpec > > > ManagedListT
void listElemDeleter(typename ManagedListT::iterator it)
Thin wrapper around an enum in order to help interpret the state of the communication state machine.
boost::function< void(const ClientGoalHandle< ActionSpec > &)> TransitionCallback
GoalHandleT initGoal(const Goal &goal, TransitionCallback transition_cb=TransitionCallback(), FeedbackCallback feedback_cb=FeedbackCallback())
void registerSendGoalFunc(SendGoalFunc send_goal_func)
bool isExpired() const
Checks if this goal handle is tracking a goal.
GoalIDGenerator id_generator_
CommState getCommState() const
Get the state of this goal's communication state machine from interaction with the server.
SendGoalFunc send_goal_func_
boost::shared_ptr< DestructionGuard > guard_
void updateResults(const ActionResultConstPtr &action_result)
ResultConstPtr getResult() const
Get result associated with this goal.
boost::function< void(const ClientGoalHandle< ActionSpec > &, const FeedbackConstPtr &)> FeedbackCallback
GoalManager< ActionSpec > GoalManagerT
void cancel()
Sends a cancel message for this specific goal to the ActionServer.
friend class ClientGoalHandle< ActionSpec >
Client side handle to monitor goal progress.
GoalManager(const boost::shared_ptr< DestructionGuard > &guard)
void reset()
Stops goal handle from tracking a goal.
boost::recursive_mutex list_mutex_
TerminalState getTerminalState() const
Get the terminal state information for this goal.
void registerCancelFunc(CancelFunc cancel_func)
boost::shared_ptr< DestructionGuard > guard_
This class protects an object from being destructed until all users of that object relinquish control...
actionlib
Author(s): Eitan Marder-Eppstein, Vijay Pradeep, Mikael Arguedas
autogenerated on Fri May 19 2023 02:36:55