From 39d542623e31b303205a856d13f35e72f2da2038 Mon Sep 17 00:00:00 2001 From: Shintaro Sakoda Date: Wed, 16 Aug 2023 11:59:58 +0900 Subject: [PATCH] Change parameter declaration timing Signed-off-by: Shintaro Sakoda --- .../src/lanelet2_map_loader/lanelet2_map_loader_node.cpp | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp b/map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp index 42c46e2b5e96c..cac9857af92aa 100644 --- a/map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp +++ b/map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp @@ -55,12 +55,15 @@ Lanelet2MapLoaderNode::Lanelet2MapLoaderNode(const rclcpp::NodeOptions & options sub_map_projector_type_ = create_subscription( "input/map_projector_info", rclcpp::QoS{1}.transient_local(), [this](const MapProjectorInfo::ConstSharedPtr msg) { on_map_projector_info(msg); }); + + declare_parameter("lanelet2_map_path", ""); + declare_parameter("center_line_resolution", 5.0); } void Lanelet2MapLoaderNode::on_map_projector_info(const MapProjectorInfo::ConstSharedPtr msg) { - const auto lanelet2_filename = declare_parameter("lanelet2_map_path", ""); - const auto center_line_resolution = declare_parameter("center_line_resolution", 5.0); + const auto lanelet2_filename = get_parameter("lanelet2_map_path").as_string(); + const auto center_line_resolution = get_parameter("center_line_resolution").as_double(); // load map from file const auto map =