PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
Loading...
Searching...
No Matches
mode_executor.hpp
1/****************************************************************************
2 * Copyright (c) 2023 PX4 Development Team.
3 * SPDX-License-Identifier: BSD-3-Clause
4 ****************************************************************************/
5
6#pragma once
7
8#include "mode.hpp"
9#include "overrides.hpp"
10
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>
16
17#include <functional>
18
19class Registration;
20
21namespace px4_ros2
22{
31{
32public:
33 using CompletedCallback = std::function<void (Result)>;
34
45
46 enum class DeactivateReason
47 {
48 FailsafeActivated,
49 Other
50 };
51
52 ModeExecutorBase(
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;
57
62 bool doRegister();
63
64
68 virtual void onActivate() = 0;
69
73 virtual void onDeactivate(DeactivateReason reason) = 0;
74
79 virtual void onFailsafeDeferred() {}
80
85 uint32_t command, float param1 = NAN, float param2 = NAN, float param3 = NAN,
86 float param4 = NAN,
87 float param5 = NAN, float param6 = NAN, float param7 = NAN);
88
97 ModeBase::ModeID mode_id, const CompletedCallback & on_completed,
98 bool forced = false);
99
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);
103
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);
108
109 bool isInCharge() const {return _is_in_charge;}
110
111 bool isArmed() const {return _is_armed;}
112
113 ModeBase & ownedMode() {return _owned_mode;}
114
115 int id() const;
116
117 rclcpp::Node & node() {return _node;}
118
119 ConfigOverrides & configOverrides() {return _config_overrides;}
120
133 bool deferFailsafesSync(bool enabled, int timeout_s = 0);
134
135private:
136 class ScheduledMode
137 {
138public:
139 ScheduledMode(rclcpp::Node & node, const std::string & topic_namespace_prefix);
140
141 bool active() const {return _mode_id != ModeBase::kModeIDInvalid;}
142 void activate(ModeBase::ModeID mode_id, const CompletedCallback & on_completed);
143 void cancel();
144 ModeBase::ModeID modeId() const {return _mode_id;}
145
146private:
147 void reset() {_mode_id = ModeBase::kModeIDInvalid;}
148
149 ModeBase::ModeID _mode_id{ModeBase::kModeIDInvalid};
150 CompletedCallback _on_completed_callback;
151 rclcpp::Subscription<px4_msgs::msg::ModeCompleted>::SharedPtr _mode_completed_sub;
152 };
153
154 class WaitForVehicleStatusCondition
155 {
156public:
157 using RunCheckCallback =
158 std::function<bool (const px4_msgs::msg::VehicleStatus::UniquePtr & msg)>;
159 WaitForVehicleStatusCondition() = default;
160
161 bool active() const {return _on_completed_callback != nullptr;}
162 void update(const px4_msgs::msg::VehicleStatus::UniquePtr & msg);
163
164 void activate(
165 const RunCheckCallback & run_check_callback,
166 const CompletedCallback & on_completed);
167 void cancel();
168
169private:
170 CompletedCallback _on_completed_callback;
171 RunCheckCallback _run_check_callback;
172 };
173
174 void onRegistered();
175
176 void callOnActivate();
177 void callOnDeactivate(DeactivateReason reason);
178
179 void vehicleStatusUpdated(const px4_msgs::msg::VehicleStatus::UniquePtr & msg);
180
181 void scheduleMode(
182 ModeBase::ModeID mode_id, const px4_msgs::msg::VehicleCommand & cmd,
183 const ModeExecutorBase::CompletedCallback & on_completed, bool forced = false);
184
185 rclcpp::Node & _node;
186 const std::string _topic_namespace_prefix;
187 const Settings _settings;
188 ModeBase & _owned_mode;
189
190 std::shared_ptr<Registration> _registration;
191
192 rclcpp::Subscription<px4_msgs::msg::VehicleStatus>::SharedPtr _vehicle_status_sub;
193 rclcpp::Publisher<px4_msgs::msg::VehicleCommand>::SharedPtr _vehicle_command_pub;
194
195 ScheduledMode _current_scheduled_mode;
196 WaitForVehicleStatusCondition _current_wait_vehicle_status;
197
198 bool _is_in_charge{false};
199 bool _is_armed{false};
200 bool _was_never_activated{true};
201 ModeBase::ModeID _prev_nav_state{ModeBase::kModeIDInvalid};
202 uint8_t _prev_failsafe_defer_state{px4_msgs::msg::VehicleStatus::FAILSAFE_DEFER_STATE_DISABLED};
203
204 ConfigOverrides _config_overrides;
205};
206
208} // namespace px4_ros2
uint8_t ModeID
Mode ID, corresponds to nav_state.
Definition mode.hpp:72
Base class for a mode executor.
Definition mode_executor.hpp:31
virtual void onDeactivate(DeactivateReason reason)=0
bool deferFailsafesSync(bool enabled, int timeout_s=0)
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)
void scheduleMode(ModeBase::ModeID mode_id, const CompletedCallback &on_completed, bool forced=false)
virtual void onFailsafeDeferred()
Definition mode_executor.hpp:79
virtual void onActivate()=0
Result
Definition mode.hpp:30
Definition mode_executor.hpp:36
Activation
Definition mode_executor.hpp:38
@ 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...