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 #include <px4_msgs/msg/mode_completed.hpp>
10 #include <px4_msgs/msg/vehicle_control_mode.hpp>
11 #include <px4_msgs/msg/vehicle_status.hpp>
12 #include <px4_ros2/common/context.hpp>
13 #include <px4_ros2/common/setpoint_base.hpp>
14 #include <px4_ros2/components/shared_subscription.hpp>
15 #include <rclcpp/rclcpp.hpp>
16 
17 #include "health_and_arming_checks.hpp"
18 #include "manual_control_input.hpp"
19 #include "overrides.hpp"
20 
21 class Registration;
22 struct RegistrationSettings;
23 
24 namespace px4_ros2 {
29 enum class Result {
30  Success = 0,
31  Rejected,
32  Interrupted,
33  Timeout,
34  Deactivated,
35 
36  // Mode-specific results
37  ModeFailureOther = 100,
38 };
39 
40 static_assert(static_cast<int>(Result::ModeFailureOther) ==
41  static_cast<int>(px4_msgs::msg::ModeCompleted::RESULT_FAILURE_OTHER),
42  "definition mismatch");
43 
44 constexpr inline const char* resultToString(Result result) noexcept
45 {
46  switch (result) {
47  case Result::Success:
48  return "Success";
49 
50  case Result::Rejected:
51  return "Rejected";
52 
54  return "Interrupted";
55 
56  case Result::Timeout:
57  return "Timeout";
58 
60  return "Deactivated";
61 
62  case Result::ModeFailureOther:
63  return "Mode Failure (generic)";
64  }
65 
66  return "Unknown";
67 }
68 
73 class ModeBase : public Context {
74  public:
75  using ModeID = uint8_t;
76  static constexpr ModeID kModeIDInvalid = 0xff;
77 
78  static constexpr ModeID kModeIDPosctl = px4_msgs::msg::VehicleStatus::NAVIGATION_STATE_POSCTL;
79  static constexpr ModeID kModeIDTakeoff =
80  px4_msgs::msg::VehicleStatus::NAVIGATION_STATE_AUTO_TAKEOFF;
81  static constexpr ModeID kModeIDDescend = px4_msgs::msg::VehicleStatus::NAVIGATION_STATE_DESCEND;
82  static constexpr ModeID kModeIDLand = px4_msgs::msg::VehicleStatus::NAVIGATION_STATE_AUTO_LAND;
83  static constexpr ModeID kModeIDRtl = px4_msgs::msg::VehicleStatus::NAVIGATION_STATE_AUTO_RTL;
84  static constexpr ModeID kModeIDPrecisionLand =
85  px4_msgs::msg::VehicleStatus::NAVIGATION_STATE_AUTO_PRECLAND;
86  static constexpr ModeID kModeIDLoiter =
87  px4_msgs::msg::VehicleStatus::NAVIGATION_STATE_AUTO_LOITER;
88 
89  struct Settings {
90  // NOLINTNEXTLINE allow implicit conversion
91  Settings(std::string mode_name) : name(std::move(mode_name)) {}
92 
93  const std::string name;
95  false};
96  ModeID replace_internal_mode{kModeIDInvalid};
97  bool prevent_arming{false};
98  bool user_selectable{true};
99 
100  Settings& activateEvenWhileDisarmed(bool activate)
101  {
102  activate_even_while_disarmed = activate;
103  return *this;
104  }
105  Settings& replaceInternalMode(ModeID mode)
106  {
107  replace_internal_mode = mode;
108  return *this;
109  }
110  Settings& preventArming(bool prevent)
111  {
112  prevent_arming = prevent;
113  return *this;
114  }
115  Settings& userSelectable(bool selectable)
116  {
117  user_selectable = selectable;
118  return *this;
119  }
120  };
121 
122  ModeBase(rclcpp::Node& node, Settings settings, const std::string& topic_namespace_prefix = "");
123  ModeBase(const ModeBase&) = delete;
124  virtual ~ModeBase();
125 
131  bool doRegister();
132 
137 
141  virtual void onActivate() {}
142 
146  virtual void onDeactivate() {}
147 
153  void setSetpointUpdateRate(float rate_hz);
154 
155  virtual void updateSetpoint(float dt_s) {}
156 
162  void completed(Result result);
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(const px4_msgs::msg::VehicleStatus::UniquePtr& msg,
199  bool do_not_activate = false);
200 
201  void callOnActivate();
202  void callOnDeactivate();
203 
204  void updateSetpointUpdateTimer();
205 
206  void updateModeRequirementsFromSetpoints();
207  void setSetpointUpdateRateFromSetpointTypes();
208  void activateSetpointType(SetpointBase& setpoint);
209 
210  std::shared_ptr<Registration> _registration;
211 
212  const Settings _settings;
213  bool _skip_message_compatibility_check{false};
214 
215  HealthAndArmingChecks _health_and_arming_checks;
216 
217  rclcpp::Publisher<px4_msgs::msg::ModeCompleted>::SharedPtr _mode_completed_pub;
218  rclcpp::Publisher<px4_msgs::msg::VehicleControlMode>::SharedPtr _config_control_setpoints_pub;
219 
220  SharedSubscriptionCallbackInstance _vehicle_status_sub_cb;
221 
222  bool _is_active{false};
223  bool _is_armed{false};
224  bool _completed{false};
225 
226  float _setpoint_update_rate_hz{0.f};
227  rclcpp::TimerBase::SharedPtr _setpoint_update_timer;
228  rclcpp::Time _last_setpoint_update{};
229 
230  ConfigOverrides _config_overrides;
231 
232  std::vector<std::shared_ptr<SetpointBase>> _setpoint_types;
233  std::vector<SetpointBase*>
234  _new_setpoint_types;
235 };
236 
238 } // namespace px4_ros2
Definition: context.hpp:18
Definition: health_and_arming_checks.hpp:21
Base class for a mode.
Definition: mode.hpp:73
virtual void checkArmingAndRunConditions(HealthAndArmingCheckReporter &reporter)
Definition: mode.hpp:136
virtual void onDeactivate()
Definition: mode.hpp:146
RequirementFlags & modeRequirements()
Definition: mode.hpp:178
void setSetpointUpdateRate(float rate_hz)
uint8_t ModeID
Mode ID, corresponds to nav_state.
Definition: mode.hpp:75
virtual void onActivate()
Definition: mode.hpp:141
void completed(Result result)
Result
Definition: mode.hpp:29
@ Interrupted
Ctrl-C or another error (from ROS)
@ Deactivated
Mode or executor got deactivated.
@ Rejected
The request was rejected.
Definition: mode.hpp:89
bool user_selectable
If true, the mode is selectable by the user.
Definition: mode.hpp:98
bool activate_even_while_disarmed
If true, the mode is also activated while disarmed if selected.
Definition: mode.hpp:94
const std::string name
Name of the mode with length < 25 characters.
Definition: mode.hpp:93
bool prevent_arming
Prevent arming while in this mode.
Definition: mode.hpp:97
ModeID replace_internal_mode
Can be used to replace an fmu-internal mode.
Definition: mode.hpp:96
Requirement flags used by modes.
Definition: requirement_flags.hpp:15