From 3f8773208a1c2f48becec350f1d697012f40a4c8 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Bar=C4=B1=C5=9F=20Zeren?= Date: Tue, 27 Feb 2024 19:40:02 +0300 Subject: [PATCH] Solve conflicts MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Barış Zeren --- .../component_interface_specs/CMakeLists.txt | 19 ------------------- .../lanelet2_map_loader_node.cpp | 4 ++-- 2 files changed, 2 insertions(+), 21 deletions(-) diff --git a/common/component_interface_specs/CMakeLists.txt b/common/component_interface_specs/CMakeLists.txt index 11ccb63f4a7a8..146f3688513cd 100644 --- a/common/component_interface_specs/CMakeLists.txt +++ b/common/component_interface_specs/CMakeLists.txt @@ -4,25 +4,6 @@ project(component_interface_specs) find_package(autoware_cmake REQUIRED) autoware_package() -include_directories( - include - SYSTEM - ${rclcpp_INCLUDE_DIRS} - ${rosidl_runtime_cpp_INCLUDE_DIRS} - ${rcl_INCLUDE_DIRS} - ${autoware_adapi_v1_msgs_INCLUDE_DIRS} - ${autoware_auto_planning_msgs_INCLUDE_DIRS} - ${autoware_planning_msgs_INCLUDE_DIRS} - ${autoware_auto_vehicle_msgs_INCLUDE_DIRS} - ${tier4_control_msgs_INCLUDE_DIRS} - ${nav_msgs_INCLUDE_DIRS} - ${tier4_system_msgs_INCLUDE_DIRS} - ${tier4_vehicle_msgs_INCLUDE_DIRS} - ${autoware_auto_perception_msgs_INCLUDE_DIRS} - ${tier4_map_msgs_INCLUDE_DIRS} - ${autoware_map_msgs_INCLUDE_DIRS} -) - if(BUILD_TESTING) ament_auto_add_gtest(gtest_${PROJECT_NAME} test/gtest_main.cpp 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 320c46bc34f55..90bdc51f7459e 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 @@ -80,8 +80,8 @@ Lanelet2MapLoaderNode::Lanelet2MapLoaderNode(const rclcpp::NodeOptions & options sub_map_projector_info_, [this](const MapProjectorInfo::Message::ConstSharedPtr msg) { on_map_projector_info(msg); }); - declare_parameter("lanelet2_map_path", ""); - declare_parameter("center_line_resolution"); + declare_parameter("lanelet2_map_path"); + declare_parameter("center_line_resolution"); if (declare_parameter("enabled_dynamic_lanelet_loading")) { std::vector lanelet2_paths_or_directory =