|
| 1 | +// Copyright 2024 TIER IV, Inc. |
| 2 | +// |
| 3 | +// Licensed under the Apache License, Version 2.0 (the "License"); |
| 4 | +// you may not use this file except in compliance with the License. |
| 5 | +// You may obtain a copy of the License at |
| 6 | +// |
| 7 | +// http://www.apache.org/licenses/LICENSE-2.0 |
| 8 | +// |
| 9 | +// Unless required by applicable law or agreed to in writing, software |
| 10 | +// distributed under the License is distributed on an "AS IS" BASIS, |
| 11 | +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| 12 | +// See the License for the specific language governing permissions and |
| 13 | +// limitations under the License. |
| 14 | + |
| 15 | +#ifndef AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__PATH_HPP_ |
| 16 | +#define AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__PATH_HPP_ |
| 17 | + |
| 18 | +#include "autoware/behavior_path_lane_change_module/structs/data.hpp" |
| 19 | +#include "autoware/behavior_path_lane_change_module/structs/path.hpp" |
| 20 | + |
| 21 | +#include <autoware/behavior_path_planner_common/utils/utils.hpp> |
| 22 | + |
| 23 | +#include <vector> |
| 24 | + |
| 25 | +namespace autoware::behavior_path_planner::utils::lane_change |
| 26 | +{ |
| 27 | +using behavior_path_planner::LaneChangePath; |
| 28 | +using behavior_path_planner::lane_change::CommonDataPtr; |
| 29 | + |
| 30 | +/** |
| 31 | + * @brief Generates a prepare segment for a lane change maneuver. |
| 32 | + * |
| 33 | + * This function generates the "prepare segment" of the path by trimming it to the specified length, |
| 34 | + * adjusting longitudinal velocity for acceleration or deceleration, and ensuring the starting point |
| 35 | + * meets necessary constraints for a lane change. |
| 36 | + * |
| 37 | + * @param common_data_ptr Shared pointer to CommonData containing current and target lane |
| 38 | + * information, vehicle parameters, and ego state. |
| 39 | + * @param prev_module_path The input path from the previous module, which will be used |
| 40 | + * as the base for the prepare segment. |
| 41 | + * @param prep_metric Preparation metrics containing desired length and velocity for the segment. |
| 42 | + * @param prepare_segment Output parameter where the resulting prepare segment path will be stored. |
| 43 | + * |
| 44 | + * @throws std::logic_error If the lane change start point is behind the target lanelet or |
| 45 | + * if lane information is invalid. |
| 46 | + * |
| 47 | + * @return true if the prepare segment is successfully generated, false otherwise. |
| 48 | + */ |
| 49 | +bool get_prepare_segment( |
| 50 | + const CommonDataPtr & common_data_ptr, const PathWithLaneId & prev_module_path, |
| 51 | + const LaneChangePhaseMetrics prep_metric, PathWithLaneId & prepare_segment); |
| 52 | + |
| 53 | +/** |
| 54 | + * @brief Generates the candidate path for a lane change maneuver. |
| 55 | + * |
| 56 | + * This function calculates the candidate lane change path based on the provided preparation |
| 57 | + * and lane change metrics. It resamples the target lane reference path, determines the start |
| 58 | + * and end poses for the lane change, and constructs the shift line required for the maneuver. |
| 59 | + * The function ensures that the resulting path satisfies length and distance constraints. |
| 60 | + * |
| 61 | + * @param common_data_ptr Shared pointer to CommonData containing route, lane, and transient data. |
| 62 | + * @param prep_metric Metrics for the preparation phase, including path length and velocity. |
| 63 | + * @param lc_metric Metrics for the lane change phase, including path length and velocity. |
| 64 | + * @param prep_segment The path segment prepared before initiating the lane change. |
| 65 | + * @param sorted_lane_ids A vector of sorted lane IDs used for updating lane information in the |
| 66 | + * path. |
| 67 | + * @param lc_start_pose The pose where the lane change begins. |
| 68 | + * @param shift_length The lateral distance to shift during the lane change maneuver. |
| 69 | + * |
| 70 | + * @throws std::logic_error If the target lane reference path is empty, candidate path generation |
| 71 | + * fails, or the resulting path length exceeds terminal constraints. |
| 72 | + * |
| 73 | + * @return LaneChangePath The constructed candidate lane change path. |
| 74 | + */ |
| 75 | +LaneChangePath get_candidate_path( |
| 76 | + const CommonDataPtr & common_data_ptr, const LaneChangePhaseMetrics & prep_metric, |
| 77 | + const LaneChangePhaseMetrics & lc_metric, const PathWithLaneId & prep_segment, |
| 78 | + const std::vector<std::vector<int64_t>> & sorted_lane_ids, const double shift_length); |
| 79 | + |
| 80 | +/** |
| 81 | + * @brief Constructs a candidate path for a lane change maneuver. |
| 82 | + * |
| 83 | + * This function generates a candidate lane change path by shifting the target lane's reference path |
| 84 | + * and combining it with the prepare segment. It verifies the path's validity by checking the yaw |
| 85 | + * difference, adjusting longitudinal velocity, and updating lane IDs based on the provided lane |
| 86 | + * sorting information. |
| 87 | + * |
| 88 | + * @param lane_change_info Information about the lane change, including shift line and target |
| 89 | + * velocity. |
| 90 | + * @param prepare_segment The path segment leading up to the lane change. |
| 91 | + * @param target_lane_reference_path The reference path of the target lane. |
| 92 | + * @param sorted_lane_ids A vector of sorted lane IDs used to update the candidate path's lane IDs. |
| 93 | + * |
| 94 | + * @return std::optional<LaneChangePath> The constructed candidate path if valid, or std::nullopt |
| 95 | + * if the path fails any constraints. |
| 96 | + */ |
| 97 | +LaneChangePath construct_candidate_path( |
| 98 | + const LaneChangeInfo & lane_change_info, const PathWithLaneId & prepare_segment, |
| 99 | + const PathWithLaneId & target_lane_reference_path, |
| 100 | + const std::vector<std::vector<int64_t>> & sorted_lane_ids); |
| 101 | +} // namespace autoware::behavior_path_planner::utils::lane_change |
| 102 | +#endif // AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__PATH_HPP_ |
0 commit comments