PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
setpoint_base.hpp
1 /****************************************************************************
2  * Copyright (c) 2023 PX4 Development Team.
3  * SPDX-License-Identifier: BSD-3-Clause
4  ****************************************************************************/
5 
6 #pragma once
7 
8 #include <cstdint>
9 #include <functional>
10 #include <memory>
11 #include <px4_msgs/msg/vehicle_control_mode.hpp>
12 #include <rclcpp/rclcpp.hpp>
13 
14 #include "context.hpp"
15 #include "exception.hpp"
16 
17 namespace px4_ros2 {
18 
19 class SetpointBase : public std::enable_shared_from_this<SetpointBase> {
20  public:
21  using ShouldActivateCB = std::function<void()>;
22 
23  struct Configuration {
24  void fillControlMode(px4_msgs::msg::VehicleControlMode& control_mode)
25  {
26  control_mode.flag_control_rates_enabled = rates_enabled;
27  control_mode.flag_control_attitude_enabled = attitude_enabled;
28  control_mode.flag_control_acceleration_enabled = acceleration_enabled;
29  control_mode.flag_control_velocity_enabled = velocity_enabled;
30  control_mode.flag_control_position_enabled = position_enabled;
31  control_mode.flag_control_altitude_enabled = altitude_enabled;
32  control_mode.flag_control_allocation_enabled = control_allocation_enabled;
33  control_mode.flag_control_climb_rate_enabled = climb_rate_enabled;
34  }
35 
36  bool control_allocation_enabled{true};
37  bool rates_enabled{true};
38  bool attitude_enabled{true};
39  bool altitude_enabled{true};
40  bool acceleration_enabled{true};
41  bool velocity_enabled{true};
42  bool position_enabled{true};
43  bool local_position_is_optional{false};
44  bool climb_rate_enabled{false};
45  };
46 
47  explicit SetpointBase(Context& context) { context.addSetpointType(this); }
48 
49  virtual ~SetpointBase() = default;
50 
51  std::shared_ptr<SetpointBase> getSharedPtr()
52  {
53  try {
54  return shared_from_this();
55  } catch (const std::bad_weak_ptr& exception) {
56  throw Exception("Setpoint must be instantiated with std::make_shared<>");
57  }
58  return {};
59  }
60 
61  virtual Configuration getConfiguration() = 0;
62 
63  virtual float desiredUpdateRateHz() { return 50.f; }
64 
65  void setShouldActivateCallback(const ShouldActivateCB& should_activate_cb)
66  {
67  _should_activate_cb = should_activate_cb;
68  }
69  void setActive(bool active) { _active = active; }
70 
71  protected:
72  void onUpdate()
73  {
74  if (!_active && _should_activate_cb) {
75  _should_activate_cb();
76  }
77  }
78 
79  private:
80  ShouldActivateCB _should_activate_cb;
81  bool _active{false};
82 };
83 
84 } /* namespace px4_ros2 */
Definition: context.hpp:18
Definition: setpoint_base.hpp:19
Definition: setpoint_base.hpp:23