From d9f6620237f8a5c46319b544105816d48285f574 Mon Sep 17 00:00:00 2001 From: scepter914 Date: Sat, 3 Feb 2024 20:35:06 +0900 Subject: [PATCH] fix(simple_object_merger): delete default param in src Signed-off-by: scepter914 --- .../simple_object_merger_node/simple_object_merger_node.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/perception/simple_object_merger/src/simple_object_merger_node/simple_object_merger_node.cpp b/perception/simple_object_merger/src/simple_object_merger_node/simple_object_merger_node.cpp index 683c6921eef5b..56250af766421 100644 --- a/perception/simple_object_merger/src/simple_object_merger_node/simple_object_merger_node.cpp +++ b/perception/simple_object_merger/src/simple_object_merger_node/simple_object_merger_node.cpp @@ -80,9 +80,9 @@ SimpleObjectMergerNode::SimpleObjectMergerNode(const rclcpp::NodeOptions & node_ std::bind(&SimpleObjectMergerNode::onSetParam, this, std::placeholders::_1)); // Node Parameter - node_param_.update_rate_hz = declare_parameter("update_rate_hz", 20.0); - node_param_.new_frame_id = declare_parameter("new_frame_id", "base_link"); - node_param_.timeout_threshold = declare_parameter("timeout_threshold", 0.1); + node_param_.update_rate_hz = declare_parameter("update_rate_hz"); + node_param_.new_frame_id = declare_parameter("new_frame_id"); + node_param_.timeout_threshold = declare_parameter("timeout_threshold"); declare_parameter("input_topics", std::vector()); node_param_.topic_names = get_parameter("input_topics").as_string_array();