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>
17 #include "health_and_arming_checks.hpp"
18 #include "manual_control_input.hpp"
19 #include "overrides.hpp"
22 struct RegistrationSettings;
37 ModeFailureOther = 100,
40 static_assert(
static_cast<int>(Result::ModeFailureOther) ==
41 static_cast<int>(px4_msgs::msg::ModeCompleted::RESULT_FAILURE_OTHER),
42 "definition mismatch");
44 constexpr
inline const char* resultToString(
Result result) noexcept
62 case Result::ModeFailureOther:
63 return "Mode Failure (generic)";
76 static constexpr
ModeID kModeIDInvalid = 0xff;
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;
91 Settings(std::string mode_name) :
name(std::move(mode_name)) {}
100 Settings& activateEvenWhileDisarmed(
bool activate)
105 Settings& replaceInternalMode(
ModeID mode)
110 Settings& preventArming(
bool prevent)
115 Settings& userSelectable(
bool selectable)
122 ModeBase(rclcpp::Node& node, Settings settings,
const std::string& topic_namespace_prefix =
"");
123 ModeBase(
const ModeBase&) =
delete;
155 virtual void updateSetpoint(
float dt_s) {}
168 bool isArmed()
const {
return _is_armed; }
170 bool isActive()
const {
return _is_active; }
172 ConfigOverrides& configOverrides() {
return _config_overrides; }
181 void setSkipMessageCompatibilityCheck() { _skip_message_compatibility_check =
true; }
182 void overrideRegistration(
const std::shared_ptr<Registration>& registration);
184 void disableWatchdogTimer() { _health_and_arming_checks.disableWatchdogTimer(); }
186 bool defaultMessageCompatibilityCheck();
189 void addSetpointType(SetpointBase* setpoint)
override;
190 void setRequirement(
const RequirementFlags& requirement_flags)
override;
192 friend class ModeExecutorBase;
193 RegistrationSettings getRegistrationSettings()
const;
194 void onAboutToRegister();
197 void unsubscribeVehicleStatus();
198 void vehicleStatusUpdated(
const px4_msgs::msg::VehicleStatus::UniquePtr& msg,
199 bool do_not_activate =
false);
201 void callOnActivate();
202 void callOnDeactivate();
204 void updateSetpointUpdateTimer();
206 void updateModeRequirementsFromSetpoints();
207 void setSetpointUpdateRateFromSetpointTypes();
208 void activateSetpointType(SetpointBase& setpoint);
210 std::shared_ptr<Registration> _registration;
212 const Settings _settings;
213 bool _skip_message_compatibility_check{
false};
215 HealthAndArmingChecks _health_and_arming_checks;
217 rclcpp::Publisher<px4_msgs::msg::ModeCompleted>::SharedPtr _mode_completed_pub;
218 rclcpp::Publisher<px4_msgs::msg::VehicleControlMode>::SharedPtr _config_control_setpoints_pub;
220 SharedSubscriptionCallbackInstance _vehicle_status_sub_cb;
222 bool _is_active{
false};
223 bool _is_armed{
false};
224 bool _completed{
false};
226 float _setpoint_update_rate_hz{0.f};
227 rclcpp::TimerBase::SharedPtr _setpoint_update_timer;
228 rclcpp::Time _last_setpoint_update{};
230 ConfigOverrides _config_overrides;
232 std::vector<std::shared_ptr<SetpointBase>> _setpoint_types;
233 std::vector<SetpointBase*>
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.
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