73 static constexpr ModeID kModeIDInvalid = 0xff;
75 static constexpr ModeID kModeIDPosctl =
76 px4_msgs::msg::VehicleStatus::NAVIGATION_STATE_POSCTL;
77 static constexpr ModeID kModeIDTakeoff =
78 px4_msgs::msg::VehicleStatus::NAVIGATION_STATE_AUTO_TAKEOFF;
79 static constexpr ModeID kModeIDDescend =
80 px4_msgs::msg::VehicleStatus::NAVIGATION_STATE_DESCEND;
81 static constexpr ModeID kModeIDLand =
82 px4_msgs::msg::VehicleStatus::NAVIGATION_STATE_AUTO_LAND;
83 static constexpr ModeID kModeIDRtl =
84 px4_msgs::msg::VehicleStatus::NAVIGATION_STATE_AUTO_RTL;
85 static constexpr ModeID kModeIDPrecisionLand =
86 px4_msgs::msg::VehicleStatus::NAVIGATION_STATE_AUTO_PRECLAND;
87 static constexpr ModeID kModeIDLoiter =
88 px4_msgs::msg::VehicleStatus::NAVIGATION_STATE_AUTO_LOITER;
94 std::string mode_name,
bool want_activate_even_while_disarmed =
false,
95 ModeID request_replace_internal_mode = kModeIDInvalid)
104 rclcpp::Node & node, Settings settings,
105 const std::string & topic_namespace_prefix =
"");
138 virtual void updateSetpoint(
float dt_s) {}
152 bool isArmed()
const {
return _is_armed;}
154 bool isActive()
const {
return _is_active;}
156 ConfigOverrides & configOverrides() {
return _config_overrides;}
165 void setSkipMessageCompatibilityCheck() {_skip_message_compatibility_check =
true;}
166 void overrideRegistration(
const std::shared_ptr<Registration> & registration);
169 void addSetpointType(SetpointBase * setpoint)
override;
170 void setRequirement(
const RequirementFlags & requirement_flags)
override;
172 friend class ModeExecutorBase;
173 RegistrationSettings getRegistrationSettings()
const;
174 void onAboutToRegister();
177 void unsubscribeVehicleStatus();
178 void vehicleStatusUpdated(
179 const px4_msgs::msg::VehicleStatus::UniquePtr & msg,
180 bool do_not_activate =
false);
182 void callOnActivate();
183 void callOnDeactivate();
185 void updateSetpointUpdateTimer();
187 void updateModeRequirementsFromSetpoints();
188 void setSetpointUpdateRateFromSetpointTypes();
189 void activateSetpointType(SetpointBase & setpoint);
191 std::shared_ptr<Registration> _registration;
193 const Settings _settings;
194 bool _skip_message_compatibility_check{
false};
196 HealthAndArmingChecks _health_and_arming_checks;
198 rclcpp::Subscription<px4_msgs::msg::VehicleStatus>::SharedPtr _vehicle_status_sub;
199 rclcpp::Publisher<px4_msgs::msg::ModeCompleted>::SharedPtr _mode_completed_pub;
200 rclcpp::Publisher<px4_msgs::msg::VehicleControlMode>::SharedPtr _config_control_setpoints_pub;
202 bool _is_active{
false};
203 bool _is_armed{
false};
204 bool _completed{
false};
206 float _setpoint_update_rate_hz{0.f};
207 rclcpp::TimerBase::SharedPtr _setpoint_update_timer;
208 rclcpp::Time _last_setpoint_update{};
210 ConfigOverrides _config_overrides;
212 std::vector<std::shared_ptr<SetpointBase>> _setpoint_types;
213 std::vector<SetpointBase *> _new_setpoint_types;
Definition context.hpp:20