8 #include <px4_ros2/mission/actions/action.hpp>
9 #include <px4_ros2/mission/mission_executor.hpp>
10 #include <px4_ros2/components/mode.hpp>
11 #include <px4_ros2/vehicle_state/land_detected.hpp>
12 #include <rclcpp/rclcpp.hpp>
15 namespace px4_ros2::default_actions
28 ~
Rtl()
override =
default;
29 std::string name()
const override {
return "rtl";}
33 const std::shared_ptr<ActionHandler> & handler,
const ActionArguments & arguments,
34 const std::function<
void()> & on_completed)
override
36 handler->runMode(ModeBase::kModeIDRtl, on_completed);
47 ~
Land()
override =
default;
48 std::string name()
const override {
return "land";}
52 const std::shared_ptr<ActionHandler> & handler,
const ActionArguments & arguments,
53 const std::function<
void()> & on_completed)
override
55 handler->runMode(ModeBase::kModeIDLand, on_completed);
67 std::string name()
const override {
return "takeoff";}
70 const std::shared_ptr<ActionHandler> & handler,
const ActionArguments & arguments,
71 const std::function<
void()> & on_completed)
override
73 handler->runMode(ModeBase::kModeIDTakeoff, on_completed);
88 ~
Hold()
override =
default;
89 std::string name()
const override {
return "hold";}
94 const std::shared_ptr<ActionHandler> & handler,
const ActionArguments & arguments,
95 const std::function<
void()> & on_completed)
override
97 float duration_s = 1.0f;
98 if (arguments.contains(
"duration")) {
99 duration_s = arguments.at<
float>(
"duration");
101 handler->runMode(ModeBase::kModeIDLoiter, [] {});
102 _timer = _node.create_wall_timer(
103 std::chrono::duration<float>(duration_s), [
this, on_completed] {
115 rclcpp::Node & _node;
116 std::shared_ptr<rclcpp::TimerBase> _timer;
126 explicit OnResume(
ModeBase & mode, std::shared_ptr<LandDetected> land_detected)
127 : _node(mode.node()), _landed(std::move(land_detected))
132 std::string name()
const override {
return "onResume";}
135 const std::shared_ptr<ActionHandler> & handler,
const ActionArguments & arguments,
136 const std::function<
void()> & on_completed)
override;
139 void resumeFromUnexpectedLanding(
140 const std::shared_ptr<ActionHandler> & handler,
141 const std::function<
void()> & on_completed,
int current_mission_index);
142 void navigateToPreviousWaypoint(
143 const std::shared_ptr<ActionHandler> & handler,
144 const std::function<
void()> & on_completed,
int current_mission_index);
146 rclcpp::Node & _node;
147 std::shared_ptr<LandDetected> _landed;
158 std::string name()
const override {
return "onFailure";}
161 const std::shared_ptr<ActionHandler> & handler,
const ActionArguments & arguments,
162 const std::function<
void()> & on_completed)
override;
173 std::string name()
const override {
return "changeSettings";}
178 const std::shared_ptr<ActionHandler> & handler,
const ActionArguments & arguments,
179 const std::function<
void()> & on_completed)
override;
184 std::unique_ptr<ActionStateKeeper> _state;
Arguments passed to an action from the mission JSON definition.
Definition: mission.hpp:29
Interface class for an action.
Definition: action.hpp:26
Base class for a mode.
Definition: mode.hpp:71
Action to change mission settings (e.g. velocity)
Definition: default_actions.hpp:170
void deactivate() override
bool shouldStopAtWaypoint(const ActionArguments &arguments) override
Definition: default_actions.hpp:175
Default action to trigger the Hold (Loiter) mode.
Definition: default_actions.hpp:82
bool shouldStopAtWaypoint(const ActionArguments &arguments) override
Definition: default_actions.hpp:91
void deactivate() override
Definition: default_actions.hpp:109
Default action to trigger the Land mode.
Definition: default_actions.hpp:45
bool shouldStopAtWaypoint(const ActionArguments &arguments) override
Definition: default_actions.hpp:50
Default action to handle failures.
Definition: default_actions.hpp:155
Default action to resume missions.
Definition: default_actions.hpp:124
Default action to trigger the RTL mode.
Definition: default_actions.hpp:26
bool shouldStopAtWaypoint(const ActionArguments &arguments) override
Definition: default_actions.hpp:31
Default action to trigger the Takeoff mode.
Definition: default_actions.hpp:64