Skip to content

Commit

Permalink
Please linters, add more notes
Browse files Browse the repository at this point in the history
Signed-off-by: Ivan Santiago Paunovic <[email protected]>
  • Loading branch information
ivanpauno committed Oct 21, 2020
1 parent 584e9f8 commit 8a9f069
Show file tree
Hide file tree
Showing 2 changed files with 13 additions and 12 deletions.
24 changes: 12 additions & 12 deletions rclcpp/include/rclcpp/create_subscription.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<statistics_msgs::msg::MetricsMessage>> publisher =
rclcpp::detail::create_publisher<statistics_msgs::msg::MetricsMessage>(
node_parameters,
node_topics_interface,
options.topic_stats_options.publish_topic,
qos);
std::shared_ptr<Publisher<statistics_msgs::msg::MetricsMessage>>
publisher = rclcpp::detail::create_publisher<statistics_msgs::msg::MetricsMessage>(
node_parameters,
node_topics_interface,
options.topic_stats_options.publish_topic,
qos);

subscription_topic_stats = std::make_shared<
rclcpp::topic_statistics::SubscriptionTopicStatistics<CallbackMessageT>
Expand Down Expand Up @@ -131,7 +131,7 @@ create_subscription(

return std::dynamic_pointer_cast<SubscriptionT>(sub);
}
} // namespace detail
} // namespace detail

/// Create and return a subscription of the given MessageT type.
/**
Expand Down Expand Up @@ -184,8 +184,8 @@ create_subscription(
{
return rclcpp::detail::create_subscription<
MessageT, CallbackT, AllocatorT, CallbackMessageT, SubscriptionT, MessageMemoryStrategyT>(
std::forward<NodeT>(node), std::forward<NodeT>(node), topic_name, qos,
std::forward<CallbackT>(callback), options, msg_mem_strat);
std::forward<NodeT>(node), std::forward<NodeT>(node), topic_name, qos,
std::forward<CallbackT>(callback), options, msg_mem_strat);
}

/// Create and return a subscription of the given MessageT type.
Expand Down Expand Up @@ -220,9 +220,9 @@ create_subscription(
{
return rclcpp::detail::create_subscription<
MessageT, CallbackT, AllocatorT, CallbackMessageT, SubscriptionT, MessageMemoryStrategyT>(
std::forward<rclcpp::node_interfaces::NodeParametersInterface>(node_parameters),
std::forward<rclcpp::node_interfaces::NodeTopicsInterface>(node_topics),
topic_name, qos, std::forward<CallbackT>(callback), options, msg_mem_strat);
std::forward<rclcpp::node_interfaces::NodeParametersInterface>(node_parameters),
std::forward<rclcpp::node_interfaces::NodeTopicsInterface>(node_topics),
topic_name, qos, std::forward<CallbackT>(callback), options, msg_mem_strat);
}

} // namespace rclcpp
Expand Down
1 change: 1 addition & 0 deletions rclcpp/src/rclcpp/node_interfaces/node_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,6 +70,7 @@ NodeBase::NodeBase(
std::shared_ptr<std::recursive_mutex> logging_mutex = get_global_logging_mutex();
{
std::lock_guard<std::recursive_mutex> 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.
Expand Down

0 comments on commit 8a9f069

Please sign in to comment.