diff --git a/planning/autoware_behavior_path_lane_change_module/include/autoware_behavior_path_lane_change_module/utils/data_structs.hpp b/planning/autoware_behavior_path_lane_change_module/include/autoware_behavior_path_lane_change_module/utils/data_structs.hpp index 71e04e7fef457..e88029420e296 100644 --- a/planning/autoware_behavior_path_lane_change_module/include/autoware_behavior_path_lane_change_module/utils/data_structs.hpp +++ b/planning/autoware_behavior_path_lane_change_module/include/autoware_behavior_path_lane_change_module/utils/data_structs.hpp @@ -25,37 +25,6 @@ #include #include -namespace autoware::behavior_path_planner::lane_change -{ -struct CancelParameters -{ - bool enable_on_prepare_phase{true}; - bool enable_on_lane_changing_phase{false}; - double delta_time{1.0}; - double duration{5.0}; - double max_lateral_jerk{10.0}; - double overhang_tolerance{0.0}; - - // unsafe_hysteresis_threshold will be compare with the number of detected unsafe instance. If the - // number of unsafe exceeds unsafe_hysteresis_threshold, the lane change will be cancelled or - // aborted. - int unsafe_hysteresis_threshold{2}; -}; - -struct PathSafetyStatus -{ - bool is_safe{true}; - bool is_object_coming_from_rear{false}; -}; - -struct LanesPolygon -{ - std::optional current; - std::optional target; - std::vector target_backward; -}; - -} // namespace autoware::behavior_path_planner::lane_change namespace autoware::behavior_path_planner { struct LateralAccelerationMap @@ -99,6 +68,21 @@ struct LateralAccelerationMap } }; +struct LaneChangeCancelParameters +{ + bool enable_on_prepare_phase{true}; + bool enable_on_lane_changing_phase{false}; + double delta_time{1.0}; + double duration{5.0}; + double max_lateral_jerk{10.0}; + double overhang_tolerance{0.0}; + + // unsafe_hysteresis_threshold will be compare with the number of detected unsafe instance. If the + // number of unsafe exceeds unsafe_hysteresis_threshold, the lane change will be cancelled or + // aborted. + int unsafe_hysteresis_threshold{2}; +}; + struct LaneChangeParameters { // trajectory generation @@ -158,7 +142,7 @@ struct LaneChangeParameters utils::path_safety_checker::RSSparams rss_params_for_stuck{}; // abort - lane_change::CancelParameters cancel{}; + LaneChangeCancelParameters cancel{}; double finish_judge_lateral_threshold{0.2}; @@ -219,4 +203,20 @@ enum class LaneChangeModuleType { }; } // namespace autoware::behavior_path_planner +namespace autoware::behavior_path_planner::lane_change +{ +struct PathSafetyStatus +{ + bool is_safe{true}; + bool is_object_coming_from_rear{false}; +}; + +struct LanesPolygon +{ + std::optional current; + std::optional target; + std::vector target_backward; +}; +} // namespace autoware::behavior_path_planner::lane_change + #endif // AUTOWARE_BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__DATA_STRUCTS_HPP_