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 <px4_ros2/components/mode.hpp>
9 #include <px4_ros2/components/mode_executor.hpp>
10 #include <px4_ros2/mission/actions/action.hpp>
11 #include <px4_ros2/mission/mission.hpp>
12 #include <px4_ros2/mission/trajectory/trajectory_executor.hpp>
13 #include <px4_ros2/vehicle_state/land_detected.hpp>
14 #include <vector>
15 
16 namespace px4_ros2 {
21 class AsyncFunctionCalls;
22 class ActionStateKeeper;
23 
29  public:
30  struct Configuration {
31  std::vector<std::function<std::shared_ptr<ActionInterface>(ModeBase& mode)>>
32  custom_actions_factory;
33  std::set<std::string> default_actions{
34  "changeSettings", "onResume", "onFailure", "takeoff", "rtl", "land", "hold"};
35  std::function<std::shared_ptr<TrajectoryExecutorInterface>(ModeBase& mode)>
36  trajectory_executor_factory;
37  std::string persistence_filename;
38 
39  template <class ActionType, typename... Args>
40  Configuration& addCustomAction(Args&&... args)
41  {
42  custom_actions_factory.push_back(
43  [args = std::tie(std::forward<Args>(args)...)](ModeBase& mode) mutable {
44  return std::apply(
45  [&mode](auto&&... args) {
46  return std::make_shared<ActionType>(mode, std::forward<Args>(args)...);
47  },
48  std::move(args));
49  });
50  return *this;
51  }
52  template <typename TrajectoryExecutorType, typename... Args>
53  Configuration& withTrajectoryExecutor(Args&&... args)
54  {
55  trajectory_executor_factory = [args = std::tie(std::forward<Args>(args)...)](
56  ModeBase& mode) mutable {
57  return std::apply(
58  [&mode](auto&&... args) {
59  return std::make_shared<TrajectoryExecutorType>(mode, std::forward<Args>(args)...);
60  },
61  std::move(args));
62  };
63  return *this;
64  }
65  Configuration& withPersistenceFile(const std::string& filename)
66  {
67  persistence_filename = filename;
68  return *this;
69  }
70  };
71 
72  MissionExecutor(const std::string& mode_name, const Configuration& configuration,
73  rclcpp::Node& node, const std::string& topic_namespace_prefix = "");
74 
75  virtual ~MissionExecutor();
76 
77  bool doRegister();
78 
79  void setMission(const Mission& mission);
80  void resetMission();
81 
82  const Mission& mission() const { return *_mission; }
83 
84  void onActivated(const std::function<void()>& callback) { _on_activated = callback; }
85  void onDeactivated(const std::function<void()>& callback) { _on_deactivated = callback; }
90  void onProgressUpdate(const std::function<void(int)>& callback)
91  {
92  _on_progress_update = callback;
93  }
94  void onCompleted(const std::function<void()>& callback) { _on_completed = callback; }
95  void onFailsafeDeferred(const std::function<void()>& callback);
96  void onReadynessUpdate(
97  const std::function<void(bool ready, const std::vector<std::string>& errors)>& callback);
98 
105  void onActivityInfoChange(const std::function<void(const std::optional<std::string>&)>& callback)
106  {
107  _on_activity_info_change = callback;
108  }
109 
120  void setActivityInfo(const std::optional<std::string>& activity_info);
131  bool deferFailsafes(bool enabled, int timeout_s = 0);
132 
133  bool controlAutoSetHome(bool enabled);
134 
139  void abort();
140 
141  protected:
142  class MissionMode : public ModeBase {
143  public:
144  MissionMode(rclcpp::Node& node, const Settings& settings,
145  const std::string& topic_namespace_prefix, MissionExecutor& mission_executor)
146  : ModeBase(node, settings, topic_namespace_prefix), _mission_executor(mission_executor)
147  {
148  }
149 
150  explicit MissionMode(const ModeBase& mode_base) = delete;
151 
152  ~MissionMode() override = default;
154  {
155  _mission_executor.checkArmingAndRunConditions(reporter);
156  }
157  void updateSetpoint(float dt_s) override { _mission_executor.updateSetpoint(); }
158 
159  void disableWatchdogTimer() // NOLINT we just want to change the methods visibility
160  {
161  ModeBase::disableWatchdogTimer();
162  }
163 
164  private:
165  MissionExecutor& _mission_executor;
166  };
167 
169  public:
170  MissionModeExecutor(rclcpp::Node& node, const Settings& settings, ModeBase& owned_mode,
171  const std::string& topic_namespace_prefix,
172  MissionExecutor& mission_executor)
173  : ModeExecutorBase(settings, owned_mode), _mission_executor(mission_executor)
174  {
175  }
176 
177  explicit MissionModeExecutor(const ModeExecutorBase& mode_executor_base) = delete;
178 
179  ~MissionModeExecutor() override = default;
180  void onActivate() override { _mission_executor.onActivate(); }
181  void onDeactivate(DeactivateReason reason) override { _mission_executor.onDeactivate(reason); }
182  void onFailsafeDeferred() override
183  {
184  if (on_failsafe_deferred) {
185  on_failsafe_deferred();
186  }
187  }
188 
189  Result sendCommandSync(uint32_t command, float param1, float param2, float param3, float param4,
190  float param5, float param6, float param7) override
191  {
192  if (command_handler) {
193  return command_handler(command, param1) ? Result::Success : Result::Rejected;
194  }
195  return ModeExecutorBase::sendCommandSync(command, param1, param2, param3, param4, param5,
196  param6, param7);
197  }
198 
199  void setRegistration(const std::shared_ptr<Registration>& registration)
200  {
201  setSkipMessageCompatibilityCheck();
202  overrideRegistration(registration);
203  }
204  std::function<bool(uint32_t, float)> command_handler{nullptr};
205  std::function<void()> on_failsafe_deferred{nullptr};
206 
207  private:
208  MissionExecutor& _mission_executor;
209  };
210 
211  virtual bool doRegisterImpl(MissionMode& mode, MissionModeExecutor& executor_base);
212 
213  void setCommandHandler(const std::function<bool(uint32_t, float)>& command_handler)
214  {
215  _mode_executor->command_handler = command_handler;
216  }
217 
218  ModeBase::ModeID modeId() const { return _mode->id(); }
219 
220  ModeExecutorBase& modeExecutor() { return *_mode_executor; }
221 
222  std::shared_ptr<LandDetected> _land_detected;
223 
224  private:
225  using ActionID = int;
226  enum class AbortReason {
227  Other,
228  ModeFailure,
229  TrajectoryFailure,
230  NoValidMission,
231  ActionDoesNotExist,
232  };
233  static std::string abortReasonStr(AbortReason reason);
234 
235  void checkArmingAndRunConditions(HealthAndArmingCheckReporter& reporter);
236  void checkReadynessAndReport();
237  void updateSetpoint();
238  void onActivate();
239  void onDeactivate(ModeExecutorBase::DeactivateReason reason);
240 
241  bool isReady() const { return _has_valid_mission && _actions_ready; }
242 
243  void runMode(ModeBase::ModeID mode_id, const std::function<void()>& on_completed,
244  const std::function<void()>& on_failure = nullptr);
253  void runModeTakeoff(float altitude, float heading, const std::function<void()>& on_completed,
254  const std::function<void()>& on_failure = nullptr);
255  void runAction(const std::string& action_name, const ActionArguments& arguments,
256  const std::function<void()>& on_completed);
257  void runTrajectory(const std::shared_ptr<Mission>& trajectory, int start_index, int end_index,
258  const std::function<void(int)>& on_index_reached, bool stop_at_last_item);
259 
260  void runNextMissionItem();
261  void runCurrentMissionItem(bool resuming);
262  void resetMissionState();
263  std::pair<int, bool> getNextTrajectorySegment(int start_index) const;
264  bool currentActionSupportsResumeFromLanded() const;
265 
266  void setTrajectoryOptions(const TrajectoryOptions& options);
267  void clearTrajectoryOptions();
268 
269  void setCurrentMissionIndex(int index);
270 
271  void abort(AbortReason reason);
272  void invalidateActionHandler();
273 
274  void savePersistentState();
275  void clearPersistentState() const;
276  bool tryLoadPersistentState();
277  nlohmann::json getOnResumeStateAndClear();
278  void runOnResumeStoreState();
279 
280  struct ActionState {
281  std::string name;
282  ActionArguments arguments;
283  };
284  std::unique_ptr<ActionStateKeeper> addContinousAction(const ActionState& state);
285  void removeContinousAction(ActionID id);
286  void runStoredActions();
287  void deactivateAllActions();
288 
289  struct PersistentState {
290  std::optional<int> current_index;
291  std::string mission_checksum;
292 
293  std::map<ActionID, ActionState> continuous_actions;
294 
295  void toJson(nlohmann::json& j) const;
296  void fromJson(const nlohmann::json& j);
297  };
298 
299  PersistentState _state;
300  int _next_continuous_action_id{0};
301  const std::string _persistence_filename;
302 
303  enum class MissionItemState {
304  Trajectory,
305  Other,
306  };
307  MissionItemState _mission_item_state{MissionItemState::Other};
308  ModeBase::ModeID _active_mode{};
309  bool _is_active{false};
310 
311  std::optional<rclcpp::Time> _trajectory_update_warn;
312 
313  std::shared_ptr<TrajectoryExecutorInterface> _trajectory_executor;
314  std::map<std::string, std::shared_ptr<ActionInterface>> _actions;
315  std::shared_ptr<Mission> _mission;
316  TrajectoryOptions _trajectory_options;
317  bool _has_valid_mission{false};
318  static const std::vector<std::string> kNoMissionErrors;
319  std::vector<std::string> _mission_errors{kNoMissionErrors};
320  bool _actions_ready{false};
321  rclcpp::TimerBase::SharedPtr _readyness_timer;
322  int _abort_recursion_level{
323  0};
324 
325  rclcpp::Node& _node;
326  std::unique_ptr<MissionMode> _mode;
327  std::unique_ptr<MissionModeExecutor> _mode_executor;
328  std::shared_ptr<ActionHandler> _action_handler;
329 
330  std::unique_ptr<AsyncFunctionCalls> _reporting; // Report asynchronously to avoid potential
331  // recursive calls and state changes in between
332  std::function<void()> _on_activated;
333  std::function<void()> _on_deactivated;
334  std::function<void(int)> _on_progress_update;
335  std::function<void()> _on_completed;
336  std::function<void(const std::optional<std::string>&)> _on_activity_info_change;
337  std::function<void(bool ready, const std::vector<std::string>& errors)> _on_readyness_update;
338 
339  friend class ActionHandler;
340  friend class ActionStateKeeper;
341 };
342 
344  public:
345  ActionStateKeeper(int id, MissionExecutor& mission_executor)
346  : _id(id), _mission_executor(mission_executor)
347  {
348  }
349 
350  ~ActionStateKeeper() { _mission_executor.removeContinousAction(_id); }
351 
352  private:
353  const int _id;
354  MissionExecutor& _mission_executor;
355 };
356 
362  public:
363  explicit ActionHandler(MissionExecutor& mission_executor) : _mission_executor(mission_executor) {}
364 
365  void runMode(ModeBase::ModeID mode_id, const std::function<void()>& on_completed,
366  const std::function<void()>& on_failure = nullptr)
367  {
368  if (!_valid) {
369  RCLCPP_WARN(_mission_executor._node.get_logger(), "ActionHandler is not valid anymore");
370  return;
371  }
372  _mission_executor.runMode(mode_id, on_completed, on_failure);
373  }
382  void runModeTakeoff(float altitude, float heading, const std::function<void()>& on_completed,
383  const std::function<void()>& on_failure = nullptr)
384  {
385  if (!_valid) {
386  RCLCPP_WARN(_mission_executor._node.get_logger(), "ActionHandler is not valid anymore");
387  return;
388  }
389  _mission_executor.runModeTakeoff(altitude, heading, on_completed, on_failure);
390  }
391  void runAction(const std::string& action_name, const ActionArguments& arguments,
392  const std::function<void()>& on_completed)
393  {
394  if (!_valid) {
395  RCLCPP_WARN(_mission_executor._node.get_logger(), "ActionHandler is not valid anymore");
396  return;
397  }
398  _mission_executor.runAction(action_name, arguments, on_completed);
399  }
400  void runTrajectory(const std::shared_ptr<Mission>& trajectory,
401  const std::function<void()>& on_completed, bool stop_at_last_item = true);
402 
406  TrajectoryOptions getTrajectoryOptions() const { return _mission_executor._trajectory_options; }
411  {
412  if (!_valid) {
413  RCLCPP_WARN(_mission_executor._node.get_logger(), "ActionHandler is not valid anymore");
414  return;
415  }
416  _mission_executor.clearTrajectoryOptions();
417  }
424  {
425  if (!_valid) {
426  RCLCPP_WARN(_mission_executor._node.get_logger(), "ActionHandler is not valid anymore");
427  return;
428  }
429  _mission_executor.setTrajectoryOptions(options);
430  }
431 
440  void setActvityInfo(const std::string& activity_info)
441  {
442  if (!_valid) {
443  RCLCPP_WARN(_mission_executor._node.get_logger(), "ActionHandler is not valid anymore");
444  return;
445  }
446  _mission_executor.setActivityInfo(activity_info);
447  }
448 
455  {
456  if (!_valid) {
457  RCLCPP_WARN(_mission_executor._node.get_logger(), "ActionHandler is not valid anymore");
458  return;
459  }
460  _mission_executor.setActivityInfo(std::nullopt);
461  }
462 
463  std::optional<int> getCurrentMissionIndex() const;
473  void setCurrentMissionIndex(int index);
474 
475  bool currentActionSupportsResumeFromLanded() const;
476 
491  std::unique_ptr<ActionStateKeeper> storeState(const std::string& action_name,
492  const ActionArguments& arguments)
493  {
494  if (!_valid) {
495  return nullptr;
496  }
497  return _mission_executor.addContinousAction(
498  MissionExecutor::ActionState{action_name, arguments});
499  }
500 
501  const Mission& mission() const { return _mission_executor.mission(); }
502 
510  bool deferFailsafes(bool enabled, int timeout_s = 0)
511  {
512  if (!_valid) {
513  RCLCPP_WARN(_mission_executor._node.get_logger(), "ActionHandler is not valid anymore");
514  return false;
515  }
516  return _mission_executor.deferFailsafes(enabled, timeout_s);
517  }
518 
519  bool controlAutoSetHome(bool enabled)
520  {
521  if (!_valid) {
522  RCLCPP_WARN(_mission_executor._node.get_logger(), "ActionHandler is not valid anymore");
523  return false;
524  }
525  return _mission_executor.controlAutoSetHome(enabled);
526  }
527 
533  void onFailsafeDeferred(const std::function<void()>& callback)
534  {
535  if (!_valid) {
536  RCLCPP_WARN(_mission_executor._node.get_logger(), "ActionHandler is not valid anymore");
537  return;
538  }
539  _mission_executor.onFailsafeDeferred(callback);
540  }
541 
548  bool isValid() const { return _valid; }
549 
550  private:
551  friend class MissionExecutor;
552  void setInvalid() { _valid = false; }
553 
554  bool _valid{true};
555  MissionExecutor& _mission_executor;
556 };
557 
559 } /* namespace px4_ros2 */
Arguments passed to an action from the mission JSON definition.
Definition: mission.hpp:25
Handler passed to custom actions to run modes, actions and trajectories.
Definition: mission_executor.hpp:361
void setTrajectoryOptions(const TrajectoryOptions &options)
Override the trajectory config options.
Definition: mission_executor.hpp:423
TrajectoryOptions getTrajectoryOptions() const
get the current trajectory config options
Definition: mission_executor.hpp:406
void setActvityInfo(const std::string &activity_info)
Sets the activity info for the mission executor. This method forwards the provided activity string to...
Definition: mission_executor.hpp:440
bool isValid() const
Check if the handler is still valid.
Definition: mission_executor.hpp:548
void clearActivityInfo()
Clears the activity information. This method sets the activity info of the mission executor to std::n...
Definition: mission_executor.hpp:454
bool deferFailsafes(bool enabled, int timeout_s=0)
enable/disable deferral of failsafes
Definition: mission_executor.hpp:510
void clearTrajectoryOptions()
Reset the current trajectory config options to the mission defaults.
Definition: mission_executor.hpp:410
void onFailsafeDeferred(const std::function< void()> &callback)
register callback for failsafe notification
Definition: mission_executor.hpp:533
void runModeTakeoff(float altitude, float heading, const std::function< void()> &on_completed, const std::function< void()> &on_failure=nullptr)
Trigger a takeoff.
Definition: mission_executor.hpp:382
std::unique_ptr< ActionStateKeeper > storeState(const std::string &action_name, const ActionArguments &arguments)
store the state of a continuous action
Definition: mission_executor.hpp:491
void setCurrentMissionIndex(int index)
Set the current mission index.
Definition: mission_executor.hpp:343
Definition: health_and_arming_checks.hpp:21
Definition: mission_executor.hpp:168
void onActivate() override
Definition: mission_executor.hpp:180
Result sendCommandSync(uint32_t command, float param1, float param2, float param3, float param4, float param5, float param6, float param7) override
Definition: mission_executor.hpp:189
void onFailsafeDeferred() override
Definition: mission_executor.hpp:182
void onDeactivate(DeactivateReason reason) override
Definition: mission_executor.hpp:181
Definition: mission_executor.hpp:142
void checkArmingAndRunConditions(HealthAndArmingCheckReporter &reporter) override
Definition: mission_executor.hpp:153
Mission execution state machine.
Definition: mission_executor.hpp:28
void onActivityInfoChange(const std::function< void(const std::optional< std::string > &)> &callback)
Registers a callback to be invoked when the activity information changes. This callback provides a wa...
Definition: mission_executor.hpp:105
bool deferFailsafes(bool enabled, int timeout_s=0)
void onProgressUpdate(const std::function< void(int)> &callback)
Definition: mission_executor.hpp:90
void setActivityInfo(const std::optional< std::string > &activity_info)
Sets a string with extra information about the current activity. This provides more specific context ...
Mission definition.
Definition: mission.hpp:149
Base class for a mode.
Definition: mode.hpp:73
uint8_t ModeID
Mode ID, corresponds to nav_state.
Definition: mode.hpp:75
Base class for a mode executor.
Definition: mode_executor.hpp:29
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:29
@ Rejected
The request was rejected.
Definition: mission_executor.hpp:30
Definition: mode.hpp:89
Definition: mode_executor.hpp:33
Definition: mission.hpp:114