Codebase list ros-actionlib / 6f30fa8
New upstream snapshot. Debian Janitor 1 year, 6 months ago
28 changed file(s) with 205 addition(s) and 263 deletion(s). Raw diff Collapse all Expand all
+0
-1
.gitignore less more
0 *.pyc
6161 typedef ClientGoalHandle<ActionSpec> GoalHandle;
6262
6363 private:
64 ACTION_DEFINITION(ActionSpec);
64 ACTION_DEFINITION(ActionSpec)
6565 typedef ActionClient<ActionSpec> ActionClientT;
6666 typedef boost::function<void (GoalHandle)> TransitionCallback;
6767 typedef boost::function<void (GoalHandle, const FeedbackConstPtr &)> FeedbackCallback;
7474 * Constructs an ActionClient and sets up the necessary ros topics for the ActionInterface
7575 * \param name The action name. Defines the namespace in which the action communicates
7676 * \param queue CallbackQueue from which this action will process messages.
77 * The default (NULL) is to use the global queue
78 */
79 ActionClient(const std::string & name, ros::CallbackQueueInterface * queue = NULL)
77 * The default (nullptr) is to use the global queue
78 */
79 ActionClient(const std::string & name, ros::CallbackQueueInterface * queue = nullptr)
8080 : n_(name), guard_(new DestructionGuard()),
8181 manager_(guard_)
8282 {
9191 * \param n The node handle on top of which we want to namespace our action
9292 * \param name The action name. Defines the namespace in which the action communicates
9393 * \param queue CallbackQueue from which this action will process messages.
94 * The default (NULL) is to use the global queue
94 * The default (nullptr) is to use the global queue
9595 */
9696 ActionClient(const ros::NodeHandle & n, const std::string & name,
97 ros::CallbackQueueInterface * queue = NULL)
97 ros::CallbackQueueInterface * queue = nullptr)
9898 : n_(n, name), guard_(new DestructionGuard()),
9999 manager_(guard_)
100100 {
4545 template<class ActionSpec>
4646 ClientGoalHandle<ActionSpec>::ClientGoalHandle()
4747 {
48 gm_ = NULL;
48 gm_ = nullptr;
4949 active_ = false;
5050 }
5151
8080 boost::recursive_mutex::scoped_lock lock(gm_->list_mutex_);
8181 list_handle_.reset();
8282 active_ = false;
83 gm_ = NULL;
83 gm_ = nullptr;
8484 }
8585 }
8686
229229 ActionGoalConstPtr action_goal = list_handle_.getElem()->getActionGoal();
230230
231231 if (!action_goal) {
232 ROS_ERROR_NAMED("actionlib", "BUG: Got a NULL action_goal");
232 ROS_ERROR_NAMED("actionlib", "BUG: Got a nullptr action_goal");
233233 }
234234
235235 if (gm_->send_goal_func_) {
6969 class GoalManager
7070 {
7171 public:
72 ACTION_DEFINITION(ActionSpec);
72 ACTION_DEFINITION(ActionSpec)
7373 typedef GoalManager<ActionSpec> GoalManagerT;
7474 typedef ClientGoalHandle<ActionSpec> GoalHandleT;
7575 typedef boost::function<void (GoalHandleT)> TransitionCallback;
121121 class ClientGoalHandle
122122 {
123123 private:
124 ACTION_DEFINITION(ActionSpec);
124 ACTION_DEFINITION(ActionSpec)
125125
126126 public:
127127 /**
171171 /**
172172 * \brief Get result associated with this goal
173173 *
174 * \return NULL if no result received. Otherwise returns shared_ptr to result.
174 * \return nullptr if no result received. Otherwise returns shared_ptr to result.
175175 */
176176 ResultConstPtr getResult() const;
177177
221221 {
222222 private:
223223 // generates typedefs that we'll use to make our lives easier
224 ACTION_DEFINITION(ActionSpec);
224 ACTION_DEFINITION(ActionSpec)
225225
226226 public:
227227 typedef boost::function<void (const ClientGoalHandle<ActionSpec> &)> TransitionCallback;
111111 return &status_vec[i];
112112 }
113113 }
114 return NULL;
114 return nullptr;
115115 }
116116
117117 template<class ActionSpec>
7979 send_goal_func_(action_goal);
8080 } else {
8181 ROS_WARN_NAMED("actionlib",
82 "Possible coding error: send_goal_func_ set to NULL. Not going to send goal");
82 "Possible coding error: send_goal_func_ set to nullptr. Not going to send goal");
8383 }
8484
8585 return GoalHandleT(this, list_handle, guard_);
7979 class ServiceClientImpT : public ServiceClientImp
8080 {
8181 public:
82 ACTION_DEFINITION(ActionSpec);
82 ACTION_DEFINITION(ActionSpec)
8383 typedef ClientGoalHandle<ActionSpec> GoalHandleT;
8484 typedef SimpleActionClient<ActionSpec> SimpleActionClientT;
8585
7171 class SimpleActionClient
7272 {
7373 private:
74 ACTION_DEFINITION(ActionSpec);
74 ACTION_DEFINITION(ActionSpec)
7575 typedef ClientGoalHandle<ActionSpec> GoalHandleT;
7676 typedef SimpleActionClient<ActionSpec> SimpleActionClientT;
7777
179179
180180 /**
181181 * \brief Get the Result of the current goal
182 * \return shared pointer to the result. Note that this pointer will NEVER be NULL
182 * \return shared pointer to the result. Note that this pointer will NEVER be nullptr
183183 */
184184 ResultConstPtr getResult() const;
185185
263263 new boost::thread(boost::bind(&SimpleActionClient<ActionSpec>::spinThread, this));
264264 ac_.reset(new ActionClientT(n, name, &callback_queue));
265265 } else {
266 spin_thread_ = NULL;
266 spin_thread_ = nullptr;
267267 ac_.reset(new ActionClientT(n, name));
268268 }
269269 }
+0
-178
actionlib/include/actionlib/client_goal_status.h less more
0 /*********************************************************************
1 * Software License Agreement (BSD License)
2 *
3 * Copyright (c) 2008, Willow Garage, Inc.
4 * All rights reserved.
5 *
6 * Redistribution and use in source and binary forms, with or without
7 * modification, are permitted provided that the following conditions
8 * are met:
9 *
10 * * Redistributions of source code must retain the above copyright
11 * notice, this list of conditions and the following disclaimer.
12 * * Redistributions in binary form must reproduce the above
13 * copyright notice, this list of conditions and the following
14 * disclaimer in the documentation and/or other materials provided
15 * with the distribution.
16 * * Neither the name of the Willow Garage nor the names of its
17 * contributors may be used to endorse or promote products derived
18 * from this software without specific prior written permission.
19 *
20 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31 * POSSIBILITY OF SUCH DAMAGE.
32 *********************************************************************/
33
34 #ifndef ACTIONLIB__CLIENT_GOAL_STATUS_H_
35 #define ACTIONLIB__CLIENT_GOAL_STATUS_H_
36
37 #include <string>
38
39 #include "actionlib/GoalStatus.h"
40 #include "ros/console.h"
41
42 namespace actionlib
43 {
44
45 /**
46 * \brief Thin wrapper around an enum in order to help interpret the client-side status of a goal request
47 * The possible states are defined the ClientGoalStatus::StateEnum. They are also defined in StateEnum.
48 * we can also get there from \link ClientGoalStatus::StateEnum here \endlink
49 **/
50 class ClientGoalStatus
51 {
52 public:
53 //! \brief Defines the various states the Goal can be in, as perceived by the client
54 enum StateEnum
55 {
56 PENDING, //!< The goal has yet to be processed by the action server
57 ACTIVE, //!< The goal is currently being processed by the action server
58 PREEMPTED, //!< The goal was preempted by either another goal, or a preempt message being sent to the action server
59 SUCCEEDED, //!< The goal was achieved successfully by the action server
60 ABORTED, //!< The goal was aborted by the action server
61 REJECTED, //!< The ActionServer refused to start processing the goal, possibly because a goal is infeasible
62 LOST //!< The goal was sent by the ActionClient, but disappeared due to some communication error
63 };
64
65 ClientGoalStatus(StateEnum state)
66 {
67 state_ = state;
68 }
69
70 /**
71 * \brief Build a ClientGoalStatus from a GoalStatus.
72 * Note that the only GoalStatuses that can be converted into a
73 * ClientGoalStatus are {PREEMPTED, SUCCEEDED, ABORTED, REJECTED}
74 * \param goal_status The GoalStatus msg that we want to convert
75 */
76 ClientGoalStatus(const GoalStatus & goal_status)
77 {
78 fromGoalStatus(goal_status);
79 }
80
81 /**
82 * \brief Check if the goal is in a terminal state
83 * \return TRUE if in PREEMPTED, SUCCEDED, ABORTED, REJECTED, or LOST
84 */
85 inline bool isDone() const
86 {
87 if (state_ == PENDING || state_ == ACTIVE) {
88 return false;
89 }
90 return true;
91 }
92
93 /**
94 * \brief Copy the raw enum into the object
95 */
96 inline const StateEnum & operator=(const StateEnum & state)
97 {
98 state_ = state;
99 return state;
100 }
101
102 /**
103 * \brief Straightforward enum equality check
104 */
105 inline bool operator==(const ClientGoalStatus & rhs) const
106 {
107 return state_ == rhs.state_;
108 }
109
110 /**
111 * \brief Straightforward enum inequality check
112 */
113 inline bool operator!=(const ClientGoalStatus & rhs) const
114 {
115 return !(state_ == rhs.state_);
116 }
117
118 /**
119 * \brief Store a GoalStatus in a ClientGoalStatus
120 * Note that the only GoalStatuses that can be converted into a
121 * ClientGoalStatus are {PREEMPTED, SUCCEEDED, ABORTED, REJECTED}
122 * \param goal_status The GoalStatus msg that we want to convert
123 */
124 void fromGoalStatus(const GoalStatus & goal_status)
125 {
126 switch (goal_status.status) {
127 case GoalStatus::PREEMPTED:
128 state_ = ClientGoalStatus::PREEMPTED; break;
129 case GoalStatus::SUCCEEDED:
130 state_ = ClientGoalStatus::SUCCEEDED; break;
131 case GoalStatus::ABORTED:
132 state_ = ClientGoalStatus::ABORTED; break;
133 case GoalStatus::REJECTED:
134 state_ = ClientGoalStatus::REJECTED; break;
135 default:
136 state_ = ClientGoalStatus::LOST;
137 ROS_ERROR_NAMED("actionlib", "Cannot convert GoalStatus %u to ClientGoalState",
138 goal_status.status); break;
139 }
140 }
141
142 /**
143 * \brief Stringify the enum
144 * \return String that has the name of the enum
145 */
146 std::string toString() const
147 {
148 switch (state_) {
149 case PENDING:
150 return "PENDING";
151 case ACTIVE:
152 return "ACTIVE";
153 case PREEMPTED:
154 return "PREEMPTED";
155 case SUCCEEDED:
156 return "SUCCEEDED";
157 case ABORTED:
158 return "ABORTED";
159 case REJECTED:
160 return "REJECTED";
161 case LOST:
162 return "LOST";
163 default:
164 ROS_ERROR_NAMED("actionlib", "BUG: Unhandled ClientGoalStatus");
165 break;
166 }
167 return "BUG-UNKNOWN";
168 }
169
170 private:
171 StateEnum state_;
172 ClientGoalStatus(); //!< Need to always specific an initial state. Thus, no empty constructor
173 };
174
175 } // namespace actionlib
176
177 #endif // ACTIONLIB__CLIENT_GOAL_STATUS_H_
235235 iterator managed_it = iterator(list_it);
236236
237237 ElemDeleter deleter(managed_it, custom_deleter, guard);
238 boost::shared_ptr<void> tracker( (void *) NULL, deleter);
238 boost::shared_ptr<void> tracker(nullptr, deleter);
239239
240240 list_it->handle_tracker_ = tracker;
241241
5252 if (callback_) {
5353 callback_(e);
5454 } else {
55 ROS_ERROR_NAMED("actionlib", "Got a NULL Timer OneShotTimer Callback");
55 ROS_ERROR_NAMED("actionlib", "Got a nullptr Timer OneShotTimer Callback");
5656 }
5757 }
5858 }
7575 typedef ServerGoalHandle<ActionSpec> GoalHandle;
7676
7777 // generates typedefs that we'll use to make our lives easier
78 ACTION_DEFINITION(ActionSpec);
78 ACTION_DEFINITION(ActionSpec)
7979
8080 /**
8181 * @brief Constructor for an ActionServer
6767 typedef ServerGoalHandle<ActionSpec> GoalHandle;
6868
6969 // generates typedefs that we'll use to make our lives easier
70 ACTION_DEFINITION(ActionSpec);
70 ACTION_DEFINITION(ActionSpec)
7171
7272 /**
7373 * @brief Constructor for an ActionServer
239239
240240 // we need to create a handle tracker for the incoming goal and update the StatusTracker
241241 HandleTrackerDeleter<ActionSpec> d(this, it, guard_);
242 boost::shared_ptr<void> handle_tracker((void *)NULL, d);
242 boost::shared_ptr<void> handle_tracker(nullptr, d);
243243 (*it).handle_tracker_ = handle_tracker;
244244
245245 // check if this goal has already been canceled based on its timestamp
296296 if ((*it).handle_tracker_.expired()) {
297297 // if the handle tracker is expired, then we need to create a new one
298298 HandleTrackerDeleter<ActionSpec> d(this, it, guard_);
299 handle_tracker = boost::shared_ptr<void>((void *)NULL, d);
299 handle_tracker = boost::shared_ptr<void>(nullptr, d);
300300 (*it).handle_tracker_ = handle_tracker;
301301
302302 // we also need to reset the time that the status is supposed to be removed from the list
6363 {
6464 private:
6565 // generates typedefs that we'll use to make our lives easier
66 ACTION_DEFINITION(ActionSpec);
66 ACTION_DEFINITION(ActionSpec)
6767
6868 public:
6969 /**
4545 {
4646 template<class ActionSpec>
4747 ServerGoalHandle<ActionSpec>::ServerGoalHandle()
48 : as_(NULL) {}
48 : as_(nullptr) {}
4949
5050 template<class ActionSpec>
5151 ServerGoalHandle<ActionSpec>::ServerGoalHandle(const ServerGoalHandle & gh)
5555 template<class ActionSpec>
5656 void ServerGoalHandle<ActionSpec>::setAccepted(const std::string & text)
5757 {
58 if (as_ == NULL) {
58 if (as_ == nullptr) {
5959 ROS_ERROR_NAMED("actionlib",
6060 "You are attempting to call methods on an uninitialized goal handle");
6161 return;
9898 template<class ActionSpec>
9999 void ServerGoalHandle<ActionSpec>::setCanceled(const Result & result, const std::string & text)
100100 {
101 if (as_ == NULL) {
101 if (as_ == nullptr) {
102102 ROS_ERROR_NAMED("actionlib",
103103 "You are attempting to call methods on an uninitialized goal handle");
104104 return;
141141 template<class ActionSpec>
142142 void ServerGoalHandle<ActionSpec>::setRejected(const Result & result, const std::string & text)
143143 {
144 if (as_ == NULL) {
144 if (as_ == nullptr) {
145145 ROS_ERROR_NAMED("actionlib",
146146 "You are attempting to call methods on an uninitialized goal handle");
147147 return;
179179 template<class ActionSpec>
180180 void ServerGoalHandle<ActionSpec>::setAborted(const Result & result, const std::string & text)
181181 {
182 if (as_ == NULL) {
182 if (as_ == nullptr) {
183183 ROS_ERROR_NAMED("actionlib",
184184 "You are attempting to call methods on an uninitialized goal handle");
185185 return;
217217 template<class ActionSpec>
218218 void ServerGoalHandle<ActionSpec>::setSucceeded(const Result & result, const std::string & text)
219219 {
220 if (as_ == NULL) {
220 if (as_ == nullptr) {
221221 ROS_ERROR_NAMED("actionlib",
222222 "You are attempting to call methods on an uninitialized goal handle");
223223 return;
255255 template<class ActionSpec>
256256 void ServerGoalHandle<ActionSpec>::publishFeedback(const Feedback & feedback)
257257 {
258 if (as_ == NULL) {
258 if (as_ == nullptr) {
259259 ROS_ERROR_NAMED("actionlib",
260260 "You are attempting to call methods on an uninitialized goal handle");
261261 return;
283283 template<class ActionSpec>
284284 bool ServerGoalHandle<ActionSpec>::isValid() const
285285 {
286 return goal_ && as_ != NULL;
286 return goal_ && as_ != nullptr;
287287 }
288288
289289 template<class ActionSpec>
302302 template<class ActionSpec>
303303 actionlib_msgs::GoalID ServerGoalHandle<ActionSpec>::getGoalID() const
304304 {
305 if (goal_ && as_ != NULL) {
305 if (goal_ && as_ != nullptr) {
306306 DestructionGuard::ScopedProtector protector(*guard_);
307307 if (protector.isProtected()) {
308308 boost::recursive_mutex::scoped_lock lock(as_->lock_);
320320 template<class ActionSpec>
321321 actionlib_msgs::GoalStatus ServerGoalHandle<ActionSpec>::getGoalStatus() const
322322 {
323 if (goal_ && as_ != NULL) {
323 if (goal_ && as_ != nullptr) {
324324 DestructionGuard::ScopedProtector protector(*guard_);
325325 if (protector.isProtected()) {
326326 boost::recursive_mutex::scoped_lock lock(as_->lock_);
379379 template<class ActionSpec>
380380 bool ServerGoalHandle<ActionSpec>::setCancelRequested()
381381 {
382 if (as_ == NULL) {
382 if (as_ == nullptr) {
383383 ROS_ERROR_NAMED("actionlib",
384384 "You are attempting to call methods on an uninitialized goal handle");
385385 return false;
7171 {
7272 public:
7373 // generates typedefs that we'll use to make our lives easier
74 ACTION_DEFINITION(ActionSpec);
74 ACTION_DEFINITION(ActionSpec)
7575
7676 typedef typename ActionServer<ActionSpec>::GoalHandle GoalHandle;
7777
6060 {
6161 public:
6262 // generates typedefs that we'll use to make our lives easier
63 ACTION_DEFINITION(ActionSpec);
63 ACTION_DEFINITION(ActionSpec)
6464
6565 typedef typename ActionServer<ActionSpec>::GoalHandle GoalHandle;
6666 typedef boost::function<void (const GoalConstPtr &)> ExecuteCallback;
4747 ExecuteCallback execute_callback,
4848 bool auto_start)
4949 : new_goal_(false), preempt_request_(false), new_goal_preempt_request_(false), execute_callback_(
50 execute_callback), execute_thread_(NULL), need_to_terminate_(false)
51 {
52 if (execute_callback_ != NULL) {
50 execute_callback), execute_thread_(nullptr), need_to_terminate_(false)
51 {
52 if (execute_callback_) {
5353 execute_thread_ = new boost::thread(boost::bind(&SimpleActionServer::executeLoop, this));
5454 }
5555
6363 template<class ActionSpec>
6464 SimpleActionServer<ActionSpec>::SimpleActionServer(std::string name, bool auto_start)
6565 : new_goal_(false), preempt_request_(false), new_goal_preempt_request_(false), execute_callback_(
66 NULL), execute_thread_(NULL), need_to_terminate_(false)
66 NULL), execute_thread_(nullptr), need_to_terminate_(false)
6767 {
6868 // create the action server
6969 as_ = boost::shared_ptr<ActionServer<ActionSpec> >(new ActionServer<ActionSpec>(n_, name,
7171 boost::bind(&SimpleActionServer::preemptCallback, this, _1),
7272 auto_start));
7373
74 if (execute_callback_ != NULL) {
74 if (execute_callback_) {
7575 execute_thread_ = new boost::thread(boost::bind(&SimpleActionServer::executeLoop, this));
7676 }
7777 }
8080 SimpleActionServer<ActionSpec>::SimpleActionServer(std::string name,
8181 ExecuteCallback execute_callback)
8282 : new_goal_(false), preempt_request_(false), new_goal_preempt_request_(false), execute_callback_(
83 execute_callback), execute_thread_(NULL), need_to_terminate_(false)
83 execute_callback), execute_thread_(nullptr), need_to_terminate_(false)
8484 {
8585 // create the action server
8686 as_ = boost::shared_ptr<ActionServer<ActionSpec> >(new ActionServer<ActionSpec>(n_, name,
8888 boost::bind(&SimpleActionServer::preemptCallback, this, _1),
8989 true));
9090
91 if (execute_callback_ != NULL) {
91 if (execute_callback_) {
9292 execute_thread_ = new boost::thread(boost::bind(&SimpleActionServer::executeLoop, this));
9393 }
9494 }
9999 ExecuteCallback execute_callback,
100100 bool auto_start)
101101 : n_(n), new_goal_(false), preempt_request_(false), new_goal_preempt_request_(false),
102 execute_callback_(execute_callback), execute_thread_(NULL), need_to_terminate_(false)
102 execute_callback_(execute_callback), execute_thread_(nullptr), need_to_terminate_(false)
103103 {
104104 // create the action server
105105 as_ = boost::shared_ptr<ActionServer<ActionSpec> >(new ActionServer<ActionSpec>(n, name,
107107 boost::bind(&SimpleActionServer::preemptCallback, this, _1),
108108 auto_start));
109109
110 if (execute_callback_ != NULL) {
110 if (execute_callback_) {
111111 execute_thread_ = new boost::thread(boost::bind(&SimpleActionServer::executeLoop, this));
112112 }
113113 }
116116 SimpleActionServer<ActionSpec>::SimpleActionServer(ros::NodeHandle n, std::string name,
117117 bool auto_start)
118118 : n_(n), new_goal_(false), preempt_request_(false), new_goal_preempt_request_(false),
119 execute_callback_(NULL), execute_thread_(NULL), need_to_terminate_(false)
119 execute_callback_(NULL), execute_thread_(nullptr), need_to_terminate_(false)
120120 {
121121 // create the action server
122122 as_ = boost::shared_ptr<ActionServer<ActionSpec> >(new ActionServer<ActionSpec>(n, name,
124124 boost::bind(&SimpleActionServer::preemptCallback, this, _1),
125125 auto_start));
126126
127 if (execute_callback_ != NULL) {
127 if (execute_callback_) {
128128 execute_thread_ = new boost::thread(boost::bind(&SimpleActionServer::executeLoop, this));
129129 }
130130 }
133133 SimpleActionServer<ActionSpec>::SimpleActionServer(ros::NodeHandle n, std::string name,
134134 ExecuteCallback execute_callback)
135135 : n_(n), new_goal_(false), preempt_request_(false), new_goal_preempt_request_(false),
136 execute_callback_(execute_callback), execute_thread_(NULL), need_to_terminate_(false)
136 execute_callback_(execute_callback), execute_thread_(nullptr), need_to_terminate_(false)
137137 {
138138 // create the action server
139139 as_ = boost::shared_ptr<ActionServer<ActionSpec> >(new ActionServer<ActionSpec>(n, name,
141141 boost::bind(&SimpleActionServer::preemptCallback, this, _1),
142142 true));
143143
144 if (execute_callback_ != NULL) {
144 if (execute_callback_) {
145145 execute_thread_ = new boost::thread(boost::bind(&SimpleActionServer::executeLoop, this));
146146 }
147147 }
167167 if (execute_thread_) {
168168 execute_thread_->join();
169169 delete execute_thread_;
170 execute_thread_ = NULL;
170 execute_thread_ = nullptr;
171171 }
172172 }
173173 }
5555 {
5656 private:
5757 // generates typedefs that we'll use to make our lives easier
58 ACTION_DEFINITION(ActionSpec);
58 ACTION_DEFINITION(ActionSpec)
5959
6060 public:
6161 StatusTracker(const actionlib_msgs::GoalID & goal_id, unsigned int status);
99 the resulting point cloud, detecting the handle of a door, etc.
1010 </description>
1111 <maintainer email="michael@openrobotics.org">Michael Carroll</maintainer>
12 <maintainer email="jacob@openrobotics.org">Jacob Perron</maintainer>
1213 <license>BSD</license>
1314
1415 <url type="website">http://www.ros.org/wiki/actionlib</url>
595595
596596 if self.pub_goal.impl.has_connection(server_id) and \
597597 self.pub_cancel.impl.has_connection(server_id):
598 # We'll also check that all of the subscribers have at least
599 # one publisher, this isn't a perfect check, but without
600 # publisher callbacks... it'll have to do
601 status_num_pubs = 0
602 for stat in self.status_sub.impl.get_stats()[1]:
603 if stat[4]:
604 status_num_pubs += 1
605
606 result_num_pubs = 0
607 for stat in self.result_sub.impl.get_stats()[1]:
608 if stat[4]:
609 result_num_pubs += 1
610
611 feedback_num_pubs = 0
612 for stat in self.feedback_sub.impl.get_stats()[1]:
613 if stat[4]:
614 feedback_num_pubs += 1
615
616 if status_num_pubs > 0 and result_num_pubs > 0 and feedback_num_pubs > 0:
598 # Check that the connections to the result and feedback
599 # topics have completed and are ready to receive data.
600 # Check the connections by checking the callerid from the
601 # publisher's header against the server_id.
602 # Note: there is no need to check the status topic, as
603 # we already received a status message in last_status_msg
604 # and are using it as the source of truth for the server_id.
605 # Note: there is no need to grab the c_lock, the
606 # implementation guarantees to never mutate the connection
607 # list, only replace the reference. So all we need to do is
608 # to copy a reference ourselves. This behavior is
609 # documented in the comment above the c_lock creation in
610 # rospy._TopicImpl.__init__.
611 result_sub_connections = self.result_sub.impl.connections
612 result_sub_found = False
613 for c in result_sub_connections:
614 if c.callerid_pub == server_id:
615 result_sub_found = True
616 feedback_sub_connections = self.feedback_sub.impl.connections
617 feedback_sub_found = False
618 for c in feedback_sub_connections:
619 if c.callerid_pub == server_id:
620 feedback_sub_found = True
621
622 if result_sub_found and feedback_sub_found:
617623 started = True
618624 break
619625
211211 self.gh = None
212212
213213 def _handle_transition(self, gh):
214
215 if gh != self.gh:
216 rospy.logerr("Got a transition callback on a goal handle that we're not tracking")
217 return
218
214219 comm_state = gh.get_comm_state()
215220
216221 error_msg = "Received comm state %s when in simple state %s with SimpleActionClient in NS %s" % \
235240 rospy.logerr(error_msg)
236241 elif comm_state == CommState.DONE:
237242 if self.simple_state in [SimpleGoalState.PENDING, SimpleGoalState.ACTIVE]:
238 self._set_simple_state(SimpleGoalState.DONE)
239243 if self.done_cb:
240244 self.done_cb(gh.get_goal_status(), gh.get_result())
241245 with self.done_condition:
246 self._set_simple_state(SimpleGoalState.DONE)
242247 self.done_condition.notifyAll()
243248 elif self.simple_state == SimpleGoalState.DONE:
244249 rospy.logerr("SimpleActionClient received DONE twice")
207207 self.execute_condition.acquire()
208208
209209 try:
210 rospy.logdebug("A new goal %shas been recieved by the single goal action server", goal.get_goal_id().id)
210 rospy.logdebug("A new goal %s has been received by the single goal action server", goal.get_goal_id().id)
211211
212212 # check that the timestamp is past that of the current goal and the next goal
213213 if((not self.current_goal.get_goal() or goal.get_goal_id().stamp >= self.current_goal.get_goal_id().stamp)
2222 add_executable(actionlib-simple_client_allocator_test EXCLUDE_FROM_ALL simple_client_allocator_test.cpp)
2323 target_link_libraries(actionlib-simple_client_allocator_test ${PROJECT_NAME} ${GTEST_LIBRARIES})
2424
25 add_executable(actionlib-simple_action_server_construction_test EXCLUDE_FROM_ALL simple_action_server_construction_test.cpp)
26 target_link_libraries(actionlib-simple_action_server_construction_test ${PROJECT_NAME} ${GTEST_LIBRARIES})
27
2528 add_executable(actionlib-action_client_destruction_test EXCLUDE_FROM_ALL action_client_destruction_test.cpp)
2629 target_link_libraries(actionlib-action_client_destruction_test ${PROJECT_NAME} ${GTEST_LIBRARIES})
2730
4043 actionlib-server_goal_handle_destruction
4144 actionlib-simple_client_wait_test
4245 actionlib-simple_client_allocator_test
46 actionlib-simple_action_server_construction_test
4347 actionlib-action_client_destruction_test
4448 actionlib-test_cpp_simple_client_cancel_crash
4549 actionlib-exercise_simple_client
0 /*********************************************************************
1 * Software License Agreement (BSD License)
2 *
3 * Copyright (c) 2021, Smart Robotics BV.
4 * All rights reserved.
5 *
6 * Redistribution and use in source and binary forms, with or without
7 * modification, are permitted provided that the following conditions
8 * are met:
9 *
10 * * Redistributions of source code must retain the above copyright
11 * notice, this list of conditions and the following disclaimer.
12 * * Redistributions in binary form must reproduce the above
13 * copyright notice, this list of conditions and the following
14 * disclaimer in the documentation and/or other materials provided
15 * with the distribution.
16 * * Neither the name of the Willow Garage nor the names of its
17 * contributors may be used to endorse or promote products derived
18 * from this software without specific prior written permission.
19 *
20 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31 * POSSIBILITY OF SUCH DAMAGE.
32 *********************************************************************/
33
34 //! \author Ramon Wijnands
35
36 #include <actionlib/TestAction.h>
37 #include <actionlib/server/simple_action_server.h>
38 #include <gtest/gtest.h>
39 #include <stdlib.h>
40
41 #pragma GCC diagnostic ignored "-Wdeprecated-declarations"
42
43 using namespace actionlib;
44
45 TEST(SimpleActionServerConstruction, test_name_cb_autostart) {
46 SimpleActionServer<TestAction>::ExecuteCallback callback = [](const TestGoalConstPtr&){};
47 SimpleActionServer<TestAction> as("name", callback, false);
48 }
49
50 TEST(SimpleActionServerConstruction, test_name_autostart) {
51 SimpleActionServer<TestAction> as("name", false);
52 }
53
54 TEST(SimpleActionServerConstruction, test_name) {
55 SimpleActionServer<TestAction> as("name");
56 }
57
58 TEST(SimpleActionServerConstruction, test_name_cb) {
59 SimpleActionServer<TestAction>::ExecuteCallback callback = [](const TestGoalConstPtr&){};
60 SimpleActionServer<TestAction> as("name", callback);
61 }
62
63 TEST(SimpleActionServerConstruction, test_nh_name_cb_autostart) {
64 ros::NodeHandle nh;
65 SimpleActionServer<TestAction>::ExecuteCallback callback = [](const TestGoalConstPtr&){};
66 SimpleActionServer<TestAction> as(nh, "name", callback, false);
67 }
68
69 TEST(SimpleActionServerConstruction, test_nh_name_autostart) {
70 ros::NodeHandle nh;
71 SimpleActionServer<TestAction> as(nh, "name", false);
72 }
73
74 TEST(SimpleActionServerConstruction, test_nh_name) {
75 ros::NodeHandle nh;
76 SimpleActionServer<TestAction> as(nh, "name");
77 }
78
79 TEST(SimpleActionServerConstruction, test_nh_name_cb) {
80 ros::NodeHandle nh;
81 SimpleActionServer<TestAction>::ExecuteCallback callback = [](const TestGoalConstPtr&){};
82 SimpleActionServer<TestAction> as(nh, "name", callback);
83 }
84
85 int main(int argc, char **argv) {
86 testing::InitGoogleTest(&argc, argv);
87
88 ros::init(argc, argv, "simple_action_server_construction");
89
90 return RUN_ALL_TESTS();
91 }
44 <description>The actionlib_tools package</description>
55
66 <maintainer email="michael@openrobotics.org">Michael Carroll</maintainer>
7 <maintainer email="jacob@openrobotics.org">Jacob Perron</maintainer>
78 <license>BSD</license>
89
910 <url type="website">http://www.ros.org/wiki/actionlib</url>
231231
232232 (options, args) = parser.parse_args(rospy.myargv())
233233
234 if (len(args) == 2):
234 if len(args) == 2:
235235 # get action type via rostopic
236 topic_type = rostopic._get_topic_type("%s/goal" % args[1])[0]
236 action_name = args[1].rstrip('/')
237 topic_type = rostopic._get_topic_type("%s/goal" % action_name)[0]
238 if topic_type is None:
239 parser.error("unable to retrieve the topic type for goal topic '{0}/goal'\nAre you sure the action server for '{0}' is running?".format(action_name))
237240 # remove "Goal" string from action type
238 assert("Goal" in topic_type)
239 topic_type = topic_type[0:len(topic_type)-4]
240 elif (len(args) == 3):
241 topic_type = args[2]
242 print(topic_type)
243 assert("Action" in topic_type)
241 if not topic_type.endswith("ActionGoal"):
242 parser.error("topic '%s/goal' is not an action goal topic" % action_name)
243 action_type = topic_type[:-4]
244 elif len(args) == 3:
245 action_type = args[2]
246 print(action_type)
247 action_suffix = "Action"
248 if not action_type.endswith(action_suffix):
249 parser.error("the action type provided '%s' doesn't end with the '%s' suffix" % (action_type, action_suffix))
244250 else:
245251 parser.error("You must specify the action topic name (and optionally type) Eg: ./axclient.py action_topic actionlib/TwoIntsAction ")
246252
247 action = DynamicAction(topic_type)
253 action = DynamicAction(action_type)
248254 app = AXClientApp(action, args[1])
249255 app.MainLoop()
250256 app.OnQuit()
0 ros-actionlib (1.13.2+git20211019.1.3073509-1) UNRELEASED; urgency=low
1
2 * New upstream snapshot.
3
4 -- Debian Janitor <janitor@jelmer.uk> Thu, 10 Nov 2022 11:55:47 -0000
5
06 ros-actionlib (1.13.2-10) unstable; urgency=medium
17
28 * Fix/Ignore failing tests