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>
66 template<
class ActionSpec>
69 template<
class ActionSpec>
77 typedef boost::function<void (GoalHandleT, const FeedbackConstPtr &)>
FeedbackCallback;
78 typedef boost::function<void (const ActionGoalConstPtr)>
SendGoalFunc;
79 typedef boost::function<void (const actionlib_msgs::GoalID &)>
CancelFunc;
87 GoalHandleT
initGoal(
const Goal & goal,
91 void updateStatuses(
const actionlib_msgs::GoalStatusArrayConstPtr & status_array);
93 void updateResults(
const ActionResultConstPtr & action_result);
121 template<
class ActionSpec>
152 inline bool isExpired()
const;
177 ResultConstPtr getResult()
const;
220 template<
class ActionSpec>
229 typedef boost::function<void (const ClientGoalHandle<ActionSpec> &,
237 ActionGoalConstPtr getActionGoal()
const;
239 actionlib_msgs::GoalStatus getGoalStatus()
const;
240 ResultConstPtr getResult()
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);
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_ boost::shared_ptr< DestructionGuard > guard_
ManagedListT::Handle list_handle_
boost::function< void(const actionlib_msgs::GoalID &)> CancelFunc
ClientGoalHandle< ActionSpec > GoalHandleT
boost::function< void(GoalHandleT, const FeedbackConstPtr &)> FeedbackCallback
ActionResultConstPtr latest_result_
actionlib_msgs::GoalStatus latest_goal_status_
boost::recursive_mutex list_mutex_
boost::function< void(GoalHandleT)> TransitionCallback
void updateFeedbacks(const ActionFeedbackConstPtr &action_feedback)
bool operator==(const in6_addr a, const in6_addr b)
void listElemDeleter(typename ManagedListT::iterator it)
void updateResults(const ActionResultConstPtr &action_result)
SendGoalFunc send_goal_func_
boost::function< void(const ClientGoalHandle< ActionSpec > &)> TransitionCallback
GoalManager< ActionSpec > GoalManagerT
GoalIDGenerator id_generator_
StateEnum
Defines the various states the Communication State Machine can be in.
ManagedList< boost::shared_ptr< CommStateMachine< ActionSpec > > > ManagedListT
wrapper around an STL list to help with reference counting Provides handles elements in an STL list...
ActionGoalConstPtr action_goal_
Thin wrapper around an enum in order to help interpret the state of the communication state machine...
boost::function< void(const ActionGoalConstPtr)> SendGoalFunc
boost::shared_ptr< DestructionGuard > guard_
GoalManager(const boost::shared_ptr< DestructionGuard > &guard)
GoalHandleT initGoal(const Goal &goal, TransitionCallback transition_cb=TransitionCallback(), FeedbackCallback feedback_cb=FeedbackCallback())
ManagedList< boost::shared_ptr< CommStateMachine< ActionSpec > > > ManagedListT
GoalManager< ActionSpec > GoalManagerT
ClientGoalHandle< ActionSpec > GoalHandleT
FeedbackCallback feedback_cb_
ACTION_DEFINITION(ActionSpec)
void registerSendGoalFunc(SendGoalFunc send_goal_func)
boost::function< void(const ClientGoalHandle< ActionSpec > &, const FeedbackConstPtr &)> FeedbackCallback
void updateStatuses(const actionlib_msgs::GoalStatusArrayConstPtr &status_array)
Client side handle to monitor goal progress.
TransitionCallback transition_cb_
void registerCancelFunc(CancelFunc cancel_func)