diff --git a/rclcpp/include/rclcpp/create_subscription.hpp b/rclcpp/include/rclcpp/create_subscription.hpp index cbfb0ad763..d2a597a475 100644 --- a/rclcpp/include/rclcpp/create_subscription.hpp +++ b/rclcpp/include/rclcpp/create_subscription.hpp @@ -86,12 +86,12 @@ create_subscription( // TODO(ivanpauno): This could have topics statistics enabled, but I'm not sure if it makes // sense. - std::shared_ptr> publisher = - rclcpp::detail::create_publisher( - node_parameters, - node_topics_interface, - options.topic_stats_options.publish_topic, - qos); + std::shared_ptr> + publisher = rclcpp::detail::create_publisher( + node_parameters, + node_topics_interface, + options.topic_stats_options.publish_topic, + qos); subscription_topic_stats = std::make_shared< rclcpp::topic_statistics::SubscriptionTopicStatistics @@ -131,7 +131,7 @@ create_subscription( return std::dynamic_pointer_cast(sub); } -} // namespace detail +} // namespace detail /// Create and return a subscription of the given MessageT type. /** @@ -184,8 +184,8 @@ create_subscription( { return rclcpp::detail::create_subscription< MessageT, CallbackT, AllocatorT, CallbackMessageT, SubscriptionT, MessageMemoryStrategyT>( - std::forward(node), std::forward(node), topic_name, qos, - std::forward(callback), options, msg_mem_strat); + std::forward(node), std::forward(node), topic_name, qos, + std::forward(callback), options, msg_mem_strat); } /// Create and return a subscription of the given MessageT type. @@ -220,9 +220,9 @@ create_subscription( { return rclcpp::detail::create_subscription< MessageT, CallbackT, AllocatorT, CallbackMessageT, SubscriptionT, MessageMemoryStrategyT>( - std::forward(node_parameters), - std::forward(node_topics), - topic_name, qos, std::forward(callback), options, msg_mem_strat); + std::forward(node_parameters), + std::forward(node_topics), + topic_name, qos, std::forward(callback), options, msg_mem_strat); } } // namespace rclcpp diff --git a/rclcpp/src/rclcpp/node_interfaces/node_base.cpp b/rclcpp/src/rclcpp/node_interfaces/node_base.cpp index 05779331fb..524904d1c9 100644 --- a/rclcpp/src/rclcpp/node_interfaces/node_base.cpp +++ b/rclcpp/src/rclcpp/node_interfaces/node_base.cpp @@ -70,6 +70,7 @@ NodeBase::NodeBase( std::shared_ptr logging_mutex = get_global_logging_mutex(); { std::lock_guard guard(*logging_mutex); + // TODO(ivanpauno): /rosout Qos should be reconfigurable. // TODO(ivanpauno): Instead of mutually excluding rcl_node_init with the global logger mutex, // rcl_logging_rosout_init_publisher_for_node could be decoupled from there and be called // here directly.