From 123cc3a3fdf34c2d34084d3a9a59fe3279e28a5d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Tue, 17 Dec 2024 23:30:05 +0300 Subject: [PATCH] rename resolusion to resolution MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .../config/behavior_analyzer.param.yaml | 2 +- .../src/data_structs.hpp | 2 +- .../autoware_planning_data_analyzer/src/node.cpp | 12 ++++++------ 3 files changed, 8 insertions(+), 8 deletions(-) diff --git a/planning/autoware_planning_data_analyzer/config/behavior_analyzer.param.yaml b/planning/autoware_planning_data_analyzer/config/behavior_analyzer.param.yaml index dbd9e91ca..7dc0f4000 100644 --- a/planning/autoware_planning_data_analyzer/config/behavior_analyzer.param.yaml +++ b/planning/autoware_planning_data_analyzer/config/behavior_analyzer.param.yaml @@ -20,6 +20,6 @@ grid_seach: min: 0.1 max: 1.0 - resolusion: 0.2 + resolution: 0.2 dt: 1.0 thread_num: 8 diff --git a/planning/autoware_planning_data_analyzer/src/data_structs.hpp b/planning/autoware_planning_data_analyzer/src/data_structs.hpp index 53ff2b025..f8dc40f61 100644 --- a/planning/autoware_planning_data_analyzer/src/data_structs.hpp +++ b/planning/autoware_planning_data_analyzer/src/data_structs.hpp @@ -78,7 +78,7 @@ struct GridSearchParameters { double min{0.0}; double max{1.0}; - double resolusion{0.01}; + double resolution{0.01}; double dt{1.0}; size_t thread_num{4}; }; diff --git a/planning/autoware_planning_data_analyzer/src/node.cpp b/planning/autoware_planning_data_analyzer/src/node.cpp index 2859714b6..6a89ac5ce 100644 --- a/planning/autoware_planning_data_analyzer/src/node.cpp +++ b/planning/autoware_planning_data_analyzer/src/node.cpp @@ -86,7 +86,7 @@ BehaviorAnalyzerNode::BehaviorAnalyzerNode(const rclcpp::NodeOptions & node_opti parameters_->grid_seach.dt = declare_parameter("grid_seach.dt"); parameters_->grid_seach.min = declare_parameter("grid_seach.min"); parameters_->grid_seach.max = declare_parameter("grid_seach.max"); - parameters_->grid_seach.resolusion = declare_parameter("grid_seach.resolusion"); + parameters_->grid_seach.resolution = declare_parameter("grid_seach.resolution"); parameters_->grid_seach.thread_num = declare_parameter("grid_seach.thread_num"); parameters_->target_state.lat_positions = declare_parameter>("target_state.lateral_positions"); @@ -215,13 +215,13 @@ void BehaviorAnalyzerNode::weight( std::vector weight_grid; - double resolusion = p->grid_seach.resolusion; + double resolution = p->grid_seach.resolution; double min = p->grid_seach.min; double max = p->grid_seach.max; - for (double w0 = min; w0 < max + 0.1 * resolusion; w0 += resolusion) { - for (double w1 = min; w1 < max + 0.1 * resolusion; w1 += resolusion) { - for (double w2 = min; w2 < max + 0.1 * resolusion; w2 += resolusion) { - for (double w3 = min; w3 < max + 0.1 * resolusion; w3 += resolusion) { + for (double w0 = min; w0 < max + 0.1 * resolution; w0 += resolution) { + for (double w1 = min; w1 < max + 0.1 * resolution; w1 += resolution) { + for (double w2 = min; w2 < max + 0.1 * resolution; w2 += resolution) { + for (double w3 = min; w3 < max + 0.1 * resolution; w3 += resolution) { weight_grid.emplace_back(w0, w1, w2, w3); } }