8 #include <px4_ros2/components/mode.hpp>
9 #include <px4_ros2/components/wait_for_fmu.hpp>
10 #include <rclcpp/rclcpp.hpp>
32 template <
typename ModeT>
34 static_assert(std::is_base_of_v<ModeBase, ModeT>,
35 "Template type ModeT must be derived from px4_ros2::ModeBase");
38 explicit NodeWithMode(
const std::string& node_name,
bool enable_debug_output =
false)
41 if (enable_debug_output) {
43 rcutils_logging_set_logger_level(get_logger().get_name(), RCUTILS_LOG_SEVERITY_DEBUG);
45 if (ret != RCUTILS_RET_OK) {
46 RCLCPP_ERROR(get_logger(),
"Error setting severity: %s", rcutils_get_error_string().str);
47 rcutils_reset_error();
51 _mode = std::make_unique<ModeT>(*
this);
53 if (!_mode->doRegister()) {
58 ModeT& getMode()
const {
return *_mode; }
61 std::unique_ptr<ModeT> _mode;
88 template <
typename ModeExecutorT,
typename OwnedModeT,
typename... OtherModesT>
90 static_assert(std::is_base_of_v<ModeExecutorBase, ModeExecutorT>,
91 "Template type ModeExecutorT must be derived from px4_ros2::ModeExecutorBase");
93 (std::is_base_of_v<ModeBase, OwnedModeT> && ... && std::is_base_of_v<ModeBase, OtherModesT>),
94 "Template types OwnedModeT and OtherModesT must be derived from px4_ros2::ModeBase");
100 if (enable_debug_output) {
102 rcutils_logging_set_logger_level(get_logger().get_name(), RCUTILS_LOG_SEVERITY_DEBUG);
104 if (ret != RCUTILS_RET_OK) {
105 RCLCPP_ERROR(get_logger(),
"Error setting severity: %s", rcutils_get_error_string().str);
106 rcutils_reset_error();
110 _owned_mode = std::make_unique<OwnedModeT>(*
this);
111 _other_modes = std::make_tuple(std::make_unique<OtherModesT>(*this)...);
112 _mode_executor = createModeExecutor(std::index_sequence_for<OtherModesT...>{});
114 if (!_mode_executor->doRegister() || !std::apply(
115 [](
const auto&... mode) {
117 return (mode->doRegister() && ...);
125 template <
typename ModeT = OwnedModeT>
126 ModeT& getMode()
const
128 if constexpr (std::is_same_v<ModeT, OwnedModeT>) {
131 return *std::get<ModeT>(_other_modes);
136 template <std::size_t... Idx>
137 auto createModeExecutor(std::index_sequence<Idx...>)
139 if constexpr (
sizeof...(Idx) == 0) {
140 return std::make_unique<ModeExecutorT>(*_owned_mode);
142 return std::make_unique<ModeExecutorT>(*_owned_mode, *std::get<Idx>(_other_modes)...);
146 std::unique_ptr<ModeExecutorT> _mode_executor;
147 std::unique_ptr<OwnedModeT> _owned_mode;
148 std::tuple<std::unique_ptr<OtherModesT>...> _other_modes;
Definition: exception.hpp:14
A ROS2 node which instantiates a mode executor and its owned mode, and handles their registration wit...
Definition: node_with_mode.hpp:89
A ROS2 node which instantiates a control mode and handles its registration with PX4.
Definition: node_with_mode.hpp:33