8 #include <px4_ros2/components/mode.hpp>
9 #include <px4_ros2/mission/actions/action.hpp>
10 #include <px4_ros2/mission/mission_executor.hpp>
11 #include <px4_ros2/vehicle_state/land_detected.hpp>
12 #include <rclcpp/rclcpp.hpp>
14 namespace px4_ros2::default_actions {
25 ~
Rtl()
override =
default;
26 std::string name()
const override {
return "rtl"; }
29 void run(
const std::shared_ptr<ActionHandler>& handler,
const ActionArguments& arguments,
30 const std::function<
void()>& on_completed)
override
32 handler->runMode(ModeBase::kModeIDRtl, on_completed);
42 ~
Land()
override =
default;
43 std::string name()
const override {
return "land"; }
46 void run(
const std::shared_ptr<ActionHandler>& handler,
const ActionArguments& arguments,
47 const std::function<
void()>& on_completed)
override
49 handler->runMode(ModeBase::kModeIDLand, on_completed);
60 std::string name()
const override {
return "takeoff"; }
62 void run(
const std::shared_ptr<ActionHandler>& handler,
const ActionArguments& arguments,
63 const std::function<
void()>& on_completed)
override
66 if (arguments.contains(
"altitude")) {
67 altitude = arguments.at<
float>(
"altitude");
69 handler->runModeTakeoff(altitude, NAN, on_completed);
80 ~
Hold()
override =
default;
81 std::string name()
const override {
return "hold"; }
85 void run(
const std::shared_ptr<ActionHandler>& handler,
const ActionArguments& arguments,
86 const std::function<
void()>& on_completed)
override
88 float duration_s = 1.0f;
89 if (arguments.contains(
"duration")) {
90 duration_s = arguments.at<
float>(
"duration");
92 handler->runMode(ModeBase::kModeIDLoiter, [] {});
94 _node.create_wall_timer(std::chrono::duration<float>(duration_s), [
this, on_completed] {
104 std::shared_ptr<rclcpp::TimerBase> _timer;
113 explicit OnResume(
ModeBase& mode, std::shared_ptr<LandDetected> land_detected)
114 : _node(mode.node()), _landed(std::move(land_detected))
119 std::string name()
const override {
return "onResume"; }
121 void run(
const std::shared_ptr<ActionHandler>& handler,
const ActionArguments& arguments,
122 const std::function<
void()>& on_completed)
override;
125 void resumeFromUnexpectedLanding(
const std::shared_ptr<ActionHandler>& handler,
126 const std::function<
void()>& on_completed,
127 int current_mission_index);
128 void navigateToPreviousWaypoint(
const std::shared_ptr<ActionHandler>& handler,
129 const std::function<
void()>& on_completed,
130 int current_mission_index);
133 std::shared_ptr<LandDetected> _landed;
143 std::string name()
const override {
return "onFailure"; }
145 void run(
const std::shared_ptr<ActionHandler>& handler,
const ActionArguments& arguments,
146 const std::function<
void()>& on_completed)
override;
156 std::string name()
const override {
return "changeSettings"; }
160 void run(
const std::shared_ptr<ActionHandler>& handler,
const ActionArguments& arguments,
161 const std::function<
void()>& on_completed)
override;
166 std::unique_ptr<ActionStateKeeper> _state;
Arguments passed to an action from the mission JSON definition.
Definition: mission.hpp:25
Interface class for an action.
Definition: action.hpp:24
Base class for a mode.
Definition: mode.hpp:73
Action to change mission settings (e.g. velocity)
Definition: default_actions.hpp:153
void deactivate() override
bool shouldStopAtWaypoint(const ActionArguments &arguments) override
Definition: default_actions.hpp:158
Default action to trigger the Hold (Loiter) mode.
Definition: default_actions.hpp:77
bool shouldStopAtWaypoint(const ActionArguments &arguments) override
Definition: default_actions.hpp:83
void deactivate() override
Definition: default_actions.hpp:100
Default action to trigger the Land mode.
Definition: default_actions.hpp:40
bool shouldStopAtWaypoint(const ActionArguments &arguments) override
Definition: default_actions.hpp:45
Default action to handle failures.
Definition: default_actions.hpp:140
Default action to resume missions.
Definition: default_actions.hpp:111
Default action to trigger the RTL mode.
Definition: default_actions.hpp:23
bool shouldStopAtWaypoint(const ActionArguments &arguments) override
Definition: default_actions.hpp:28
Default action to trigger the Takeoff mode.
Definition: default_actions.hpp:57