From cf6b39b2141d5b48755de7a4d8dcd85e446fd86e Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" Date: Thu, 14 Mar 2024 15:35:24 +0900 Subject: [PATCH] rename nodes Signed-off-by: Takagi, Isamu --- .../src/node/aggregator.cpp | 14 +++++++------- .../src/node/aggregator.hpp | 6 +++--- .../src/node/converter.cpp | 10 +++++----- .../src/node/converter.hpp | 4 ++-- 4 files changed, 17 insertions(+), 17 deletions(-) diff --git a/system/diagnostic_graph_aggregator/src/node/aggregator.cpp b/system/diagnostic_graph_aggregator/src/node/aggregator.cpp index 48f489c186bdb..cd16ce8e33e59 100644 --- a/system/diagnostic_graph_aggregator/src/node/aggregator.cpp +++ b/system/diagnostic_graph_aggregator/src/node/aggregator.cpp @@ -20,7 +20,7 @@ namespace diagnostic_graph_aggregator { -MainNode::MainNode() : Node("diagnostic_graph_aggregator_aggregator") +AggregatorNode::AggregatorNode() : Node("aggregator") { // Init diagnostics graph. { @@ -39,7 +39,7 @@ MainNode::MainNode() : Node("diagnostic_graph_aggregator_aggregator") const auto qos_input = rclcpp::QoS(declare_parameter("input_qos_depth")); const auto qos_graph = rclcpp::QoS(declare_parameter("graph_qos_depth")); - const auto callback = std::bind(&MainNode::on_diag, this, _1); + const auto callback = std::bind(&AggregatorNode::on_diag, this, _1); sub_input_ = create_subscription("/diagnostics", qos_input, callback); pub_graph_ = create_publisher("/diagnostics_graph", qos_graph); @@ -51,12 +51,12 @@ MainNode::MainNode() : Node("diagnostic_graph_aggregator_aggregator") debug_ = declare_parameter("use_debug_mode"); } -MainNode::~MainNode() +AggregatorNode::~AggregatorNode() { // for unique_ptr } -void MainNode::on_timer() +void AggregatorNode::on_timer() { const auto stamp = now(); pub_graph_->publish(graph_.report(stamp)); @@ -64,7 +64,7 @@ void MainNode::on_timer() if (modes_) modes_->update(stamp); } -void MainNode::on_diag(const DiagnosticArray::ConstSharedPtr msg) +void AggregatorNode::on_diag(const DiagnosticArray::ConstSharedPtr msg) { graph_.callback(now(), *msg); } @@ -73,10 +73,10 @@ void MainNode::on_diag(const DiagnosticArray::ConstSharedPtr msg) int main(int argc, char ** argv) { - using diagnostic_graph_aggregator::MainNode; + using diagnostic_graph_aggregator::AggregatorNode; rclcpp::init(argc, argv); rclcpp::executors::SingleThreadedExecutor executor; - auto node = std::make_shared(); + auto node = std::make_shared(); executor.add_node(node); executor.spin(); executor.remove_node(node); diff --git a/system/diagnostic_graph_aggregator/src/node/aggregator.hpp b/system/diagnostic_graph_aggregator/src/node/aggregator.hpp index dd64809e939cc..6bf9aead9754d 100644 --- a/system/diagnostic_graph_aggregator/src/node/aggregator.hpp +++ b/system/diagnostic_graph_aggregator/src/node/aggregator.hpp @@ -26,11 +26,11 @@ namespace diagnostic_graph_aggregator { -class MainNode : public rclcpp::Node +class AggregatorNode : public rclcpp::Node { public: - MainNode(); - ~MainNode(); + AggregatorNode(); + ~AggregatorNode(); private: Graph graph_; diff --git a/system/diagnostic_graph_aggregator/src/node/converter.cpp b/system/diagnostic_graph_aggregator/src/node/converter.cpp index 54360fa033985..e93a7c6800201 100644 --- a/system/diagnostic_graph_aggregator/src/node/converter.cpp +++ b/system/diagnostic_graph_aggregator/src/node/converter.cpp @@ -60,19 +60,19 @@ std::vector complement_paths(const DiagnosticGraph & graph) return result; } -ToolNode::ToolNode() : Node("diagnostic_graph_aggregator_converter") +ConverterNode::ConverterNode() : Node("converter") { using std::placeholders::_1; const auto qos_graph = rclcpp::QoS(1); const auto qos_array = rclcpp::QoS(1); - const auto callback = std::bind(&ToolNode::on_graph, this, _1); + const auto callback = std::bind(&ConverterNode::on_graph, this, _1); sub_graph_ = create_subscription("/diagnostics_graph", qos_graph, callback); pub_array_ = create_publisher("/diagnostics_agg", qos_array); complement_inner_nodes_ = declare_parameter("complement_inner_nodes"); } -void ToolNode::on_graph(const DiagnosticGraph::ConstSharedPtr msg) +void ConverterNode::on_graph(const DiagnosticGraph::ConstSharedPtr msg) { DiagnosticArray message; message.header.stamp = msg->stamp; @@ -108,10 +108,10 @@ void ToolNode::on_graph(const DiagnosticGraph::ConstSharedPtr msg) int main(int argc, char ** argv) { - using diagnostic_graph_aggregator::ToolNode; + using diagnostic_graph_aggregator::ConverterNode; rclcpp::init(argc, argv); rclcpp::executors::SingleThreadedExecutor executor; - auto node = std::make_shared(); + auto node = std::make_shared(); executor.add_node(node); executor.spin(); executor.remove_node(node); diff --git a/system/diagnostic_graph_aggregator/src/node/converter.hpp b/system/diagnostic_graph_aggregator/src/node/converter.hpp index 62fbfc518b16e..6a70cbc2df4c6 100644 --- a/system/diagnostic_graph_aggregator/src/node/converter.hpp +++ b/system/diagnostic_graph_aggregator/src/node/converter.hpp @@ -25,10 +25,10 @@ namespace diagnostic_graph_aggregator { -class ToolNode : public rclcpp::Node +class ConverterNode : public rclcpp::Node { public: - ToolNode(); + ConverterNode(); private: bool complement_inner_nodes_;