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>
64 class ClientGoalHandle;
65 
66 template<class ActionSpec>
67 class CommStateMachine;
68 
69 template<class ActionSpec>
70 class GoalManager
71 {
72 public:
73  ACTION_DEFINITION(ActionSpec)
74  typedef GoalManager<ActionSpec> GoalManagerT;
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
100 
101 private:
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 
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:
207  typedef GoalManager<ActionSpec> GoalManagerT;
208  typedef ManagedList<boost::shared_ptr<CommStateMachine<ActionSpec> > > ManagedListT;
209 
210  ClientGoalHandle(GoalManagerT * gm, typename ManagedListT::Handle handle,
211  const boost::shared_ptr<DestructionGuard> & guard);
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
217  typename ManagedListT::Handle list_handle_;
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
256  CommState state_;
257  ActionGoalConstPtr action_goal_;
258  actionlib_msgs::GoalStatus latest_goal_status_;
259  ActionResultConstPtr latest_result_;
260 
261  // Callbacks
262  TransitionCallback transition_cb_;
263  FeedbackCallback feedback_cb_;
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_
actionlib::ClientGoalHandle::active_
bool active_
Definition: client_helpers.h:246
actionlib::ClientGoalHandle::list_handle_
ManagedListT::Handle list_handle_
Definition: client_helpers.h:249
goal_manager_imp.h
actionlib::GoalManager::CancelFunc
boost::function< void(const actionlib_msgs::GoalID &)> CancelFunc
Definition: client_helpers.h:111
actionlib::GoalManager::GoalHandleT
ClientGoalHandle< ActionSpec > GoalHandleT
Definition: client_helpers.h:107
actionlib::GoalManager::list_
ManagedListT list_
Definition: client_helpers.h:131
actionlib::GoalManager::TransitionCallback
boost::function< void(GoalHandleT)> TransitionCallback
Definition: client_helpers.h:108
actionlib::GoalManager::updateStatuses
void updateStatuses(const actionlib_msgs::GoalStatusArrayConstPtr &status_array)
Definition: goal_manager_imp.h:144
boost::shared_ptr
ACTION_DEFINITION
#define ACTION_DEFINITION(ActionSpec)
Definition: action_definition.h:77
actionlib::GoalManager::FeedbackCallback
boost::function< void(GoalHandleT, const FeedbackConstPtr &)> FeedbackCallback
Definition: client_helpers.h:109
actionlib::CommState::StateEnum
StateEnum
Defines the various states the Communication State Machine can be in.
Definition: comm_state.h:115
comm_state_machine_imp.h
actionlib::GoalManager::updateFeedbacks
void updateFeedbacks(const ActionFeedbackConstPtr &action_feedback)
Definition: goal_manager_imp.h:158
boost
actionlib::ClientGoalHandle::resend
void resend()
Resends this goal [with the same GoalID] to the ActionServer.
Definition: client_goal_handle_imp.h:239
actionlib::GoalManager::SendGoalFunc
boost::function< void(const ActionGoalConstPtr)> SendGoalFunc
Definition: client_helpers.h:110
actionlib::ManagedList
wrapper around an STL list to help with reference counting Provides handles elements in an STL list....
Definition: managed_list.h:88
actionlib::GoalManager::ManagedListT
ManagedList< boost::shared_ptr< CommStateMachine< ActionSpec > > > ManagedListT
Definition: client_helpers.h:130
actionlib::GoalIDGenerator
Definition: goal_id_generator.h:81
actionlib::GoalManager::listElemDeleter
void listElemDeleter(typename ManagedListT::iterator it)
Definition: goal_manager_imp.h:122
actionlib::CommState
Thin wrapper around an enum in order to help interpret the state of the communication state machine.
Definition: comm_state.h:79
actionlib::CommStateMachine::TransitionCallback
boost::function< void(const ClientGoalHandle< ActionSpec > &)> TransitionCallback
Definition: client_helpers.h:260
managed_list.h
enclosure_deleter.h
actionlib::GoalManager::initGoal
GoalHandleT initGoal(const Goal &goal, TransitionCallback transition_cb=TransitionCallback(), FeedbackCallback feedback_cb=FeedbackCallback())
Definition: goal_manager_imp.h:93
client_goal_handle_imp.h
actionlib::GoalManager::registerSendGoalFunc
void registerSendGoalFunc(SendGoalFunc send_goal_func)
Definition: goal_manager_imp.h:80
actionlib::ClientGoalHandle::isExpired
bool isExpired() const
Checks if this goal handle is tracking a goal.
Definition: client_goal_handle_imp.h:121
actionlib::GoalManager::id_generator_
GoalIDGenerator id_generator_
Definition: client_helpers.h:141
actionlib::CommStateMachine
Definition: client_helpers.h:99
actionlib::ClientGoalHandle::getCommState
CommState getCommState() const
Get the state of this goal's communication state machine from interaction with the server.
Definition: client_goal_handle_imp.h:128
action_definition.h
actionlib::ClientGoalHandle::gm_
GoalManagerT * gm_
Definition: client_helpers.h:245
actionlib::GoalManager::send_goal_func_
SendGoalFunc send_goal_func_
Definition: client_helpers.h:134
actionlib::GoalManager::guard_
boost::shared_ptr< DestructionGuard > guard_
Definition: client_helpers.h:137
destruction_guard.h
actionlib::GoalManager::updateResults
void updateResults(const ActionResultConstPtr &action_result)
Definition: goal_manager_imp.h:171
terminal_state.h
comm_state.h
actionlib::ClientGoalHandle::getResult
ResultConstPtr getResult() const
Get result associated with this goal.
Definition: client_goal_handle_imp.h:214
actionlib::GoalManager::cancel_func_
CancelFunc cancel_func_
Definition: client_helpers.h:135
actionlib::CommStateMachine::FeedbackCallback
boost::function< void(const ClientGoalHandle< ActionSpec > &, const FeedbackConstPtr &)> FeedbackCallback
Definition: client_helpers.h:262
actionlib::GoalManager::GoalManagerT
GoalManager< ActionSpec > GoalManagerT
Definition: client_helpers.h:106
actionlib
Definition: action_definition.h:40
actionlib::ClientGoalHandle::cancel
void cancel()
Sends a cancel message for this specific goal to the ActionServer.
Definition: client_goal_handle_imp.h:274
actionlib::GoalManager::ClientGoalHandle< ActionSpec >
friend class ClientGoalHandle< ActionSpec >
Definition: client_helpers.h:127
actionlib::ClientGoalHandle
Client side handle to monitor goal progress.
Definition: client_helpers.h:96
actionlib::GoalManager::GoalManager
GoalManager(const boost::shared_ptr< DestructionGuard > &guard)
Definition: client_helpers.h:113
actionlib::ClientGoalHandle::reset
void reset()
Stops goal handle from tracking a goal.
Definition: client_goal_handle_imp.h:103
goal_id_generator.h
actionlib::TerminalState
Definition: terminal_state.h:76
actionlib::GoalManager::list_mutex_
boost::recursive_mutex list_mutex_
Definition: client_helpers.h:139
actionlib::ClientGoalHandle::getTerminalState
TerminalState getTerminalState() const
Get the terminal state information for this goal.
Definition: client_goal_handle_imp.h:154
actionlib::GoalManager
Definition: client_helpers.h:102
actionlib::GoalManager::registerCancelFunc
void registerCancelFunc(CancelFunc cancel_func)
Definition: goal_manager_imp.h:86
actionlib::ClientGoalHandle::guard_
boost::shared_ptr< DestructionGuard > guard_
Definition: client_helpers.h:248
actionlib::DestructionGuard
This class protects an object from being destructed until all users of that object relinquish control...
Definition: destruction_guard.h:84


actionlib
Author(s): Eitan Marder-Eppstein, Vijay Pradeep, Mikael Arguedas
autogenerated on Fri May 19 2023 02:36:55