PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
mode.hpp
1 /****************************************************************************
2  * Copyright (c) 2023 PX4 Development Team.
3  * SPDX-License-Identifier: BSD-3-Clause
4  ****************************************************************************/
5 
6 #pragma once
7 
8 #include <cstdint>
9 
10 #include <rclcpp/rclcpp.hpp>
11 #include <px4_msgs/msg/mode_completed.hpp>
12 #include <px4_msgs/msg/vehicle_control_mode.hpp>
13 #include <px4_msgs/msg/vehicle_status.hpp>
14 #include "health_and_arming_checks.hpp"
15 #include "overrides.hpp"
16 #include "manual_control_input.hpp"
17 #include <px4_ros2/common/setpoint_base.hpp>
18 #include <px4_ros2/common/context.hpp>
19 #include <px4_ros2/components/shared_subscription.hpp>
20 
21 class Registration;
22 struct RegistrationSettings;
23 
24 namespace px4_ros2
25 {
30 enum class Result
31 {
32  Success = 0,
33  Rejected,
34  Interrupted,
35  Timeout,
36  Deactivated,
37 
38  // Mode-specific results
39  ModeFailureOther = 100,
40 };
41 
42 static_assert(
43  static_cast<int>(Result::ModeFailureOther) ==
44  static_cast<int>(px4_msgs::msg::ModeCompleted::RESULT_FAILURE_OTHER),
45  "definition mismatch");
46 
47 constexpr inline const char * resultToString(Result result) noexcept
48 {
49  switch (result) {
50  case Result::Success: return "Success";
51 
52  case Result::Rejected: return "Rejected";
53 
54  case Result::Interrupted: return "Interrupted";
55 
56  case Result::Timeout: return "Timeout";
57 
58  case Result::Deactivated: return "Deactivated";
59 
60  case Result::ModeFailureOther: return "Mode Failure (generic)";
61  }
62 
63  return "Unknown";
64 }
65 
70 class ModeBase : public Context
71 {
72 public:
73  using ModeID = uint8_t;
74  static constexpr ModeID kModeIDInvalid = 0xff;
75 
76  static constexpr ModeID kModeIDPosctl =
77  px4_msgs::msg::VehicleStatus::NAVIGATION_STATE_POSCTL;
78  static constexpr ModeID kModeIDTakeoff =
79  px4_msgs::msg::VehicleStatus::NAVIGATION_STATE_AUTO_TAKEOFF;
80  static constexpr ModeID kModeIDDescend =
81  px4_msgs::msg::VehicleStatus::NAVIGATION_STATE_DESCEND;
82  static constexpr ModeID kModeIDLand =
83  px4_msgs::msg::VehicleStatus::NAVIGATION_STATE_AUTO_LAND;
84  static constexpr ModeID kModeIDRtl =
85  px4_msgs::msg::VehicleStatus::NAVIGATION_STATE_AUTO_RTL;
86  static constexpr ModeID kModeIDPrecisionLand =
87  px4_msgs::msg::VehicleStatus::NAVIGATION_STATE_AUTO_PRECLAND;
88  static constexpr ModeID kModeIDLoiter =
89  px4_msgs::msg::VehicleStatus::NAVIGATION_STATE_AUTO_LOITER;
90 
91  struct Settings
92  {
93  // NOLINTNEXTLINE allow implicit conversion
94  Settings(std::string mode_name)
95  : name(std::move(mode_name)) {}
96 
97  const std::string name;
99  ModeID replace_internal_mode{kModeIDInvalid};
100  bool prevent_arming{false};
101 
102  Settings & activateEvenWhileDisarmed(bool activate)
103  {
104  activate_even_while_disarmed = activate;
105  return *this;
106  }
107  Settings & replaceInternalMode(ModeID mode)
108  {
109  replace_internal_mode = mode;
110  return *this;
111  }
112  Settings & preventArming(bool prevent)
113  {
114  prevent_arming = prevent;
115  return *this;
116  }
117  };
118 
119  ModeBase(
120  rclcpp::Node & node, Settings settings,
121  const std::string & topic_namespace_prefix = "");
122  ModeBase(const ModeBase &) = delete;
123  virtual ~ModeBase();
124 
129  bool doRegister();
130 
131 
136 
140  virtual void onActivate() = 0;
141 
145  virtual void onDeactivate() = 0;
146 
152  void setSetpointUpdateRate(float rate_hz);
153 
154  virtual void updateSetpoint(float dt_s) {}
155 
161  void completed(Result result);
162 
163 
164  // Properties & state
165 
166  ModeID id() const;
167 
168  bool isArmed() const {return _is_armed;}
169 
170  bool isActive() const {return _is_active;}
171 
172  ConfigOverrides & configOverrides() {return _config_overrides;}
173 
178  RequirementFlags & modeRequirements() {return _health_and_arming_checks.modeRequirements();}
179 
180 protected:
181  void setSkipMessageCompatibilityCheck() {_skip_message_compatibility_check = true;}
182  void overrideRegistration(const std::shared_ptr<Registration> & registration);
183 
184  void disableWatchdogTimer() {_health_and_arming_checks.disableWatchdogTimer();}
185 
186  bool defaultMessageCompatibilityCheck();
187 
188 private:
189  void addSetpointType(SetpointBase * setpoint) override;
190  void setRequirement(const RequirementFlags & requirement_flags) override;
191 
192  friend class ModeExecutorBase;
193  RegistrationSettings getRegistrationSettings() const;
194  void onAboutToRegister();
195  bool onRegistered();
196 
197  void unsubscribeVehicleStatus();
198  void vehicleStatusUpdated(
199  const px4_msgs::msg::VehicleStatus::UniquePtr & msg,
200  bool do_not_activate = false);
201 
202  void callOnActivate();
203  void callOnDeactivate();
204 
205  void updateSetpointUpdateTimer();
206 
207  void updateModeRequirementsFromSetpoints();
208  void setSetpointUpdateRateFromSetpointTypes();
209  void activateSetpointType(SetpointBase & setpoint);
210 
211  std::shared_ptr<Registration> _registration;
212 
213  const Settings _settings;
214  bool _skip_message_compatibility_check{false};
215 
216  HealthAndArmingChecks _health_and_arming_checks;
217 
218  rclcpp::Publisher<px4_msgs::msg::ModeCompleted>::SharedPtr _mode_completed_pub;
219  rclcpp::Publisher<px4_msgs::msg::VehicleControlMode>::SharedPtr _config_control_setpoints_pub;
220 
221  SharedSubscriptionCallbackInstance _vehicle_status_sub_cb;
222 
223  bool _is_active{false};
224  bool _is_armed{false};
225  bool _completed{false};
226 
227  float _setpoint_update_rate_hz{0.f};
228  rclcpp::TimerBase::SharedPtr _setpoint_update_timer;
229  rclcpp::Time _last_setpoint_update{};
230 
231  ConfigOverrides _config_overrides;
232 
233  std::vector<std::shared_ptr<SetpointBase>> _setpoint_types;
234  std::vector<SetpointBase *> _new_setpoint_types;
235 };
236 
238 } // namespace px4_ros2
Definition: context.hpp:20
Definition: health_and_arming_checks.hpp:24
Base class for a mode.
Definition: mode.hpp:71
virtual void checkArmingAndRunConditions(HealthAndArmingCheckReporter &reporter)
Definition: mode.hpp:135
RequirementFlags & modeRequirements()
Definition: mode.hpp:178
void setSetpointUpdateRate(float rate_hz)
uint8_t ModeID
Mode ID, corresponds to nav_state.
Definition: mode.hpp:73
virtual void onDeactivate()=0
virtual void onActivate()=0
void completed(Result result)
Result
Definition: mode.hpp:31
@ Interrupted
Ctrl-C or another error (from ROS)
@ Deactivated
Mode or executor got deactivated.
@ Rejected
The request was rejected.
Definition: mode.hpp:92
bool activate_even_while_disarmed
If true, the mode is also activated while disarmed if selected.
Definition: mode.hpp:98
const std::string name
Name of the mode with length < 25 characters.
Definition: mode.hpp:97
bool prevent_arming
Prevent arming while in this mode.
Definition: mode.hpp:100
ModeID replace_internal_mode
Can be used to replace an fmu-internal mode.
Definition: mode.hpp:99
Requirement flags used by modes.
Definition: requirement_flags.hpp:17