AutoAPMS
Streamlining behaviors in ROS 2
Loading...
Searching...
No Matches
action_wrapper.hpp
1// Copyright 2024 Robin Müller
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// https://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
15#pragma once
16
17#include <chrono>
18
19#include "auto_apms_util/action_context.hpp"
20#include "auto_apms_util/action_wrapper_params.hpp"
21#include "auto_apms_util/logging.hpp"
22#include "rclcpp/rclcpp.hpp"
23#include "rclcpp_action/rclcpp_action.hpp"
24
25namespace auto_apms_util
26{
27
32enum class ActionStatus : uint8_t
33{
34 RUNNING,
35 SUCCESS,
36 FAILURE
37};
38
39extern const std::string ACTION_WRAPPER_PARAM_NAME_LOOP_RATE;
40extern const std::string ACTION_WRAPPER_PARAM_NAME_FEEDBACK_RATE;
41
54template <typename ActionT>
56{
57public:
58 using Params = action_wrapper_params::Params;
59 using ParamListener = action_wrapper_params::ParamListener;
60 using Status = ActionStatus;
61 using ActionContextType = ActionContext<ActionT>;
62 using Goal = typename ActionContextType::Goal;
63 using Feedback = typename ActionContextType::Feedback;
64 using Result = typename ActionContextType::Result;
65 using GoalHandle = typename ActionContextType::GoalHandle;
66
73 explicit ActionWrapper(
74 const std::string & action_name, rclcpp::Node::SharedPtr node_ptr,
75 std::shared_ptr<ActionContextType> action_context_ptr);
76
82 explicit ActionWrapper(const std::string & action_name, rclcpp::Node::SharedPtr node_ptr);
83
89 explicit ActionWrapper(const std::string & action_name, const rclcpp::NodeOptions & options);
90
91private:
95
103 virtual bool onGoalRequest(std::shared_ptr<const Goal> goal_ptr);
104
112 virtual void setInitialResult(std::shared_ptr<const Goal> goal_ptr, std::shared_ptr<Result> result_ptr);
113
122 virtual bool onCancelRequest(std::shared_ptr<const Goal> goal_ptr, std::shared_ptr<Result> result_ptr);
123
135 virtual Status cancelGoal(std::shared_ptr<const Goal> goal_ptr, std::shared_ptr<Result> result_ptr);
136
147 virtual Status executeGoal(
148 std::shared_ptr<const Goal> goal_ptr, std::shared_ptr<Feedback> feedback_ptr,
149 std::shared_ptr<Result> result_ptr) = 0;
150
154
155 rclcpp_action::GoalResponse handle_goal_(const rclcpp_action::GoalUUID & uuid, std::shared_ptr<const Goal> goal_ptr);
156 rclcpp_action::CancelResponse handle_cancel_(std::shared_ptr<GoalHandle> goal_handle_ptr);
157 void handle_accepted_(std::shared_ptr<GoalHandle> goal_handle_ptr);
158
159 void execution_timer_callback_(std::shared_ptr<const Goal> goal_ptr);
160
161public:
162 rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface() const;
163
164protected:
165 rclcpp::Node::SharedPtr node_ptr_;
166 std::shared_ptr<ActionContextType> action_context_ptr_;
167 const ParamListener param_listener_;
168
169private:
170 typename rclcpp_action::Server<ActionT>::SharedPtr action_server_ptr_;
171 rclcpp::TimerBase::SharedPtr execution_timer_ptr_;
172 rclcpp::Time last_feedback_ts_;
173};
174
175template <class ActionT>
177 const std::string & action_name, rclcpp::Node::SharedPtr node_ptr,
178 std::shared_ptr<ActionContextType> action_context_ptr)
179: node_ptr_(node_ptr), action_context_ptr_(action_context_ptr), param_listener_(node_ptr)
180{
181 using namespace std::placeholders;
182 action_server_ptr_ = rclcpp_action::create_server<ActionT>(
183 node_ptr_, action_name, std::bind(&ActionWrapper<ActionT>::handle_goal_, this, _1, _2),
184 std::bind(&ActionWrapper<ActionT>::handle_cancel_, this, _1),
185 std::bind(&ActionWrapper<ActionT>::handle_accepted_, this, _1));
186}
187
188template <class ActionT>
189ActionWrapper<ActionT>::ActionWrapper(const std::string & action_name, rclcpp::Node::SharedPtr node_ptr)
190: ActionWrapper(action_name, node_ptr, std::make_shared<ActionContextType>(node_ptr->get_logger()))
191{
192}
193
194template <class ActionT>
195ActionWrapper<ActionT>::ActionWrapper(const std::string & action_name, const rclcpp::NodeOptions & options)
196: ActionWrapper(action_name, std::make_shared<rclcpp::Node>(action_name + "_node", options))
197{
198}
199
200template <class ActionT>
201rclcpp::node_interfaces::NodeBaseInterface::SharedPtr ActionWrapper<ActionT>::get_node_base_interface() const
202{
203 return node_ptr_->get_node_base_interface();
204}
205
206template <class ActionT>
207bool ActionWrapper<ActionT>::onGoalRequest(std::shared_ptr<const Goal> /*goal_ptr*/)
208{
209 // Always accept goal by default
210 return true;
211}
212
213template <class ActionT>
215 std::shared_ptr<const Goal> /*goal_ptr*/, std::shared_ptr<Result> /*result_ptr*/)
216{
217 // By default, the result is initialized using the default values specified in the action message definition.
218}
219
220template <class ActionT>
222 std::shared_ptr<const Goal> /*goal_ptr*/, std::shared_ptr<Result> /*result_ptr*/)
223{
224 // Always accept cancel request by default
225 return true;
226}
227
228template <class ActionT>
230 std::shared_ptr<const Goal> /*goal_ptr*/, std::shared_ptr<Result> /*result_ptr*/)
231{
232 // Do nothing by default
233 return ActionStatus::SUCCESS;
234}
235
236template <class ActionT>
237rclcpp_action::GoalResponse ActionWrapper<ActionT>::handle_goal_(
238 const rclcpp_action::GoalUUID & uuid, std::shared_ptr<const Goal> goal_ptr)
239{
240 if (action_context_ptr_->isValid() && action_context_ptr_->getGoalHandlePtr()->is_active()) {
241 RCLCPP_DEBUG(
242 node_ptr_->get_logger(), "Goal %s was REJECTED: Goal %s is still executing.",
243 rclcpp_action::to_string(uuid).c_str(),
244 rclcpp_action::to_string(action_context_ptr_->getGoalHandlePtr()->get_goal_id()).c_str());
245 return rclcpp_action::GoalResponse::REJECT;
246 }
247
248 if (!onGoalRequest(goal_ptr)) {
249 RCLCPP_DEBUG(
250 node_ptr_->get_logger(), "Goal %s was REJECTED because onGoalRequest() returned false",
251 rclcpp_action::to_string(uuid).c_str());
252 return rclcpp_action::GoalResponse::REJECT;
253 }
254
255 return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
256}
257
258template <class ActionT>
259rclcpp_action::CancelResponse ActionWrapper<ActionT>::handle_cancel_(std::shared_ptr<GoalHandle> /*goal_handle_ptr*/)
260{
261 return onCancelRequest(action_context_ptr_->getGoalHandlePtr()->get_goal(), action_context_ptr_->getResultPtr())
262 ? rclcpp_action::CancelResponse::ACCEPT
263 : rclcpp_action::CancelResponse::REJECT;
264}
265
266template <class ActionT>
267void ActionWrapper<ActionT>::handle_accepted_(std::shared_ptr<GoalHandle> goal_handle_ptr)
268{
269 action_context_ptr_->setUp(goal_handle_ptr);
270 std::shared_ptr<const Goal> goal_ptr = action_context_ptr_->getGoalHandlePtr()->get_goal();
271 setInitialResult(goal_ptr, action_context_ptr_->getResultPtr());
272 (void)goal_handle_ptr; // action_context_ptr_ takes ownership of goal handle from now on
273
274 const Params & params = param_listener_.get_params();
275
276 // Ensure that feedback is published already after the first cycle
277 last_feedback_ts_ = node_ptr_->now() - rclcpp::Duration::from_seconds(params.feedback_rate);
278
279 // Create the timer that triggers the execution routine
280 execution_timer_ptr_ = node_ptr_->create_wall_timer(
281 std::chrono::duration<double>(params.loop_rate), [this, goal_ptr]() { this->execution_timer_callback_(goal_ptr); });
282}
283
284template <class ActionT>
285void ActionWrapper<ActionT>::execution_timer_callback_(std::shared_ptr<const Goal> goal_ptr)
286{
287 // Cancel timer when goal has terminated
288 if (!action_context_ptr_->getGoalHandlePtr()->is_active()) {
289 execution_timer_ptr_->cancel();
290 return;
291 }
292
293 // Check if canceling
294 if (action_context_ptr_->getGoalHandlePtr()->is_canceling()) {
295 switch (cancelGoal(goal_ptr, action_context_ptr_->getResultPtr())) {
296 case ActionStatus::RUNNING:
297 return;
298 case ActionStatus::SUCCESS:
299 action_context_ptr_->cancel();
300 return;
301 case ActionStatus::FAILURE:
302 action_context_ptr_->abort();
303 return;
304 }
305 } else {
306 const auto ret = executeGoal(goal_ptr, action_context_ptr_->getFeedbackPtr(), action_context_ptr_->getResultPtr());
307
308 // Publish feedback
309 const auto feedback_rate = rclcpp::Duration::from_seconds(param_listener_.get_params().feedback_rate);
310 if (node_ptr_->now() - last_feedback_ts_ > feedback_rate) {
311 action_context_ptr_->publishFeedback();
312 last_feedback_ts_ = node_ptr_->now();
313 }
314
315 switch (ret) {
316 case ActionStatus::RUNNING:
317 break;
318 case ActionStatus::SUCCESS:
319 action_context_ptr_->succeed();
320 return;
321 case ActionStatus::FAILURE:
322 action_context_ptr_->abort();
323 return;
324 }
325 }
326}
327
328} // namespace auto_apms_util
Helper class that stores contextual information related to a ROS 2 action.
virtual void setInitialResult(std::shared_ptr< const Goal > goal_ptr, std::shared_ptr< Result > result_ptr)
Configure the initial action result that is set once a goal is accepted.
virtual Status executeGoal(std::shared_ptr< const Goal > goal_ptr, std::shared_ptr< Feedback > feedback_ptr, std::shared_ptr< Result > result_ptr)=0
Callback that executes work asynchronously when the goal is executing.
virtual bool onCancelRequest(std::shared_ptr< const Goal > goal_ptr, std::shared_ptr< Result > result_ptr)
Callback for handling an incoming cancel request.
ActionWrapper(const std::string &action_name, rclcpp::Node::SharedPtr node_ptr, std::shared_ptr< ActionContextType > action_context_ptr)
Constructor.
virtual Status cancelGoal(std::shared_ptr< const Goal > goal_ptr, std::shared_ptr< Result > result_ptr)
Callback that executes work asynchronously when the goal is cancelling.
ActionWrapper(const std::string &action_name, rclcpp::Node::SharedPtr node_ptr)
Constructor.
virtual bool onGoalRequest(std::shared_ptr< const Goal > goal_ptr)
Callback for handling an incoming action goal request.
ActionWrapper(const std::string &action_name, const rclcpp::NodeOptions &options)
Constructor.
ActionStatus
Status of the auto_apms_util::ActionWrapper execution process.
Fundamental helper classes and utility functions.