PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
mode_executor.hpp
1 /****************************************************************************
2  * Copyright (c) 2023 PX4 Development Team.
3  * SPDX-License-Identifier: BSD-3-Clause
4  ****************************************************************************/
5 
6 #pragma once
7 
8 #include "mode.hpp"
9 #include "overrides.hpp"
10 
11 #include <rclcpp/rclcpp.hpp>
12 #include <px4_msgs/msg/vehicle_status.hpp>
13 #include <px4_msgs/msg/vehicle_command.hpp>
14 #include <px4_msgs/msg/vehicle_command_ack.hpp>
15 #include <px4_msgs/msg/mode_completed.hpp>
16 
17 #include <functional>
18 
19 class Registration;
20 class SharedVehicleStatusToken;
21 
22 namespace px4_ros2
23 {
32 {
33 public:
34  using CompletedCallback = std::function<void (Result)>;
35 
36  struct Settings
37  {
38  enum class Activation
39  {
43  };
45  };
46 
47  enum class DeactivateReason
48  {
49  FailsafeActivated,
50  Other
51  };
52 
53  ModeExecutorBase(const Settings & settings, ModeBase & owned_mode);
54  ModeExecutorBase(const ModeExecutorBase &) = delete;
55  virtual ~ModeExecutorBase();
56 
61  bool doRegister();
62 
63 
67  virtual void onActivate() = 0;
68 
72  virtual void onDeactivate(DeactivateReason reason) = 0;
73 
78  virtual void onFailsafeDeferred() {}
79 
83  // NOLINTNEXTLINE(google-default-arguments)
85  uint32_t command, float param1 = NAN, float param2 = NAN, float param3 = NAN,
86  float param4 = NAN,
87  float param5 = NAN, float param6 = NAN, float param7 = NAN);
88 
97  ModeBase::ModeID mode_id, const CompletedCallback & on_completed,
98  bool forced = false);
99 
100  void takeoff(const CompletedCallback & on_completed, float altitude = NAN, float heading = NAN);
101  void land(const CompletedCallback & on_completed);
102  void rtl(const CompletedCallback & on_completed);
103 
104  void arm(const CompletedCallback & on_completed, bool run_preflight_checks = true);
105  void disarm(const CompletedCallback & on_completed, bool forced = false);
106  void waitReadyToArm(const CompletedCallback & on_completed);
107  void waitUntilDisarmed(const CompletedCallback & on_completed);
108 
109  bool isInCharge() const {return _is_in_charge;}
110 
111  bool isArmed() const {return _is_armed;}
112 
113  ModeBase & ownedMode() {return _owned_mode;}
114 
115  int id() const;
116 
117  rclcpp::Node & node() {return _node;}
118 
119  ConfigOverrides & configOverrides() {return _config_overrides;}
120 
133  bool deferFailsafesSync(bool enabled, int timeout_s = 0);
134 
135 protected:
136  void setSkipMessageCompatibilityCheck() {_skip_message_compatibility_check = true;}
137  void overrideRegistration(const std::shared_ptr<Registration> & registration);
138 
139 private:
140  class ScheduledMode
141  {
142 public:
143  ScheduledMode(rclcpp::Node & node, const std::string & topic_namespace_prefix);
144 
145  bool active() const {return _mode_id != ModeBase::kModeIDInvalid;}
146  void activate(ModeBase::ModeID mode_id, const CompletedCallback & on_completed);
147  void cancel();
148  ModeBase::ModeID modeId() const {return _mode_id;}
149 
150 private:
151  void reset() {_mode_id = ModeBase::kModeIDInvalid;}
152 
153  ModeBase::ModeID _mode_id{ModeBase::kModeIDInvalid};
154  CompletedCallback _on_completed_callback;
155  rclcpp::Subscription<px4_msgs::msg::ModeCompleted>::SharedPtr _mode_completed_sub;
156  };
157 
158  class WaitForVehicleStatusCondition
159  {
160 public:
161  using RunCheckCallback =
162  std::function<bool (const px4_msgs::msg::VehicleStatus::UniquePtr & msg)>;
163  WaitForVehicleStatusCondition() = default;
164 
165  bool active() const {return _on_completed_callback != nullptr;}
166  void update(const px4_msgs::msg::VehicleStatus::UniquePtr & msg);
167 
168  void activate(
169  const RunCheckCallback & run_check_callback,
170  const CompletedCallback & on_completed);
171  void cancel();
172 
173 private:
174  CompletedCallback _on_completed_callback;
175  RunCheckCallback _run_check_callback;
176  };
177 
178  void onRegistered();
179 
180  void callOnActivate();
181  void callOnDeactivate(DeactivateReason reason);
182 
183  void vehicleStatusUpdated(const px4_msgs::msg::VehicleStatus::UniquePtr & msg);
184 
185  void scheduleMode(
186  ModeBase::ModeID mode_id, const px4_msgs::msg::VehicleCommand & cmd,
187  const ModeExecutorBase::CompletedCallback & on_completed, bool forced = false);
188 
189  rclcpp::Node & _node;
190  const std::string _topic_namespace_prefix;
191  const Settings _settings;
192  bool _skip_message_compatibility_check{false};
193  ModeBase & _owned_mode;
194 
195  std::shared_ptr<Registration> _registration;
196 
197  rclcpp::Publisher<px4_msgs::msg::VehicleCommand>::SharedPtr _vehicle_command_pub;
198 
199  std::unique_ptr<SharedVehicleStatusToken> _vehicle_status_sub_token;
200 
201  ScheduledMode _current_scheduled_mode;
202  WaitForVehicleStatusCondition _current_wait_vehicle_status;
203 
204  bool _is_in_charge{false};
205  bool _is_armed{false};
206  bool _was_never_activated{true};
207  ModeBase::ModeID _prev_nav_state{ModeBase::kModeIDInvalid};
208  uint8_t _prev_failsafe_defer_state{px4_msgs::msg::VehicleStatus::FAILSAFE_DEFER_STATE_DISABLED};
209 
210  ConfigOverrides _config_overrides;
211 };
212 
214 } // namespace px4_ros2
uint8_t ModeID
Mode ID, corresponds to nav_state.
Definition: mode.hpp:73
Base class for a mode executor.
Definition: mode_executor.hpp:32
virtual Result sendCommandSync(uint32_t command, float param1=NAN, float param2=NAN, float param3=NAN, float param4=NAN, float param5=NAN, float param6=NAN, float param7=NAN)
virtual void onDeactivate(DeactivateReason reason)=0
bool deferFailsafesSync(bool enabled, int timeout_s=0)
void scheduleMode(ModeBase::ModeID mode_id, const CompletedCallback &on_completed, bool forced=false)
virtual void onFailsafeDeferred()
Definition: mode_executor.hpp:78
virtual void onActivate()=0
Result
Definition: mode.hpp:31
Definition: mode_executor.hpp:37
Activation
Definition: mode_executor.hpp:39
@ ActivateAlways
Allow the executor to always be activated (so it can arm the vehicle)
@ ActivateOnlyWhenArmed
Only activate the executor when armed (and selected)
@ ActivateImmediately
Activate the mode and executor immediately after registration. Only use this for fully autonomous exe...