33 using CompletedCallback = std::function<void (
Result)>;
46 enum class DeactivateReason
53 rclcpp::Node & node,
const Settings & settings, ModeBase & owned_mode,
54 const std::string & topic_namespace_prefix =
"");
55 ModeExecutorBase(
const ModeExecutorBase &) =
delete;
56 virtual ~ModeExecutorBase() =
default;
85 uint32_t command,
float param1 = NAN,
float param2 = NAN,
float param3 = NAN,
87 float param5 = NAN,
float param6 = NAN,
float param7 = NAN);
100 void takeoff(
const CompletedCallback & on_completed,
float altitude = NAN,
float heading = NAN);
101 void land(
const CompletedCallback & on_completed);
102 void rtl(
const CompletedCallback & on_completed);
104 void arm(
const CompletedCallback & on_completed,
bool run_preflight_checks =
true);
105 void disarm(
const CompletedCallback & on_completed,
bool forced =
false);
106 void waitReadyToArm(
const CompletedCallback & on_completed);
107 void waitUntilDisarmed(
const CompletedCallback & on_completed);
109 bool isInCharge()
const {
return _is_in_charge;}
111 bool isArmed()
const {
return _is_armed;}
113 ModeBase & ownedMode() {
return _owned_mode;}
117 rclcpp::Node & node() {
return _node;}
119 ConfigOverrides & configOverrides() {
return _config_overrides;}
139 ScheduledMode(rclcpp::Node & node,
const std::string & topic_namespace_prefix);
141 bool active()
const {
return _mode_id != ModeBase::kModeIDInvalid;}
142 void activate(
ModeBase::ModeID mode_id,
const CompletedCallback & on_completed);
147 void reset() {_mode_id = ModeBase::kModeIDInvalid;}
150 CompletedCallback _on_completed_callback;
151 rclcpp::Subscription<px4_msgs::msg::ModeCompleted>::SharedPtr _mode_completed_sub;
154 class WaitForVehicleStatusCondition
157 using RunCheckCallback =
158 std::function<bool (
const px4_msgs::msg::VehicleStatus::UniquePtr & msg)>;
159 WaitForVehicleStatusCondition() =
default;
161 bool active()
const {
return _on_completed_callback !=
nullptr;}
162 void update(
const px4_msgs::msg::VehicleStatus::UniquePtr & msg);
165 const RunCheckCallback & run_check_callback,
166 const CompletedCallback & on_completed);
170 CompletedCallback _on_completed_callback;
171 RunCheckCallback _run_check_callback;
176 void callOnActivate();
177 void callOnDeactivate(DeactivateReason reason);
179 void vehicleStatusUpdated(
const px4_msgs::msg::VehicleStatus::UniquePtr & msg);
183 const ModeExecutorBase::CompletedCallback & on_completed,
bool forced =
false);
185 rclcpp::Node & _node;
186 const std::string _topic_namespace_prefix;
187 const Settings _settings;
188 ModeBase & _owned_mode;
190 std::shared_ptr<Registration> _registration;
192 rclcpp::Subscription<px4_msgs::msg::VehicleStatus>::SharedPtr _vehicle_status_sub;
193 rclcpp::Publisher<px4_msgs::msg::VehicleCommand>::SharedPtr _vehicle_command_pub;
195 ScheduledMode _current_scheduled_mode;
196 WaitForVehicleStatusCondition _current_wait_vehicle_status;
198 bool _is_in_charge{
false};
199 bool _is_armed{
false};
200 bool _was_never_activated{
true};
202 uint8_t _prev_failsafe_defer_state{px4_msgs::msg::VehicleStatus::FAILSAFE_DEFER_STATE_DISABLED};
204 ConfigOverrides _config_overrides;
Result sendCommandSync(uint32_t command, float param1=NAN, float param2=NAN, float param3=NAN, float param4=NAN, float param5=NAN, float param6=NAN, float param7=NAN)