PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
default_actions.hpp
1 /****************************************************************************
2  * Copyright (c) 2024 PX4 Development Team.
3  * SPDX-License-Identifier: BSD-3-Clause
4  ****************************************************************************/
5 
6 #pragma once
7 
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>
13 
14 
15 namespace px4_ros2::default_actions
16 {
25 class Rtl : public ActionInterface
26 {
27 public:
28  ~Rtl() override = default;
29  std::string name() const override {return "rtl";}
30 
31  bool shouldStopAtWaypoint(const ActionArguments & arguments) override {return false;}
32  void run(
33  const std::shared_ptr<ActionHandler> & handler, const ActionArguments & arguments,
34  const std::function<void()> & on_completed) override
35  {
36  handler->runMode(ModeBase::kModeIDRtl, on_completed);
37  }
38 };
39 
44 class Land : public ActionInterface
45 {
46 public:
47  ~Land() override = default;
48  std::string name() const override {return "land";}
49 
50  bool shouldStopAtWaypoint(const ActionArguments & arguments) override {return true;}
51  void run(
52  const std::shared_ptr<ActionHandler> & handler, const ActionArguments & arguments,
53  const std::function<void()> & on_completed) override
54  {
55  handler->runMode(ModeBase::kModeIDLand, on_completed);
56  }
57 };
58 
63 class Takeoff : public ActionInterface
64 {
65 public:
66  ~Takeoff() override = default;
67  std::string name() const override {return "takeoff";}
68 
69  void run(
70  const std::shared_ptr<ActionHandler> & handler, const ActionArguments & arguments,
71  const std::function<void()> & on_completed) override
72  {
73  handler->runMode(ModeBase::kModeIDTakeoff, on_completed);
74  }
75 };
76 
81 class Hold : public ActionInterface
82 {
83 public:
84  explicit Hold(ModeBase & mode)
85  : _node(mode.node())
86  {
87  }
88  ~Hold() override = default;
89  std::string name() const override {return "hold";}
90 
91  bool shouldStopAtWaypoint(const ActionArguments & arguments) override {return true;}
92 
93  void run(
94  const std::shared_ptr<ActionHandler> & handler, const ActionArguments & arguments,
95  const std::function<void()> & on_completed) override
96  {
97  float duration_s = 1.0f;
98  if (arguments.contains("duration")) {
99  duration_s = arguments.at<float>("duration");
100  }
101  handler->runMode(ModeBase::kModeIDLoiter, [] {});
102  _timer = _node.create_wall_timer(
103  std::chrono::duration<float>(duration_s), [this, on_completed] {
104  _timer.reset();
105  on_completed();
106  });
107  }
108 
109  void deactivate() override
110  {
111  _timer.reset();
112  }
113 
114 private:
115  rclcpp::Node & _node;
116  std::shared_ptr<rclcpp::TimerBase> _timer;
117 };
118 
123 class OnResume : public ActionInterface
124 {
125 public:
126  explicit OnResume(ModeBase & mode, std::shared_ptr<LandDetected> land_detected)
127  : _node(mode.node()), _landed(std::move(land_detected))
128  {
129  }
130 
131  ~OnResume() override = default;
132  std::string name() const override {return "onResume";}
133 
134  void run(
135  const std::shared_ptr<ActionHandler> & handler, const ActionArguments & arguments,
136  const std::function<void()> & on_completed) override;
137 
138 private:
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);
145 
146  rclcpp::Node & _node;
147  std::shared_ptr<LandDetected> _landed;
148 };
149 
155 {
156 public:
157  ~OnFailure() override = default;
158  std::string name() const override {return "onFailure";}
159 
160  void run(
161  const std::shared_ptr<ActionHandler> & handler, const ActionArguments & arguments,
162  const std::function<void()> & on_completed) override;
163 };
164 
170 {
171 public:
172  ~ChangeSettings() override = default;
173  std::string name() const override {return "changeSettings";}
174 
175  bool shouldStopAtWaypoint(const ActionArguments & arguments) override {return false;}
176 
177  void run(
178  const std::shared_ptr<ActionHandler> & handler, const ActionArguments & arguments,
179  const std::function<void()> & on_completed) override;
180 
181  void deactivate() override;
182 
183 private:
184  std::unique_ptr<ActionStateKeeper> _state;
185 };
186 
188 } /* namespace px4_ros2::default_actions */
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
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