From 6b55253b86bdb943f5d9ee865919d679c05503aa Mon Sep 17 00:00:00 2001 From: yamazakiTasuku <100691117+yamazakiTasuku@users.noreply.github.com> Date: Mon, 10 Apr 2023 17:01:52 +0900 Subject: [PATCH] refactor(mission_planner): delete default values (#3127) * delete param Signed-off-by: yamazakiTasuku * fix(mission_planner): add type Signed-off-by: satoshi-ota * fix(static_centerline_optimizer): add mission planner param path Signed-off-by: satoshi-ota * fix Co-authored-by: Kosuke Takeuchi --------- Signed-off-by: yamazakiTasuku Signed-off-by: satoshi-ota Co-authored-by: yamazakiTasuku Co-authored-by: satoshi-ota Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Co-authored-by: Kosuke Takeuchi --- .../mission_planner/src/lanelet2_plugins/default_planner.cpp | 4 ++-- .../test/test_static_centerline_optimizer.test.py | 5 +++++ 2 files changed, 7 insertions(+), 2 deletions(-) diff --git a/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp b/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp index dbd561ba2c67..6ea5490077a9 100644 --- a/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp +++ b/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp @@ -145,8 +145,8 @@ void DefaultPlanner::initialize_common(rclcpp::Node * node) node_->create_publisher("debug/goal_footprint", durable_qos); vehicle_info_ = vehicle_info_util::VehicleInfoUtil(*node_).getVehicleInfo(); - param_.goal_angle_threshold_deg = node_->declare_parameter("goal_angle_threshold_deg", 45.0); - param_.enable_correct_goal_pose = node_->declare_parameter("enable_correct_goal_pose", false); + param_.goal_angle_threshold_deg = node_->declare_parameter("goal_angle_threshold_deg"); + param_.enable_correct_goal_pose = node_->declare_parameter("enable_correct_goal_pose"); } void DefaultPlanner::initialize(rclcpp::Node * node) diff --git a/planning/static_centerline_optimizer/test/test_static_centerline_optimizer.test.py b/planning/static_centerline_optimizer/test/test_static_centerline_optimizer.test.py index e4bcdeab1232..549ddbd7e524 100644 --- a/planning/static_centerline_optimizer/test/test_static_centerline_optimizer.test.py +++ b/planning/static_centerline_optimizer/test/test_static_centerline_optimizer.test.py @@ -43,6 +43,11 @@ def generate_test_description(): {"lanelet2_output_file_path": "/tmp/lanelet2_map.osm"}, {"start_lanelet_id": 215}, {"end_lanelet_id": 216}, + os.path.join( + get_package_share_directory("mission_planner"), + "config", + "mission_planner.param.yaml", + ), os.path.join( get_package_share_directory("static_centerline_optimizer"), "config/static_centerline_optimizer.param.yaml",