From f414ae56f5499f80aaa2c201f531250fe103e708 Mon Sep 17 00:00:00 2001 From: kosuke55 Date: Fri, 13 Oct 2023 16:41:16 +0900 Subject: [PATCH] fix(lane_change): fix chattering for stopped objects Signed-off-by: kosuke55 Update planning/behavior_path_planner/src/utils/path_safety_checker/safety_check.cpp fix(path_safety_checker): remove redundant parameter name Signed-off-by: Fumiya Watanabe --- .../path_safety_checker_parameters.hpp | 25 ++++---- .../path_safety_checker/safety_check.hpp | 5 +- .../src/marker_utils/utils.cpp | 5 +- .../path_safety_checker/safety_check.cpp | 60 ++++++++++++------- .../test/test_safety_check.cpp | 19 +++--- 5 files changed, 69 insertions(+), 45 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/path_safety_checker_parameters.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/path_safety_checker_parameters.hpp index d4b43ed4c0613..d027640e55bd0 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/path_safety_checker_parameters.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/path_safety_checker_parameters.hpp @@ -179,18 +179,19 @@ struct SafetyCheckParams struct CollisionCheckDebug { - std::string unsafe_reason; ///< Reason indicating unsafe situation. - Twist current_twist{}; ///< Ego vehicle's current velocity and rotation. - Pose expected_ego_pose{}; ///< Predicted future pose of ego vehicle. - Pose current_obj_pose{}; ///< Detected object's current pose. - Twist object_twist{}; ///< Detected object's velocity and rotation. - Pose expected_obj_pose{}; ///< Predicted future pose of object. - double rss_longitudinal{0.0}; ///< Longitudinal RSS measure. - double inter_vehicle_distance{0.0}; ///< Distance between ego vehicle and object. - double extended_polygon_lon_offset{0.0}; ///< Longitudinal offset for extended polygon. - double extended_polygon_lat_offset{0.0}; ///< Lateral offset for extended polygon. - bool is_front{false}; ///< True if object is in front of ego vehicle. - bool is_safe{false}; ///< True if situation is deemed safe. + std::string unsafe_reason; ///< Reason indicating unsafe situation. + Twist current_twist{}; ///< Ego vehicle's current velocity and rotation. + Pose expected_ego_pose{}; ///< Predicted future pose of ego vehicle. + Pose current_obj_pose{}; ///< Detected object's current pose. + Twist object_twist{}; ///< Detected object's velocity and rotation. + Pose expected_obj_pose{}; ///< Predicted future pose of object. + double rss_longitudinal{0.0}; ///< Longitudinal RSS measure. + double inter_vehicle_distance{0.0}; ///< Distance between ego vehicle and object. + double forward_lon_offset{0.0}; ///< Forward longitudinal offset for extended polygon. + double backward_lon_offset{0.0}; ///< Backward longitudinal offset for extended polygon. + double lat_offset{0.0}; ///< Lateral offset for extended polygon. + bool is_front{false}; ///< True if object is in front of ego vehicle. + bool is_safe{false}; ///< True if situation is deemed safe. std::vector ego_predicted_path; ///< ego vehicle's predicted path. std::vector obj_predicted_path; ///< object's predicted path. Polygon2d extended_ego_polygon{}; ///< Ego vehicle's extended collision polygon. diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/safety_check.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/safety_check.hpp index c9cedca39aca0..8d8abccbd5413 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/safety_check.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/path_safety_checker/safety_check.hpp @@ -61,10 +61,11 @@ bool isTargetObjectFront( Polygon2d createExtendedPolygon( const Pose & base_link_pose, const vehicle_info_util::VehicleInfo & vehicle_info, - const double lon_length, const double lat_margin, CollisionCheckDebug & debug); + const double lon_length, const double lat_margin, const double is_stopped_obj, + CollisionCheckDebug & debug); Polygon2d createExtendedPolygon( const Pose & obj_pose, const Shape & shape, const double lon_length, const double lat_margin, - CollisionCheckDebug & debug); + const double is_stopped_obj, CollisionCheckDebug & debug); PredictedPath convertToPredictedPath( const std::vector & path, const double time_resolution); diff --git a/planning/behavior_path_planner/src/marker_utils/utils.cpp b/planning/behavior_path_planner/src/marker_utils/utils.cpp index 7dc85de879a18..06c0111786ef9 100644 --- a/planning/behavior_path_planner/src/marker_utils/utils.cpp +++ b/planning/behavior_path_planner/src/marker_utils/utils.cpp @@ -636,8 +636,9 @@ MarkerArray showSafetyCheckInfo(const CollisionCheckDebugMap & obj_debug_vec, st << "\nRSS dist: " << std::setprecision(4) << info.rss_longitudinal << "\nEgo to obj: " << info.inter_vehicle_distance << "\nExtended polygon: " << (info.is_front ? "ego" : "object") - << "\nExtended polygon lateral offset: " << info.extended_polygon_lat_offset - << "\nExtended polygon longitudinal offset: " << info.extended_polygon_lon_offset + << "\nExtended polygon lateral offset: " << info.lat_offset + << "\nExtended polygon forward longitudinal offset: " << info.forward_lon_offset + << "\nExtended polygon backward longitudinal offset: " << info.backward_lon_offset << "\nLast checked position: " << (info.is_front ? "obj in front ego" : "obj at back ego") << "\nSafe: " << (info.is_safe ? "Yes" : "No"); diff --git a/planning/behavior_path_planner/src/utils/path_safety_checker/safety_check.cpp b/planning/behavior_path_planner/src/utils/path_safety_checker/safety_check.cpp index 6ea21faef2e2f..778d999b011b0 100644 --- a/planning/behavior_path_planner/src/utils/path_safety_checker/safety_check.cpp +++ b/planning/behavior_path_planner/src/utils/path_safety_checker/safety_check.cpp @@ -70,28 +70,33 @@ bool isTargetObjectFront( Polygon2d createExtendedPolygon( const Pose & base_link_pose, const vehicle_info_util::VehicleInfo & vehicle_info, - const double lon_length, const double lat_margin, CollisionCheckDebug & debug) + const double lon_length, const double lat_margin, const double is_stopped_obj, + CollisionCheckDebug & debug) { const double & base_to_front = vehicle_info.max_longitudinal_offset_m; const double & width = vehicle_info.vehicle_width_m; const double & base_to_rear = vehicle_info.rear_overhang_m; - const double lon_offset = std::max(lon_length + base_to_front, base_to_front); - + // if stationary object, extend forward and backward by the half of lon length + const double forward_lon_offset = base_to_front + (is_stopped_obj ? lon_length / 2 : lon_length); + const double backward_lon_offset = + -base_to_rear - (is_stopped_obj ? lon_length / 2 : 0); // minus value const double lat_offset = width / 2.0 + lat_margin; { - debug.extended_polygon_lon_offset = lon_offset; - debug.extended_polygon_lat_offset = lat_offset; + debug.forward_lon_offset = forward_lon_offset; + debug.backward_lon_offset = backward_lon_offset; + debug.lat_offset = lat_offset; } - const auto p1 = tier4_autoware_utils::calcOffsetPose(base_link_pose, lon_offset, lat_offset, 0.0); + const auto p1 = + tier4_autoware_utils::calcOffsetPose(base_link_pose, forward_lon_offset, lat_offset, 0.0); const auto p2 = - tier4_autoware_utils::calcOffsetPose(base_link_pose, lon_offset, -lat_offset, 0.0); + tier4_autoware_utils::calcOffsetPose(base_link_pose, forward_lon_offset, -lat_offset, 0.0); const auto p3 = - tier4_autoware_utils::calcOffsetPose(base_link_pose, -base_to_rear, -lat_offset, 0.0); + tier4_autoware_utils::calcOffsetPose(base_link_pose, backward_lon_offset, -lat_offset, 0.0); const auto p4 = - tier4_autoware_utils::calcOffsetPose(base_link_pose, -base_to_rear, lat_offset, 0.0); + tier4_autoware_utils::calcOffsetPose(base_link_pose, backward_lon_offset, lat_offset, 0.0); Polygon2d polygon; appendPointToPolygon(polygon, p1.position); @@ -106,7 +111,7 @@ Polygon2d createExtendedPolygon( Polygon2d createExtendedPolygon( const Pose & obj_pose, const Shape & shape, const double lon_length, const double lat_margin, - CollisionCheckDebug & debug) + const double is_stopped_obj, CollisionCheckDebug & debug) { const auto obj_polygon = tier4_autoware_utils::toPolygon2d(obj_pose, shape); if (obj_polygon.outer().empty()) { @@ -127,19 +132,27 @@ Polygon2d createExtendedPolygon( min_y = std::min(transformed_p.y, min_y); } - const double lon_offset = max_x + lon_length; + // if stationary object, extend forward and backward by the half of lon length + const double forward_lon_offset = max_x + (is_stopped_obj ? lon_length / 2 : lon_length); + const double backward_lon_offset = min_x - (is_stopped_obj ? lon_length / 2 : 0); // minus value + const double left_lat_offset = max_y + lat_margin; const double right_lat_offset = min_y - lat_margin; { - debug.extended_polygon_lon_offset = lon_offset; - debug.extended_polygon_lat_offset = (left_lat_offset + right_lat_offset) / 2; + debug.forward_lon_offset = forward_lon_offset; + debug.backward_lon_offset = backward_lon_offset; + debug.lat_offset = (left_lat_offset + right_lat_offset) / 2; } - const auto p1 = tier4_autoware_utils::calcOffsetPose(obj_pose, lon_offset, left_lat_offset, 0.0); - const auto p2 = tier4_autoware_utils::calcOffsetPose(obj_pose, lon_offset, right_lat_offset, 0.0); - const auto p3 = tier4_autoware_utils::calcOffsetPose(obj_pose, min_x, right_lat_offset, 0.0); - const auto p4 = tier4_autoware_utils::calcOffsetPose(obj_pose, min_x, left_lat_offset, 0.0); + const auto p1 = + tier4_autoware_utils::calcOffsetPose(obj_pose, forward_lon_offset, left_lat_offset, 0.0); + const auto p2 = + tier4_autoware_utils::calcOffsetPose(obj_pose, forward_lon_offset, right_lat_offset, 0.0); + const auto p3 = + tier4_autoware_utils::calcOffsetPose(obj_pose, backward_lon_offset, right_lat_offset, 0.0); + const auto p4 = + tier4_autoware_utils::calcOffsetPose(obj_pose, backward_lon_offset, left_lat_offset, 0.0); Polygon2d polygon; appendPointToPolygon(polygon, p1.position); @@ -326,14 +339,17 @@ std::vector getCollidedPolygons( const auto & lon_offset = std::max(rss_dist, min_lon_length) * hysteresis_factor; const auto & lat_margin = rss_parameters.lateral_distance_max_threshold * hysteresis_factor; - const auto & extended_ego_polygon = - is_object_front - ? createExtendedPolygon(ego_pose, ego_vehicle_info, lon_offset, lat_margin, debug) - : ego_polygon; + // TODO(watanabe) fix hard coding value + const bool is_stopped_object = object_velocity < 0.3; + const auto & extended_ego_polygon = is_object_front ? createExtendedPolygon( + ego_pose, ego_vehicle_info, lon_offset, + lat_margin, is_stopped_object, debug) + : ego_polygon; const auto & extended_obj_polygon = is_object_front ? obj_polygon - : createExtendedPolygon(obj_pose, target_object.shape, lon_offset, lat_margin, debug); + : createExtendedPolygon( + obj_pose, target_object.shape, lon_offset, lat_margin, is_stopped_object, debug); { debug.rss_longitudinal = rss_dist; diff --git a/planning/behavior_path_planner/test/test_safety_check.cpp b/planning/behavior_path_planner/test/test_safety_check.cpp index 9dfcef487cc81..d60957c7d41b4 100644 --- a/planning/behavior_path_planner/test/test_safety_check.cpp +++ b/planning/behavior_path_planner/test/test_safety_check.cpp @@ -51,9 +51,10 @@ TEST(BehaviorPathPlanningSafetyUtilsTest, createExtendedEgoPolygon) const double lon_length = 10.0; const double lat_margin = 2.0; + const bool is_stopped_object = false; - const auto polygon = - createExtendedPolygon(ego_pose, vehicle_info, lon_length, lat_margin, debug); + const auto polygon = createExtendedPolygon( + ego_pose, vehicle_info, lon_length, lat_margin, is_stopped_object, debug); EXPECT_EQ(polygon.outer().size(), static_cast(5)); @@ -78,9 +79,10 @@ TEST(BehaviorPathPlanningSafetyUtilsTest, createExtendedEgoPolygon) const double lon_length = 10.0; const double lat_margin = 2.0; + const bool is_stopped_object = false; - const auto polygon = - createExtendedPolygon(ego_pose, vehicle_info, lon_length, lat_margin, debug); + const auto polygon = createExtendedPolygon( + ego_pose, vehicle_info, lon_length, lat_margin, is_stopped_object, debug); EXPECT_EQ(polygon.outer().size(), static_cast(5)); @@ -106,9 +108,10 @@ TEST(BehaviorPathPlanningSafetyUtilsTest, createExtendedEgoPolygon) const double lon_length = 10.0; const double lat_margin = 2.0; + const bool is_stopped_object = false; - const auto polygon = - createExtendedPolygon(ego_pose, vehicle_info, lon_length, lat_margin, debug); + const auto polygon = createExtendedPolygon( + ego_pose, vehicle_info, lon_length, lat_margin, is_stopped_object, debug); EXPECT_EQ(polygon.outer().size(), static_cast(5)); @@ -154,9 +157,11 @@ TEST(BehaviorPathPlanningSafetyUtilsTest, createExtendedObjPolygon) const double lon_length = 10.0; const double lat_margin = 2.0; + const bool is_stopped_object = false; CollisionCheckDebug debug; - const auto polygon = createExtendedPolygon(obj_pose, shape, lon_length, lat_margin, debug); + const auto polygon = + createExtendedPolygon(obj_pose, shape, lon_length, lat_margin, is_stopped_object, debug); EXPECT_EQ(polygon.outer().size(), static_cast(5));