From ea6ac19ae08aeec235163e561ad73676a9d8886d Mon Sep 17 00:00:00 2001 From: kosuke55 Date: Fri, 6 Dec 2024 17:01:47 +0900 Subject: [PATCH] fix typo Signed-off-by: kosuke55 --- .../src/goal_planner_module.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp index 4d95d65f59524..716047c7ad1f1 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -245,7 +245,7 @@ bool checkOccupancyGridCollision( bool isStopped( std::deque & odometry_buffer, const nav_msgs::msg::Odometry::ConstSharedPtr self_odometry, const double duration_lower, - const double velocity_uppper) + const double velocity_upper) { odometry_buffer.push_back(self_odometry); // Delete old data in buffer_stuck_ @@ -260,7 +260,7 @@ bool isStopped( bool is_stopped = true; for (const auto & odometry : odometry_buffer) { const double ego_vel = utils::l2Norm(odometry->twist.twist.linear); - if (ego_vel > velocity_uppper) { + if (ego_vel > velocity_upper) { is_stopped = false; break; }