client_helpers.h
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2008, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
35 #ifndef ACTIONLIB__CLIENT__CLIENT_HELPERS_H_
36 #define ACTIONLIB__CLIENT__CLIENT_HELPERS_H_
37 
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>
42 #include <vector>
43 
44 
46 
47 #include "actionlib/managed_list.h"
50 
53 
55 
56 // msgs
57 #include "actionlib_msgs/GoalID.h"
58 #include "actionlib_msgs/GoalStatusArray.h"
59 
60 namespace actionlib
61 {
62 
63 template<class ActionSpec>
65 
66 template<class ActionSpec>
68 
69 template<class ActionSpec>
71 {
72 public:
73  ACTION_DEFINITION(ActionSpec);
76  typedef boost::function<void (GoalHandleT)> TransitionCallback;
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;
80 
82  : guard_(guard) {}
83 
84  void registerSendGoalFunc(SendGoalFunc send_goal_func);
85  void registerCancelFunc(CancelFunc cancel_func);
86 
87  GoalHandleT initGoal(const Goal & goal,
88  TransitionCallback transition_cb = TransitionCallback(),
89  FeedbackCallback feedback_cb = FeedbackCallback() );
90 
91  void updateStatuses(const actionlib_msgs::GoalStatusArrayConstPtr & status_array);
92  void updateFeedbacks(const ActionFeedbackConstPtr & action_feedback);
93  void updateResults(const ActionResultConstPtr & action_result);
94 
95  friend class ClientGoalHandle<ActionSpec>;
96 
97  // should be private
99  ManagedListT list_;
100 
101 private:
102  SendGoalFunc send_goal_func_;
103  CancelFunc cancel_func_;
104 
106 
107  boost::recursive_mutex list_mutex_;
108 
110 
111  void listElemDeleter(typename ManagedListT::iterator it);
112 };
113 
121 template<class ActionSpec>
122 class ClientGoalHandle
123 {
124 private:
125  ACTION_DEFINITION(ActionSpec);
126 
127 public:
135 
136  ~ClientGoalHandle();
137 
144  void reset();
145 
152  inline bool isExpired() const;
153 
161  CommState getCommState() const;
162 
170  TerminalState getTerminalState() const;
171 
177  ResultConstPtr getResult() const;
178 
184  void resend();
185 
191  void cancel();
192 
197  bool operator==(const ClientGoalHandle<ActionSpec> & rhs) const;
198 
202  bool operator!=(const ClientGoalHandle<ActionSpec> & rhs) const;
203 
204  friend class GoalManager<ActionSpec>;
205 
206 private:
209 
210  ClientGoalHandle(GoalManagerT * gm, typename ManagedListT::Handle handle,
212 
213  GoalManagerT * gm_;
214  bool active_;
215  // typename ManagedListT::iterator it_;
216  boost::shared_ptr<DestructionGuard> guard_; // Guard must still exist when the list_handle_ is destroyed
218 };
219 
220 template<class ActionSpec>
221 class CommStateMachine
222 {
223 private:
224  // generates typedefs that we'll use to make our lives easier
225  ACTION_DEFINITION(ActionSpec);
226 
227 public:
228  typedef boost::function<void (const ClientGoalHandle<ActionSpec> &)> TransitionCallback;
229  typedef boost::function<void (const ClientGoalHandle<ActionSpec> &,
230  const FeedbackConstPtr &)> FeedbackCallback;
232 
233  CommStateMachine(const ActionGoalConstPtr & action_goal,
234  TransitionCallback transition_cb,
235  FeedbackCallback feedback_cb);
236 
237  ActionGoalConstPtr getActionGoal() const;
238  CommState getCommState() const;
239  actionlib_msgs::GoalStatus getGoalStatus() const;
240  ResultConstPtr getResult() const;
241 
242  // Transitions caused by messages
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);
246 
247  // Forced transitions
248  void transitionToState(GoalHandleT & gh, const CommState::StateEnum & next_state);
249  void transitionToState(GoalHandleT & gh, const CommState & next_state);
250  void processLost(GoalHandleT & gh);
251 
252 private:
254 
255  // State
257  ActionGoalConstPtr action_goal_;
258  actionlib_msgs::GoalStatus latest_goal_status_;
259  ActionResultConstPtr latest_result_;
260 
261  // Callbacks
264 
265  // **** Implementation ****
267  void setCommState(const CommState & state);
268  void setCommState(const CommState::StateEnum & state);
269  const actionlib_msgs::GoalStatus * findGoalStatus(
270  const std::vector<actionlib_msgs::GoalStatus> & status_vec) const;
271 };
272 
273 } // namespace actionlib
274 
278 
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.
Definition: comm_state.h:51
ManagedList< boost::shared_ptr< CommStateMachine< ActionSpec > > > ManagedListT
wrapper around an STL list to help with reference counting Provides handles elements in an STL list...
Definition: managed_list.h:56
ActionGoalConstPtr action_goal_
Thin wrapper around an enum in order to help interpret the state of the communication state machine...
Definition: comm_state.h:47
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)


actionlib
Author(s): Eitan Marder-Eppstein, Vijay Pradeep, Mikael Arguedas
autogenerated on Mon Feb 28 2022 21:34:38