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>
22 struct RegistrationSettings;
39 ModeFailureOther = 100,
43 static_cast<int>(Result::ModeFailureOther) ==
44 static_cast<int>(px4_msgs::msg::ModeCompleted::RESULT_FAILURE_OTHER),
45 "definition mismatch");
47 constexpr
inline const char * resultToString(
Result result) noexcept
50 case Result::Success:
return "Success";
56 case Result::Timeout:
return "Timeout";
60 case Result::ModeFailureOther:
return "Mode Failure (generic)";
74 static constexpr
ModeID kModeIDInvalid = 0xff;
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;
95 :
name(std::move(mode_name)) {}
102 Settings & activateEvenWhileDisarmed(
bool activate)
107 Settings & replaceInternalMode(
ModeID mode)
112 Settings & preventArming(
bool prevent)
120 rclcpp::Node & node, Settings settings,
121 const std::string & topic_namespace_prefix =
"");
122 ModeBase(
const ModeBase &) =
delete;
154 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(
199 const px4_msgs::msg::VehicleStatus::UniquePtr & msg,
200 bool do_not_activate =
false);
202 void callOnActivate();
203 void callOnDeactivate();
205 void updateSetpointUpdateTimer();
207 void updateModeRequirementsFromSetpoints();
208 void setSetpointUpdateRateFromSetpointTypes();
209 void activateSetpointType(SetpointBase & setpoint);
211 std::shared_ptr<Registration> _registration;
213 const Settings _settings;
214 bool _skip_message_compatibility_check{
false};
216 HealthAndArmingChecks _health_and_arming_checks;
218 rclcpp::Publisher<px4_msgs::msg::ModeCompleted>::SharedPtr _mode_completed_pub;
219 rclcpp::Publisher<px4_msgs::msg::VehicleControlMode>::SharedPtr _config_control_setpoints_pub;
221 SharedSubscriptionCallbackInstance _vehicle_status_sub_cb;
223 bool _is_active{
false};
224 bool _is_armed{
false};
225 bool _completed{
false};
227 float _setpoint_update_rate_hz{0.f};
228 rclcpp::TimerBase::SharedPtr _setpoint_update_timer;
229 rclcpp::Time _last_setpoint_update{};
231 ConfigOverrides _config_overrides;
233 std::vector<std::shared_ptr<SetpointBase>> _setpoint_types;
234 std::vector<SetpointBase *> _new_setpoint_types;
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.
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