From aebbcc5bfd142a82aee87f43ea3fb250fd54ca59 Mon Sep 17 00:00:00 2001 From: beyzanurkaya <32412808+beyzanurkaya@users.noreply.github.com> Date: Wed, 3 Jul 2024 19:53:34 +0300 Subject: [PATCH] fix(tier4_planning_rviz_plugin): fix calculation of drivable area bounds (#7815) change angle condition Signed-off-by: beyza --- .../include/tier4_planning_rviz_plugin/path/display.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display.hpp b/common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display.hpp index ef5663f024c8d..dc0cb0eb5188a 100644 --- a/common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display.hpp +++ b/common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display.hpp @@ -77,7 +77,7 @@ void visualizeBound( const float diff_angle = autoware::universe_utils::normalizeRadian(normal_vector_angle - curr_to_next_angle); - if (diff_angle == 0.0) { + if (diff_angle <= 1e-7 && diff_angle >= -1e-7) { return std::make_pair(normal_vector_angle, width); }