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>
21 struct RegistrationSettings;
38 ModeFailureOther = 100,
42 static_cast<int>(Result::ModeFailureOther) ==
43 static_cast<int>(px4_msgs::msg::ModeCompleted::RESULT_FAILURE_OTHER),
44 "definition mismatch");
46 constexpr
inline const char * resultToString(
Result result) noexcept
49 case Result::Success:
return "Success";
55 case Result::Timeout:
return "Timeout";
59 case Result::ModeFailureOther:
return "Mode Failure (generic)";
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;
92 std::string mode_name,
bool want_activate_even_while_disarmed =
false,
93 ModeID request_replace_internal_mode = kModeIDInvalid)
102 rclcpp::Node & node, Settings settings,
103 const std::string & topic_namespace_prefix =
"");
136 virtual void updateSetpoint(
float dt_s) {}
150 bool isArmed()
const {
return _is_armed;}
152 bool isActive()
const {
return _is_active;}
154 ConfigOverrides & configOverrides() {
return _config_overrides;}
163 void setSkipMessageCompatibilityCheck() {_skip_message_compatibility_check =
true;}
164 void overrideRegistration(
const std::shared_ptr<Registration> & registration);
167 void addSetpointType(SetpointBase * setpoint)
override;
168 void setRequirement(
const RequirementFlags & requirement_flags)
override;
170 friend class ModeExecutorBase;
171 RegistrationSettings getRegistrationSettings()
const;
172 void onAboutToRegister();
175 void unsubscribeVehicleStatus();
176 void vehicleStatusUpdated(
177 const px4_msgs::msg::VehicleStatus::UniquePtr & msg,
178 bool do_not_activate =
false);
180 void callOnActivate();
181 void callOnDeactivate();
183 void updateSetpointUpdateTimer();
185 void updateModeRequirementsFromSetpoints();
186 void setSetpointUpdateRateFromSetpointTypes();
187 void activateSetpointType(SetpointBase & setpoint);
189 std::shared_ptr<Registration> _registration;
191 const Settings _settings;
192 bool _skip_message_compatibility_check{
false};
194 HealthAndArmingChecks _health_and_arming_checks;
196 rclcpp::Subscription<px4_msgs::msg::VehicleStatus>::SharedPtr _vehicle_status_sub;
197 rclcpp::Publisher<px4_msgs::msg::ModeCompleted>::SharedPtr _mode_completed_pub;
198 rclcpp::Publisher<px4_msgs::msg::VehicleControlMode>::SharedPtr _config_control_setpoints_pub;
200 bool _is_active{
false};
201 bool _is_armed{
false};
202 bool _completed{
false};
204 float _setpoint_update_rate_hz{0.f};
205 rclcpp::TimerBase::SharedPtr _setpoint_update_timer;
206 rclcpp::Time _last_setpoint_update{};
208 ConfigOverrides _config_overrides;
210 std::vector<std::shared_ptr<SetpointBase>> _setpoint_types;
211 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:70
virtual void checkArmingAndRunConditions(HealthAndArmingCheckReporter &reporter)
Definition: mode.hpp:117
RequirementFlags & modeRequirements()
Definition: mode.hpp:160
void setSetpointUpdateRate(float rate_hz)
uint8_t ModeID
Mode ID, corresponds to nav_state.
Definition: mode.hpp:72
virtual void onDeactivate()=0
virtual void onActivate()=0
void completed(Result result)
Result
Definition: mode.hpp:30
@ Interrupted
Ctrl-C or another error (from ROS)
@ Deactivated
Mode or executor got deactivated.
@ Rejected
The request was rejected.
std::string name
Name of the mode with length < 25 characters.
Definition: mode.hpp:96
bool activate_even_while_disarmed
If true, the mode is also activated while disarmed if selected.
Definition: mode.hpp:97
ModeID replace_internal_mode
Can be used to replace an fmu-internal mode.
Definition: mode.hpp:98
Requirement flags used by modes.
Definition: requirement_flags.hpp:17