diff --git a/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp index 5b3c0c2f579b3..673e22cac7a67 100644 --- a/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -943,7 +943,7 @@ DecidingPathStatusWithStamp GoalPlannerModule::checkDecidingPathStatus() const // DECIDING for a certain period of time if there is no collision. const auto parking_path = utils::resamplePathWithSpline(pull_over_path->getParkingPath(), 0.5); const double margin = - parameters_->object_recognition_collision_check_margin * 0.9; // hysterisis factor + parameters_->object_recognition_collision_check_margin * 0.9; // hysteresis factor if (checkObjectsCollision(parking_path, margin)) { RCLCPP_DEBUG( getLogger(),