diff --git a/control/trajectory_follower_nodes/CMakeLists.txt b/control/trajectory_follower_nodes/CMakeLists.txt index 6ee21c45d03fc..b40bd8f16a626 100644 --- a/control/trajectory_follower_nodes/CMakeLists.txt +++ b/control/trajectory_follower_nodes/CMakeLists.txt @@ -43,7 +43,8 @@ if(BUILD_TESTING) find_package(autoware_testing REQUIRED) add_smoke_test(${PROJECT_NAME} ${CONTROLLER_NODE}_exe - PARAM_FILENAMES "lateral_controller_defaults.param.yaml longitudinal_controller_defaults.param.yaml test_vehicle_info.param.yaml" + PARAM_FILENAMES "lateral_controller_defaults.param.yaml longitudinal_controller_defaults.param.yaml +test_vehicle_info.param.yaml test_nearest_search.param.yaml" ) endif() diff --git a/control/trajectory_follower_nodes/param/test_nearest_search.param.yaml b/control/trajectory_follower_nodes/param/test_nearest_search.param.yaml new file mode 100644 index 0000000000000..eb6709764ce3e --- /dev/null +++ b/control/trajectory_follower_nodes/param/test_nearest_search.param.yaml @@ -0,0 +1,5 @@ +/**: + ros__parameters: + # ego + ego_nearest_dist_threshold: 3.0 # [m] + ego_nearest_yaw_threshold: 1.046 # [rad] = 60 [deg] diff --git a/control/trajectory_follower_nodes/test/test_controller_node.cpp b/control/trajectory_follower_nodes/test/test_controller_node.cpp index ddc4fb1fe817f..d0a2b96302124 100644 --- a/control/trajectory_follower_nodes/test/test_controller_node.cpp +++ b/control/trajectory_follower_nodes/test/test_controller_node.cpp @@ -55,7 +55,8 @@ std::shared_ptr makeNode() node_options.arguments( {"--ros-args", "--params-file", share_dir + "/param/lateral_controller_defaults.param.yaml", "--params-file", share_dir + "/param/longitudinal_controller_defaults.param.yaml", - "--params-file", share_dir + "/param/test_vehicle_info.param.yaml"}); + "--params-file", share_dir + "/param/test_vehicle_info.param.yaml", "--params-file", + share_dir + "/param/test_nearest_search.param.yaml"}); std::shared_ptr node = std::make_shared(node_options); // Enable all logging in the node diff --git a/control/trajectory_follower_nodes/test/test_lateral_controller_node.cpp b/control/trajectory_follower_nodes/test/test_lateral_controller_node.cpp index 38bca887d8630..0bd94c92cad92 100644 --- a/control/trajectory_follower_nodes/test/test_lateral_controller_node.cpp +++ b/control/trajectory_follower_nodes/test/test_lateral_controller_node.cpp @@ -51,7 +51,8 @@ std::shared_ptr makeLateralNode() rclcpp::NodeOptions node_options; node_options.arguments( {"--ros-args", "--params-file", share_dir + "/param/lateral_controller_defaults.param.yaml", - "--params-file", share_dir + "/param/test_vehicle_info.param.yaml"}); + "--params-file", share_dir + "/param/test_vehicle_info.param.yaml", "--params-file", + share_dir + "/param/test_nearest_search.param.yaml"}); std::shared_ptr node = std::make_shared(node_options); // Enable all logging in the node diff --git a/control/trajectory_follower_nodes/test/test_longitudinal_controller_node.cpp b/control/trajectory_follower_nodes/test/test_longitudinal_controller_node.cpp index 26e00d417276f..676a9a4acfa5c 100644 --- a/control/trajectory_follower_nodes/test/test_longitudinal_controller_node.cpp +++ b/control/trajectory_follower_nodes/test/test_longitudinal_controller_node.cpp @@ -48,7 +48,8 @@ std::shared_ptr makeLongitudinalNode() node_options.arguments( {"--ros-args", "--params-file", share_dir + "/param/longitudinal_controller_defaults.param.yaml", "--params-file", - share_dir + "/param/test_vehicle_info.param.yaml"}); + share_dir + "/param/test_vehicle_info.param.yaml", "--params-file", + share_dir + "/param/test_nearest_search.param.yaml"}); std::shared_ptr node = std::make_shared(node_options);