9 #include "overrides.hpp"
11 #include <rclcpp/rclcpp.hpp>
12 #include <px4_msgs/msg/vehicle_status.hpp>
13 #include <px4_msgs/msg/vehicle_command.hpp>
14 #include <px4_msgs/msg/vehicle_command_ack.hpp>
15 #include <px4_msgs/msg/mode_completed.hpp>
20 class SharedVehicleStatusToken;
34 using CompletedCallback = std::function<void (
Result)>;
47 enum class DeactivateReason
53 ModeExecutorBase(
const Settings & settings, ModeBase & owned_mode);
54 ModeExecutorBase(
const ModeExecutorBase &) =
delete;
55 virtual ~ModeExecutorBase();
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;}
136 void setSkipMessageCompatibilityCheck() {_skip_message_compatibility_check =
true;}
137 void overrideRegistration(
const std::shared_ptr<Registration> & registration);
143 ScheduledMode(rclcpp::Node & node,
const std::string & topic_namespace_prefix);
145 bool active()
const {
return _mode_id != ModeBase::kModeIDInvalid;}
146 void activate(
ModeBase::ModeID mode_id,
const CompletedCallback & on_completed);
151 void reset() {_mode_id = ModeBase::kModeIDInvalid;}
154 CompletedCallback _on_completed_callback;
155 rclcpp::Subscription<px4_msgs::msg::ModeCompleted>::SharedPtr _mode_completed_sub;
158 class WaitForVehicleStatusCondition
161 using RunCheckCallback =
162 std::function<bool (
const px4_msgs::msg::VehicleStatus::UniquePtr & msg)>;
163 WaitForVehicleStatusCondition() =
default;
165 bool active()
const {
return _on_completed_callback !=
nullptr;}
166 void update(
const px4_msgs::msg::VehicleStatus::UniquePtr & msg);
169 const RunCheckCallback & run_check_callback,
170 const CompletedCallback & on_completed);
174 CompletedCallback _on_completed_callback;
175 RunCheckCallback _run_check_callback;
180 void callOnActivate();
181 void callOnDeactivate(DeactivateReason reason);
183 void vehicleStatusUpdated(
const px4_msgs::msg::VehicleStatus::UniquePtr & msg);
187 const ModeExecutorBase::CompletedCallback & on_completed,
bool forced =
false);
189 rclcpp::Node & _node;
190 const std::string _topic_namespace_prefix;
191 const Settings _settings;
192 bool _skip_message_compatibility_check{
false};
193 ModeBase & _owned_mode;
195 std::shared_ptr<Registration> _registration;
197 rclcpp::Publisher<px4_msgs::msg::VehicleCommand>::SharedPtr _vehicle_command_pub;
199 std::unique_ptr<SharedVehicleStatusToken> _vehicle_status_sub_token;
201 ScheduledMode _current_scheduled_mode;
202 WaitForVehicleStatusCondition _current_wait_vehicle_status;
204 bool _is_in_charge{
false};
205 bool _is_armed{
false};
206 bool _was_never_activated{
true};
208 uint8_t _prev_failsafe_defer_state{px4_msgs::msg::VehicleStatus::FAILSAFE_DEFER_STATE_DISABLED};
210 ConfigOverrides _config_overrides;
uint8_t ModeID
Mode ID, corresponds to nav_state.
Definition: mode.hpp:73
Base class for a mode executor.
Definition: mode_executor.hpp:32
virtual 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)
virtual void onDeactivate(DeactivateReason reason)=0
bool deferFailsafesSync(bool enabled, int timeout_s=0)
void scheduleMode(ModeBase::ModeID mode_id, const CompletedCallback &on_completed, bool forced=false)
virtual void onFailsafeDeferred()
Definition: mode_executor.hpp:78
virtual void onActivate()=0
Result
Definition: mode.hpp:31
Definition: mode_executor.hpp:37
Activation
Definition: mode_executor.hpp:39
@ ActivateAlways
Allow the executor to always be activated (so it can arm the vehicle)
@ ActivateOnlyWhenArmed
Only activate the executor when armed (and selected)
@ ActivateImmediately
Activate the mode and executor immediately after registration. Only use this for fully autonomous exe...