PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
mission_executor.hpp
1 /****************************************************************************
2  * Copyright (c) 2024 PX4 Development Team.
3  * SPDX-License-Identifier: BSD-3-Clause
4  ****************************************************************************/
5 
6 #pragma once
7 #include <memory>
8 #include <vector>
9 
10 #include <px4_ros2/components/mode.hpp>
11 #include <px4_ros2/components/mode_executor.hpp>
12 #include <px4_ros2/mission/mission.hpp>
13 #include <px4_ros2/mission/actions/action.hpp>
14 #include <px4_ros2/mission/trajectory/trajectory_executor.hpp>
15 #include <px4_ros2/vehicle_state/land_detected.hpp>
16 
17 namespace px4_ros2
18 {
23 class AsyncFunctionCalls;
24 class ActionStateKeeper;
25 
31 {
32 public:
34  {
35  std::vector<std::function<std::shared_ptr<ActionInterface>(ModeBase & mode)>>
36  custom_actions_factory;
37  std::set<std::string> default_actions{"changeSettings", "onResume", "onFailure", "takeoff",
38  "rtl", "land", "hold"};
39  std::function<std::shared_ptr<TrajectoryExecutorInterface>(ModeBase & mode)>
40  trajectory_executor_factory;
41  std::string persistence_filename;
42 
43  template<class ActionType, typename ... Args>
44  Configuration & addCustomAction(Args &&... args)
45  {
46  custom_actions_factory.push_back(
47  [args = std::tie(std::forward<Args>(args) ...)](ModeBase & mode)mutable {
48  return std::apply(
49  [&mode](auto &&... args)
50  {
51  return std::make_shared<ActionType>(mode, std::forward<Args>(args)...);
52  }, std::move(args));
53  });
54  return *this;
55  }
56  template<typename TrajectoryExecutorType, typename ... Args>
57  Configuration & withTrajectoryExecutor(Args &&... args)
58  {
59  trajectory_executor_factory =
60  [args = std::tie(std::forward<Args>(args) ...)](ModeBase & mode)mutable {
61  return std::apply(
62  [&mode](auto &&... args)
63  {
64  return std::make_shared<TrajectoryExecutorType>(mode, std::forward<Args>(args)...);
65  }, std::move(args));
66  };
67  return *this;
68  }
69  Configuration & withPersistenceFile(const std::string & filename)
70  {
71  persistence_filename = filename;
72  return *this;
73  }
74  };
75 
77  const std::string & mode_name, const Configuration & configuration,
78  rclcpp::Node & node, const std::string & topic_namespace_prefix = "");
79 
80  virtual ~MissionExecutor();
81 
82  bool doRegister();
83 
84  void setMission(const Mission & mission);
85  void resetMission();
86 
87  const Mission & mission() const {return *_mission;}
88 
89  void onActivated(const std::function<void()> & callback) {_on_activated = callback;}
90  void onDeactivated(const std::function<void()> & callback) {_on_deactivated = callback;}
95  void onProgressUpdate(const std::function<void(int)> & callback) {_on_progress_update = callback;}
96  void onCompleted(const std::function<void()> & callback) {_on_completed = callback;}
97  void onFailsafeDeferred(const std::function<void()> & callback);
98  void onReadynessUpdate(
99  const std::function<void(bool ready,
100  const std::vector<std::string> & errors)> & callback);
101 
112  bool deferFailsafes(bool enabled, int timeout_s = 0);
113 
118  void abort();
119 
120 protected:
121  class MissionMode : public ModeBase
122  {
123 public:
124  MissionMode(
125  rclcpp::Node & node, const Settings & settings, const std::string & topic_namespace_prefix,
126  MissionExecutor & mission_executor)
127  : ModeBase(node, settings, topic_namespace_prefix), _mission_executor(mission_executor)
128  {
129  }
130 
131  explicit MissionMode(const ModeBase & mode_base) = delete;
132 
133  ~MissionMode() override = default;
135  {
136  _mission_executor.checkArmingAndRunConditions(reporter);
137  }
138  void onActivate() override {}
139  void onDeactivate() override {}
140  void updateSetpoint(float dt_s) override {_mission_executor.updateSetpoint();}
141 
142  void disableWatchdogTimer() // NOLINT we just want to change the methods visibility
143  {
144  ModeBase::disableWatchdogTimer();
145  }
146 
147 private:
148  MissionExecutor & _mission_executor;
149  };
150 
152  {
153 public:
155  rclcpp::Node & node, const Settings & settings, ModeBase & owned_mode,
156  const std::string & topic_namespace_prefix, MissionExecutor & mission_executor)
157  : ModeExecutorBase(node, settings, owned_mode, topic_namespace_prefix), _mission_executor(
158  mission_executor)
159  {
160  }
161 
162  explicit MissionModeExecutor(const ModeExecutorBase & mode_executor_base) = delete;
163 
164  ~MissionModeExecutor() override = default;
165  void onActivate() override {_mission_executor.onActivate();}
166  void onDeactivate(DeactivateReason reason) override {_mission_executor.onDeactivate(reason);}
167  void onFailsafeDeferred() override
168  {
169  if (on_failsafe_deferred) {
170  on_failsafe_deferred();
171  }
172  }
173 
175  uint32_t command, float param1, float param2, float param3,
176  float param4, float param5, float param6, float param7) override
177  {
178  if (command_handler) {
179  return command_handler(
180  command,
181  param1) ? Result::Success : Result::Rejected;
182  }
184  command, param1, param2, param3, param4, param5,
185  param6, param7);
186  }
187 
188  void setRegistration(const std::shared_ptr<Registration> & registration)
189  {
190  setSkipMessageCompatibilityCheck();
191  overrideRegistration(registration);
192  }
193  std::function<bool(uint32_t, float)> command_handler{nullptr};
194  std::function<void()> on_failsafe_deferred{nullptr};
195 
196 private:
197  MissionExecutor & _mission_executor;
198  };
199 
200  virtual bool doRegisterImpl(MissionMode & mode, MissionModeExecutor & executor_base);
201 
202  void setCommandHandler(const std::function<bool(uint32_t, float)> & command_handler)
203  {
204  _mode_executor->command_handler = command_handler;
205  }
206 
207  ModeBase::ModeID modeId() const {return _mode->id();}
208 
209  ModeExecutorBase & modeExecutor() {return *_mode_executor;}
210 
211  std::shared_ptr<LandDetected> _land_detected;
212 
213 private:
214  using ActionID = int;
215  enum class AbortReason
216  {
217  Other,
218  ModeFailure,
219  TrajectoryFailure,
220  NoValidMission,
221  ActionDoesNotExist,
222  };
223  static std::string abortReasonStr(AbortReason reason);
224 
225  void checkArmingAndRunConditions(HealthAndArmingCheckReporter & reporter);
226  void checkReadynessAndReport();
227  void updateSetpoint();
228  void onActivate();
229  void onDeactivate(ModeExecutorBase::DeactivateReason reason);
230 
231  bool isReady() const {return _has_valid_mission && _actions_ready;}
232 
233  void runMode(
234  ModeBase::ModeID mode_id,
235  const std::function<void()> & on_completed, const std::function<void()> & on_failure = nullptr);
236  void runAction(
237  const std::string & action_name, const ActionArguments & arguments,
238  const std::function<void()> & on_completed);
239  void runTrajectory(
240  const std::shared_ptr<Mission> & trajectory, int start_index, int end_index,
241  const std::function<void(int)> & on_index_reached, bool stop_at_last_item);
242 
243  void runNextMissionItem();
244  void runCurrentMissionItem(bool resuming);
245  void resetMissionState();
246  std::pair<int, bool> getNextTrajectorySegment(int start_index) const;
247  bool currentActionSupportsResumeFromLanded() const;
248 
249  void setTrajectoryOptions(const TrajectoryOptions & options);
250  void clearTrajectoryOptions();
251 
252  void setCurrentMissionIndex(int index);
253 
254  void abort(AbortReason reason);
255  void invalidateActionHandler();
256 
257  void savePersistentState();
258  void clearPersistentState() const;
259  bool tryLoadPersistentState();
260  nlohmann::json getOnResumeStateAndClear();
261  void runOnResumeStoreState();
262 
263  struct ActionState
264  {
265  std::string name;
266  ActionArguments arguments;
267  };
268  std::unique_ptr<ActionStateKeeper> addContinousAction(const ActionState & state);
269  void removeContinousAction(ActionID id);
270  void runStoredActions();
271  void deactivateAllActions();
272 
273  struct PersistentState
274  {
275  std::optional<int> current_index;
276  std::string mission_checksum;
277 
278  std::map<ActionID, ActionState> continuous_actions;
279 
280  void toJson(nlohmann::json & j) const;
281  void fromJson(const nlohmann::json & j);
282  };
283 
284  PersistentState _state;
285  int _next_continuous_action_id{0};
286  const std::string _persistence_filename;
287 
288  enum class MissionItemState
289  {
290  Trajectory,
291  Other,
292  };
293  MissionItemState _mission_item_state{MissionItemState::Other};
294  ModeBase::ModeID _active_mode{};
295  bool _is_active{false};
296 
297  std::optional<rclcpp::Time> _trajectory_update_warn;
298 
299  std::shared_ptr<TrajectoryExecutorInterface> _trajectory_executor;
300  std::map<std::string, std::shared_ptr<ActionInterface>> _actions;
301  std::shared_ptr<Mission> _mission;
302  TrajectoryOptions _trajectory_options;
303  bool _has_valid_mission{false};
304  static const std::vector<std::string> kNoMissionErrors;
305  std::vector<std::string> _mission_errors{kNoMissionErrors};
306  bool _actions_ready{false};
307  rclcpp::TimerBase::SharedPtr _readyness_timer;
308  int _abort_recursion_level{0};
309 
310  rclcpp::Node & _node;
311  std::unique_ptr<MissionMode> _mode;
312  std::unique_ptr<MissionModeExecutor> _mode_executor;
313  std::shared_ptr<ActionHandler> _action_handler;
314 
315  std::unique_ptr<AsyncFunctionCalls> _reporting; // Report asynchronously to avoid potential recursive calls and state changes in between
316  std::function<void()> _on_activated;
317  std::function<void()> _on_deactivated;
318  std::function<void(int)> _on_progress_update;
319  std::function<void()> _on_completed;
320  std::function<void(bool ready, const std::vector<std::string> & errors)> _on_readyness_update;
321 
322  friend class ActionHandler;
323  friend class ActionStateKeeper;
324 };
325 
327 {
328 public:
329  ActionStateKeeper(int id, MissionExecutor & mission_executor)
330  : _id(id), _mission_executor(mission_executor) {}
331 
333  {
334  _mission_executor.removeContinousAction(_id);
335  }
336 
337 private:
338  const int _id;
339  MissionExecutor & _mission_executor;
340 };
341 
347 {
348 public:
349  explicit ActionHandler(MissionExecutor & mission_executor)
350  : _mission_executor(mission_executor) {}
351 
352  void runMode(
353  ModeBase::ModeID mode_id,
354  const std::function<void()> & on_completed, const std::function<void()> & on_failure = nullptr)
355  {
356  if (!_valid) {
357  RCLCPP_WARN(_mission_executor._node.get_logger(), "ActionHandler is not valid anymore");
358  return;
359  }
360  _mission_executor.runMode(mode_id, on_completed, on_failure);
361  }
362  void runAction(
363  const std::string & action_name, const ActionArguments & arguments,
364  const std::function<void()> & on_completed)
365  {
366  if (!_valid) {
367  RCLCPP_WARN(_mission_executor._node.get_logger(), "ActionHandler is not valid anymore");
368  return;
369  }
370  _mission_executor.runAction(action_name, arguments, on_completed);
371  }
372  void runTrajectory(
373  const std::shared_ptr<Mission> & trajectory,
374  const std::function<void()> & on_completed, bool stop_at_last_item = true);
375 
379  TrajectoryOptions getTrajectoryOptions() const {return _mission_executor._trajectory_options;}
384  {
385  if (!_valid) {
386  RCLCPP_WARN(_mission_executor._node.get_logger(), "ActionHandler is not valid anymore");
387  return;
388  }
389  _mission_executor.clearTrajectoryOptions();
390  }
397  {
398  if (!_valid) {
399  RCLCPP_WARN(_mission_executor._node.get_logger(), "ActionHandler is not valid anymore");
400  return;
401  }
402  _mission_executor.setTrajectoryOptions(options);
403  }
404 
405 
406  std::optional<int> getCurrentMissionIndex() const;
414  void setCurrentMissionIndex(int index);
415 
416  bool currentActionSupportsResumeFromLanded() const;
417 
429  std::unique_ptr<ActionStateKeeper> storeState(
430  const std::string & action_name,
431  const ActionArguments & arguments)
432  {
433  if (!_valid) {
434  return nullptr;
435  }
436  return _mission_executor.addContinousAction(
437  MissionExecutor::ActionState{action_name,
438  arguments});
439  }
440 
441  const Mission & mission() const {return _mission_executor.mission();}
442 
450  bool deferFailsafes(bool enabled, int timeout_s = 0)
451  {
452  if (!_valid) {
453  RCLCPP_WARN(_mission_executor._node.get_logger(), "ActionHandler is not valid anymore");
454  return false;
455  }
456  return _mission_executor.deferFailsafes(enabled, timeout_s);
457  }
458 
464  void onFailsafeDeferred(const std::function<void()> & callback)
465  {
466  if (!_valid) {
467  RCLCPP_WARN(_mission_executor._node.get_logger(), "ActionHandler is not valid anymore");
468  return;
469  }
470  _mission_executor.onFailsafeDeferred(callback);
471  }
472 
480  bool isValid() const {return _valid;}
481 
482 private:
483  friend class MissionExecutor;
484  void setInvalid() {_valid = false;}
485 
486  bool _valid{true};
487  MissionExecutor & _mission_executor;
488 };
489 
491 } /* namespace px4_ros2 */
Arguments passed to an action from the mission JSON definition.
Definition: mission.hpp:29
Handler passed to custom actions to run modes, actions and trajectories.
Definition: mission_executor.hpp:347
void setTrajectoryOptions(const TrajectoryOptions &options)
Override the trajectory config options.
Definition: mission_executor.hpp:396
TrajectoryOptions getTrajectoryOptions() const
get the current trajectory config options
Definition: mission_executor.hpp:379
bool isValid() const
Check if the handler is still valid.
Definition: mission_executor.hpp:480
bool deferFailsafes(bool enabled, int timeout_s=0)
enable/disable deferral of failsafes
Definition: mission_executor.hpp:450
void clearTrajectoryOptions()
Reset the current trajectory config options to the mission defaults.
Definition: mission_executor.hpp:383
void onFailsafeDeferred(const std::function< void()> &callback)
register callback for failsafe notification
Definition: mission_executor.hpp:464
std::unique_ptr< ActionStateKeeper > storeState(const std::string &action_name, const ActionArguments &arguments)
store the state of a continuous action
Definition: mission_executor.hpp:429
void setCurrentMissionIndex(int index)
Set the current mission index.
Definition: mission_executor.hpp:327
Definition: health_and_arming_checks.hpp:24
Definition: mission_executor.hpp:152
void onActivate() override
Definition: mission_executor.hpp:165
Result sendCommandSync(uint32_t command, float param1, float param2, float param3, float param4, float param5, float param6, float param7) override
Definition: mission_executor.hpp:174
void onFailsafeDeferred() override
Definition: mission_executor.hpp:167
void onDeactivate(DeactivateReason reason) override
Definition: mission_executor.hpp:166
Definition: mission_executor.hpp:122
void onDeactivate() override
Definition: mission_executor.hpp:139
void checkArmingAndRunConditions(HealthAndArmingCheckReporter &reporter) override
Definition: mission_executor.hpp:134
void onActivate() override
Definition: mission_executor.hpp:138
Mission execution state machine.
Definition: mission_executor.hpp:31
bool deferFailsafes(bool enabled, int timeout_s=0)
void onProgressUpdate(const std::function< void(int)> &callback)
Definition: mission_executor.hpp:95
Mission definition.
Definition: mission.hpp:158
Base class for a mode.
Definition: mode.hpp:71
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)
Result
Definition: mode.hpp:31
@ Rejected
The request was rejected.
Definition: mission_executor.hpp:34
Definition: mode.hpp:92
Definition: mode_executor.hpp:37
Definition: mission.hpp:121