AutoAPMS
Resilient Robot Mission Management
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 exposeToGlobalDebugLogging(node_ptr_->get_logger());
182
183 using namespace std::placeholders;
184 action_server_ptr_ = rclcpp_action::create_server<ActionT>(
185 node_ptr_, action_name, std::bind(&ActionWrapper<ActionT>::handle_goal_, this, _1, _2),
186 std::bind(&ActionWrapper<ActionT>::handle_cancel_, this, _1),
187 std::bind(&ActionWrapper<ActionT>::handle_accepted_, this, _1));
188}
189
190template <class ActionT>
191ActionWrapper<ActionT>::ActionWrapper(const std::string & action_name, rclcpp::Node::SharedPtr node_ptr)
192: ActionWrapper(action_name, node_ptr, std::make_shared<ActionContextType>(node_ptr->get_logger()))
193{
194}
195
196template <class ActionT>
197ActionWrapper<ActionT>::ActionWrapper(const std::string & action_name, const rclcpp::NodeOptions & options)
198: ActionWrapper(action_name, std::make_shared<rclcpp::Node>(action_name + "_node", options))
199{
200}
201
202template <class ActionT>
203rclcpp::node_interfaces::NodeBaseInterface::SharedPtr ActionWrapper<ActionT>::get_node_base_interface() const
204{
205 return node_ptr_->get_node_base_interface();
206}
207
208template <class ActionT>
209bool ActionWrapper<ActionT>::onGoalRequest(std::shared_ptr<const Goal> /*goal_ptr*/)
210{
211 // Always accept goal by default
212 return true;
213}
214
215template <class ActionT>
217 std::shared_ptr<const Goal> /*goal_ptr*/, std::shared_ptr<Result> /*result_ptr*/)
218{
219 // By default, the result is initialized using the default values specified in the action message definition.
220}
221
222template <class ActionT>
224 std::shared_ptr<const Goal> /*goal_ptr*/, std::shared_ptr<Result> /*result_ptr*/)
225{
226 // Always accept cancel request by default
227 return true;
228}
229
230template <class ActionT>
232 std::shared_ptr<const Goal> /*goal_ptr*/, std::shared_ptr<Result> /*result_ptr*/)
233{
234 // Do nothing by default
235 return ActionStatus::SUCCESS;
236}
237
238template <class ActionT>
239rclcpp_action::GoalResponse ActionWrapper<ActionT>::handle_goal_(
240 const rclcpp_action::GoalUUID & uuid, std::shared_ptr<const Goal> goal_ptr)
241{
242 if (action_context_ptr_->isValid() && action_context_ptr_->getGoalHandlePtr()->is_active()) {
243 RCLCPP_DEBUG(
244 node_ptr_->get_logger(), "Goal %s was REJECTED: Goal %s is still executing.",
245 rclcpp_action::to_string(uuid).c_str(),
246 rclcpp_action::to_string(action_context_ptr_->getGoalHandlePtr()->get_goal_id()).c_str());
247 return rclcpp_action::GoalResponse::REJECT;
248 }
249
250 if (!onGoalRequest(goal_ptr)) {
251 RCLCPP_DEBUG(
252 node_ptr_->get_logger(), "Goal %s was REJECTED because onGoalRequest() returned false",
253 rclcpp_action::to_string(uuid).c_str());
254 return rclcpp_action::GoalResponse::REJECT;
255 }
256
257 return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
258}
259
260template <class ActionT>
261rclcpp_action::CancelResponse ActionWrapper<ActionT>::handle_cancel_(std::shared_ptr<GoalHandle> /*goal_handle_ptr*/)
262{
263 return onCancelRequest(action_context_ptr_->getGoalHandlePtr()->get_goal(), action_context_ptr_->getResultPtr())
264 ? rclcpp_action::CancelResponse::ACCEPT
265 : rclcpp_action::CancelResponse::REJECT;
266}
267
268template <class ActionT>
269void ActionWrapper<ActionT>::handle_accepted_(std::shared_ptr<GoalHandle> goal_handle_ptr)
270{
271 action_context_ptr_->setUp(goal_handle_ptr);
272 std::shared_ptr<const Goal> goal_ptr = action_context_ptr_->getGoalHandlePtr()->get_goal();
273 setInitialResult(goal_ptr, action_context_ptr_->getResultPtr());
274 (void)goal_handle_ptr; // action_context_ptr_ takes ownership of goal handle from now on
275
276 const Params & params = param_listener_.get_params();
277
278 // Ensure that feedback is published already after the first cycle
279 last_feedback_ts_ = node_ptr_->now() - rclcpp::Duration::from_seconds(params.feedback_rate);
280
281 // Create the timer that triggers the execution routine
282 execution_timer_ptr_ = node_ptr_->create_wall_timer(
283 std::chrono::duration<double>(params.loop_rate), [this, goal_ptr]() { this->execution_timer_callback_(goal_ptr); });
284}
285
286template <class ActionT>
287void ActionWrapper<ActionT>::execution_timer_callback_(std::shared_ptr<const Goal> goal_ptr)
288{
289 // Cancel timer when goal has terminated
290 if (!action_context_ptr_->getGoalHandlePtr()->is_active()) {
291 execution_timer_ptr_->cancel();
292 return;
293 }
294
295 // Check if canceling
296 if (action_context_ptr_->getGoalHandlePtr()->is_canceling()) {
297 switch (cancelGoal(goal_ptr, action_context_ptr_->getResultPtr())) {
298 case ActionStatus::RUNNING:
299 return;
300 case ActionStatus::SUCCESS:
301 action_context_ptr_->cancel();
302 return;
303 case ActionStatus::FAILURE:
304 action_context_ptr_->abort();
305 return;
306 }
307 } else {
308 const auto ret = executeGoal(goal_ptr, action_context_ptr_->getFeedbackPtr(), action_context_ptr_->getResultPtr());
309
310 // Publish feedback
311 const auto feedback_rate = rclcpp::Duration::from_seconds(param_listener_.get_params().feedback_rate);
312 if (node_ptr_->now() - last_feedback_ts_ > feedback_rate) {
313 action_context_ptr_->publishFeedback();
314 last_feedback_ts_ = node_ptr_->now();
315 }
316
317 switch (ret) {
318 case ActionStatus::RUNNING:
319 break;
320 case ActionStatus::SUCCESS:
321 action_context_ptr_->succeed();
322 return;
323 case ActionStatus::FAILURE:
324 action_context_ptr_->abort();
325 return;
326 }
327 }
328}
329
330} // 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.
void exposeToGlobalDebugLogging(const rclcpp::Logger &logger)
Enable ROS 2 debug logging, if the C preprocessor flag _AUTO_APMS_DEBUG_LOGGING is set.
Definition logging.cpp:25
Fundamental helper classes and utility functions.