AutoAPMS
Resilient Robot Mission Management
Loading...
Searching...
No Matches
mode_executor.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 "auto_apms_px4/mode.hpp"
18#include "auto_apms_px4/vehicle_command_client.hpp"
19#include "auto_apms_util/action_wrapper.hpp"
20#include "px4_msgs/msg/mode_completed.hpp"
21#include "px4_msgs/msg/vehicle_status.hpp"
22#include "px4_ros2/components/wait_for_fmu.hpp"
23
28
34namespace auto_apms_px4
35{
36
83template <class ActionT>
84class ModeExecutor : public auto_apms_util::ActionWrapper<ActionT>
85{
86 enum class State : uint8_t
87 {
88 REQUEST_ACTIVATION,
89 WAIT_FOR_ACTIVATION,
90 WAIT_FOR_COMPLETION_SIGNAL,
91 COMPLETE
92 };
93
94public:
95 using VehicleCommandClient = auto_apms_px4::VehicleCommandClient;
96 using FlightMode = VehicleCommandClient::FlightMode;
97 using typename auto_apms_util::ActionWrapper<ActionT>::ActionContextType;
98 using typename auto_apms_util::ActionWrapper<ActionT>::Goal;
99 using typename auto_apms_util::ActionWrapper<ActionT>::Feedback;
100 using typename auto_apms_util::ActionWrapper<ActionT>::Result;
101 using ActionStatus = auto_apms_util::ActionStatus;
102
103 explicit ModeExecutor(
104 const std::string & action_name, rclcpp::Node::SharedPtr node_ptr,
105 std::shared_ptr<ActionContextType> action_context_ptr, uint8_t mode_id, bool deactivate_before_completion = true);
106 explicit ModeExecutor(
107 const std::string & action_name, const rclcpp::NodeOptions & options, uint8_t mode_id,
108 bool deactivate_before_completion = true);
109 explicit ModeExecutor(
110 const std::string & action_name, const rclcpp::NodeOptions & options, FlightMode flight_mode,
111 bool deactivate_before_completion = true);
112
113private:
114 void setUp();
115 auto_apms_util::ActionStatus asyncDeactivateFlightMode();
116 bool onGoalRequest(std::shared_ptr<const Goal> goal_ptr) override final;
117 bool onCancelRequest(std::shared_ptr<const Goal> goal_ptr, std::shared_ptr<Result> result_ptr) override final;
119 std::shared_ptr<const Goal> goal_ptr, std::shared_ptr<Result> result_ptr) override final;
121 std::shared_ptr<const Goal> goal_ptr, std::shared_ptr<Feedback> feedback_ptr,
122 std::shared_ptr<Result> result_ptr) override final;
123
124protected:
125 bool isCurrentNavState(uint8_t nav_state);
126 virtual bool sendActivationCommand(const VehicleCommandClient & client, std::shared_ptr<const Goal> goal_ptr);
127 virtual bool isCompleted(std::shared_ptr<const Goal> goal_ptr, const px4_msgs::msg::VehicleStatus & vehicle_status);
128 virtual void setFeedback(std::shared_ptr<Feedback> feedback_ptr, const px4_msgs::msg::VehicleStatus & vehicle_status);
129
130 uint8_t getModeID() const;
131
132private:
133 const VehicleCommandClient vehicle_command_client_;
134 const uint8_t mode_id_;
135 bool deactivate_before_completion_;
136 rclcpp::Subscription<px4_msgs::msg::VehicleStatus>::SharedPtr vehicle_status_sub_ptr_;
137 rclcpp::Subscription<px4_msgs::msg::ModeCompleted>::SharedPtr mode_completed_sub_ptr_;
138 px4_msgs::msg::VehicleStatus::SharedPtr last_vehicle_status_ptr_;
139 bool mode_completed_{false};
140 bool deactivation_command_sent_{false};
141 State state_{State::REQUEST_ACTIVATION};
142 rclcpp::Time activation_command_sent_time_;
143 rclcpp::Duration activation_timeout_{0, 0};
144};
145
153template <class ActionT, class ModeT>
154class ModeExecutorFactory
155{
156public:
157 ModeExecutorFactory(
158 const std::string & action_name, const rclcpp::NodeOptions & options,
159 const std::string & topic_namespace_prefix = "", bool deactivate_before_completion = true);
160
161 rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface();
162
163private:
164 rclcpp::Node::SharedPtr node_ptr_; // It's necessary to also store the node pointer here for successful destruction
165 std::unique_ptr<ModeBase<ActionT>> mode_ptr_;
166 std::shared_ptr<ModeExecutor<ActionT>> mode_executor_ptr_;
167};
168
169// #####################################################################################################################
170// ################################ DEFINITIONS ##############################################
171// #####################################################################################################################
172
173template <class ActionT>
174ModeExecutor<ActionT>::ModeExecutor(
175 const std::string & action_name, rclcpp::Node::SharedPtr node_ptr,
176 std::shared_ptr<ActionContextType> action_context_ptr, uint8_t mode_id, bool deactivate_before_completion)
177: auto_apms_util::ActionWrapper<ActionT>(action_name, node_ptr, action_context_ptr),
178 vehicle_command_client_(*node_ptr),
179 mode_id_(mode_id),
180 deactivate_before_completion_(deactivate_before_completion)
181{
182 setUp();
183}
184
185template <class ActionT>
186ModeExecutor<ActionT>::ModeExecutor(
187 const std::string & action_name, const rclcpp::NodeOptions & options, uint8_t mode_id,
188 bool deactivate_before_completion)
189: auto_apms_util::ActionWrapper<ActionT>(action_name, options),
190 vehicle_command_client_(*this->node_ptr_),
191 mode_id_(mode_id),
192 deactivate_before_completion_(deactivate_before_completion)
193{
194 setUp();
195}
196
197template <class ActionT>
198ModeExecutor<ActionT>::ModeExecutor(
199 const std::string & action_name, const rclcpp::NodeOptions & options, FlightMode flight_mode,
200 bool deactivate_before_completion)
201: ModeExecutor<ActionT>(action_name, options, static_cast<uint8_t>(flight_mode), deactivate_before_completion)
202{
203}
204
205template <class ActionT>
206void ModeExecutor<ActionT>::setUp()
207{
208 vehicle_status_sub_ptr_ = this->node_ptr_->template create_subscription<px4_msgs::msg::VehicleStatus>(
209 "/fmu/out/vehicle_status", rclcpp::QoS(1).best_effort(),
210 [this](px4_msgs::msg::VehicleStatus::UniquePtr msg) { last_vehicle_status_ptr_ = std::move(msg); });
211
212 mode_completed_sub_ptr_ = this->node_ptr_->template create_subscription<px4_msgs::msg::ModeCompleted>(
213 "/fmu/out/mode_completed", rclcpp::QoS(1).best_effort(), [this](px4_msgs::msg::ModeCompleted::UniquePtr msg) {
214 if (msg->nav_state == mode_id_) {
215 if (msg->result == px4_msgs::msg::ModeCompleted::RESULT_SUCCESS) {
216 this->mode_completed_ = true;
217 } else {
218 RCLCPP_ERROR(this->node_ptr_->get_logger(), "Flight mode %i failed to execute. Aborting...", this->mode_id_);
219 this->action_context_ptr_->abort();
220 }
221 return;
222 }
223 });
224}
225
226template <class ActionT>
227auto_apms_util::ActionStatus ModeExecutor<ActionT>::asyncDeactivateFlightMode()
228{
229 // If currently waiting for flight mode activation and HOLD is active we need to wait for the nav state to change
230 // before starting deactivation. Otherwise, we'll misinterpret the current nav state when in
231 // WAIT_FOR_HOLDING_STATE_REACHED and return success immediately
232 bool is_holding = isCurrentNavState(static_cast<uint8_t>(FlightMode::Hold));
233 if (state_ == State::WAIT_FOR_ACTIVATION) {
234 if (is_holding) {
235 auto & clock = *this->node_ptr_->get_clock();
236 RCLCPP_DEBUG_THROTTLE(
237 this->node_ptr_->get_logger(), clock, 250, "Waiting for flight mode %i to become active before deactivating...",
238 mode_id_);
239 return ActionStatus::RUNNING;
240 } else {
241 state_ = State::COMPLETE; // Change state to indicate that mode has been activated
242 }
243 }
244
245 if (is_holding) {
246 RCLCPP_DEBUG(this->node_ptr_->get_logger(), "Deactivated flight mode successfully (HOLD is active)");
247 return ActionStatus::SUCCESS;
248 } else {
249 // Only send command if not in HOLD already
250 if (!deactivation_command_sent_) {
251 if (!vehicle_command_client_.syncActivateFlightMode(FlightMode::Hold)) {
252 RCLCPP_ERROR(this->node_ptr_->get_logger(), "Failed to send command to activate HOLD");
253 return ActionStatus::FAILURE;
254 }
255 // Force to consider only new status messages after sending new command
256 last_vehicle_status_ptr_ = nullptr;
257 deactivation_command_sent_ = true;
258 }
259 }
260
261 return ActionStatus::RUNNING;
262}
263
264template <class ActionT>
265bool ModeExecutor<ActionT>::onGoalRequest(const std::shared_ptr<const Goal> /*goal_ptr*/)
266{
267 state_ = State::REQUEST_ACTIVATION;
268 deactivation_command_sent_ = false;
269 mode_completed_ = false;
270 activation_timeout_ = rclcpp::Duration::from_seconds(fmin(this->param_listener_.get_params().loop_rate * 15, 1.5));
271 return true;
272}
273
274template <class ActionT>
276 std::shared_ptr<const Goal> /*goal_ptr*/, std::shared_ptr<Result> /*result_ptr*/)
277{
278 if (deactivate_before_completion_) {
279 // To deactivate current flight mode, enable HOLD mode.
280 RCLCPP_DEBUG(
281 this->node_ptr_->get_logger(), "Cancellation requested! Will deactivate before termination (Enter HOLD)...");
282 } else {
283 RCLCPP_DEBUG(this->node_ptr_->get_logger(), "Cancellation requested!");
284 }
285 return true;
286}
287
288template <class ActionT>
290 std::shared_ptr<const Goal> /*goal_ptr*/, std::shared_ptr<Result> /*result_ptr*/)
291{
292 if (deactivate_before_completion_) {
293 return asyncDeactivateFlightMode();
294 }
295 return ActionStatus::SUCCESS;
296}
297
298template <class ActionT>
299bool ModeExecutor<ActionT>::isCurrentNavState(uint8_t nav_state)
300{
301 if (last_vehicle_status_ptr_ && last_vehicle_status_ptr_->nav_state == nav_state) {
302 return true;
303 }
304 return false;
305}
306
307template <class ActionT>
309 std::shared_ptr<const Goal> goal_ptr, std::shared_ptr<Feedback> feedback_ptr, std::shared_ptr<Result> /*result_ptr*/)
310{
311 switch (state_) {
312 case State::REQUEST_ACTIVATION:
313 if (!sendActivationCommand(vehicle_command_client_, goal_ptr)) {
314 RCLCPP_ERROR(
315 this->node_ptr_->get_logger(), "Failed to send activation command for flight mode %i. Aborting...", mode_id_);
316 return ActionStatus::FAILURE;
317 }
318 // Force to consider only new status messages after sending new command
319 last_vehicle_status_ptr_ = nullptr;
320 state_ = State::WAIT_FOR_ACTIVATION;
321 activation_command_sent_time_ = this->node_ptr_->now();
322 RCLCPP_DEBUG(
323 this->node_ptr_->get_logger(), "Activation command for flight mode %i was sent successfully", mode_id_);
324 return ActionStatus::RUNNING;
325 case State::WAIT_FOR_ACTIVATION:
326 if (isCurrentNavState(mode_id_)) {
327 RCLCPP_DEBUG(this->node_ptr_->get_logger(), "Flight mode %i is active", mode_id_);
328 state_ = State::WAIT_FOR_COMPLETION_SIGNAL;
329 } else if (this->node_ptr_->now() - activation_command_sent_time_ > activation_timeout_) {
330 RCLCPP_ERROR(this->node_ptr_->get_logger(), "Timeout activating flight mode %i. Aborting...", mode_id_);
331 return ActionStatus::FAILURE;
332 }
333 return ActionStatus::RUNNING;
334 case State::WAIT_FOR_COMPLETION_SIGNAL:
335 // Populate feedback message
336 setFeedback(feedback_ptr, *last_vehicle_status_ptr_);
337
338 // Check if execution should be terminated
339 if (isCompleted(goal_ptr, *last_vehicle_status_ptr_)) {
340 state_ = State::COMPLETE;
341 if (deactivate_before_completion_) {
342 // To deactivate current flight mode, enable HOLD mode
343 RCLCPP_DEBUG(
344 this->node_ptr_->get_logger(),
345 "Flight mode %i complete! Will deactivate before termination (Enter HOLD)...", mode_id_);
346 } else {
347 RCLCPP_DEBUG(
348 this->node_ptr_->get_logger(),
349 "Flight mode %i complete! Will leave current navigation state as is. User is "
350 "responsible for initiating the next flight mode...",
351 mode_id_);
352 }
353
354 // Don't return to complete in same iteration
355 break;
356 }
357 // Check if nav state changed
358 if (!isCurrentNavState(mode_id_)) {
359 RCLCPP_WARN(this->node_ptr_->get_logger(), "Flight mode %i was deactivated externally. Aborting...", mode_id_);
360 return ActionStatus::FAILURE;
361 }
362 return ActionStatus::RUNNING;
363 case State::COMPLETE:
364 break;
365 }
366
367 if (deactivate_before_completion_) {
368 const auto deactivation_state = asyncDeactivateFlightMode();
369 if (deactivation_state != ActionStatus::SUCCESS) {
370 return deactivation_state;
371 }
372 // Don't return to complete in same iteration
373 }
374
375 RCLCPP_DEBUG(this->node_ptr_->get_logger(), "Flight mode %i execution termination", mode_id_);
376 return ActionStatus::SUCCESS;
377}
378
379template <class ActionT>
380bool ModeExecutor<ActionT>::sendActivationCommand(
381 const VehicleCommandClient & client, std::shared_ptr<const Goal> /*goal_ptr*/)
382{
383 return client.syncActivateFlightMode(mode_id_);
384}
385
386template <class ActionT>
387bool ModeExecutor<ActionT>::isCompleted(
388 std::shared_ptr<const Goal> /*goal_ptr*/, const px4_msgs::msg::VehicleStatus & /*vehicle_status*/)
389{
390 return mode_completed_;
391}
392
393template <class ActionT>
394void ModeExecutor<ActionT>::setFeedback(
395 std::shared_ptr<Feedback> /*feedback_ptr*/, const px4_msgs::msg::VehicleStatus & /*vehicle_status*/)
396{
397 return;
398}
399
400template <class ActionT>
401uint8_t ModeExecutor<ActionT>::getModeID() const
402{
403 return mode_id_;
404}
405
406template <class ActionT, class ModeT>
407ModeExecutorFactory<ActionT, ModeT>::ModeExecutorFactory(
408 const std::string & action_name, const rclcpp::NodeOptions & options, const std::string & topic_namespace_prefix,
409 bool deactivate_before_completion)
410: node_ptr_(std::make_shared<rclcpp::Node>(action_name + "_node", options))
411{
412 static_assert(
413 std::is_base_of<ModeBase<ActionT>, ModeT>::value,
414 "Template argument ModeT must inherit auto_apms::ModeBase<ActionT> as public and with same type "
415 "ActionT as auto_apms::ActionWrapper<ActionT>");
416
417 const auto action_context_ptr = std::make_shared<auto_apms_util::ActionContext<ActionT>>(node_ptr_->get_logger());
418
419 mode_ptr_ = std::make_unique<ModeT>(
420 *node_ptr_, px4_ros2::ModeBase::Settings("mode_" + action_name), topic_namespace_prefix, action_context_ptr);
421
422 if (!px4_ros2::waitForFMU(*node_ptr_, std::chrono::seconds(3))) {
423 throw std::runtime_error("No message from FMU");
424 } else {
425 RCLCPP_DEBUG(node_ptr_->get_logger(), "FMU availability test successful.");
426 }
427
428 if (!mode_ptr_->doRegister()) {
429 RCLCPP_FATAL(node_ptr_->get_logger(), "Registration of mode with action_name: '%s' failed.", action_name.c_str());
430 throw std::runtime_error("Mode registration failed");
431 }
432
433 // AFTER (!) registration, the mode id can be queried to set up the executor
434 mode_executor_ptr_ = std::make_shared<ModeExecutor<ActionT>>(
435 action_name, node_ptr_, action_context_ptr, mode_ptr_->id(), deactivate_before_completion);
436}
437
438template <class ActionT, class ModeT>
439rclcpp::node_interfaces::NodeBaseInterface::SharedPtr ModeExecutorFactory<ActionT, ModeT>::get_node_base_interface()
440{
441 return node_ptr_->get_node_base_interface();
442}
443
444} // namespace auto_apms_px4
Generic template class for executing a PX4 mode implementing the interface of a standard ROS 2 action...
bool onCancelRequest(std::shared_ptr< const Goal > goal_ptr, std::shared_ptr< Result > result_ptr) override final
Callback for handling an incoming cancel request.
auto_apms_util::ActionStatus cancelGoal(std::shared_ptr< const Goal > goal_ptr, std::shared_ptr< Result > result_ptr) override final
Callback that executes work asynchronously when the goal is cancelling.
bool onGoalRequest(std::shared_ptr< const Goal > goal_ptr) override final
Callback for handling an incoming action goal request.
auto_apms_util::ActionStatus executeGoal(std::shared_ptr< const Goal > goal_ptr, std::shared_ptr< Feedback > feedback_ptr, std::shared_ptr< Result > result_ptr) override final
Callback that executes work asynchronously when the goal is executing.
Client for sending requests to the PX4 autopilot using the VehicleCommand topic.
Generic base class for implementing robot skills using the ROS 2 action concept.
ActionStatus
Status of the auto_apms_util::ActionWrapper execution process.
Implementation of PX4 mode peers offered by px4_ros2_cpp enabling integration with AutoAPMS.
Definition mode.hpp:26
Fundamental helper classes and utility functions.