|
34 | 34 | #include <optional>
|
35 | 35 | #include <utility>
|
36 | 36 |
|
| 37 | +namespace |
| 38 | +{ |
| 39 | +geometry_msgs::msg::Point32 create_point32(const geometry_msgs::msg::Pose & pose) |
| 40 | +{ |
| 41 | + geometry_msgs::msg::Point32 p; |
| 42 | + p.x = static_cast<float>(pose.position.x); |
| 43 | + p.y = static_cast<float>(pose.position.y); |
| 44 | + p.z = static_cast<float>(pose.position.z); |
| 45 | + return p; |
| 46 | +}; |
| 47 | + |
| 48 | +geometry_msgs::msg::Polygon create_execution_area( |
| 49 | + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, |
| 50 | + const geometry_msgs::msg::Pose & pose, double additional_lon_offset, double additional_lat_offset) |
| 51 | +{ |
| 52 | + const double & base_to_front = vehicle_info.max_longitudinal_offset_m; |
| 53 | + const double & width = vehicle_info.vehicle_width_m; |
| 54 | + const double & base_to_rear = vehicle_info.rear_overhang_m; |
| 55 | + |
| 56 | + // if stationary object, extend forward and backward by the half of lon length |
| 57 | + const double forward_lon_offset = base_to_front + additional_lon_offset; |
| 58 | + const double backward_lon_offset = -base_to_rear; |
| 59 | + const double lat_offset = width / 2.0 + additional_lat_offset; |
| 60 | + |
| 61 | + const auto p1 = |
| 62 | + autoware::universe_utils::calcOffsetPose(pose, forward_lon_offset, lat_offset, 0.0); |
| 63 | + const auto p2 = |
| 64 | + autoware::universe_utils::calcOffsetPose(pose, forward_lon_offset, -lat_offset, 0.0); |
| 65 | + const auto p3 = |
| 66 | + autoware::universe_utils::calcOffsetPose(pose, backward_lon_offset, -lat_offset, 0.0); |
| 67 | + const auto p4 = |
| 68 | + autoware::universe_utils::calcOffsetPose(pose, backward_lon_offset, lat_offset, 0.0); |
| 69 | + geometry_msgs::msg::Polygon polygon; |
| 70 | + |
| 71 | + polygon.points.push_back(create_point32(p1)); |
| 72 | + polygon.points.push_back(create_point32(p2)); |
| 73 | + polygon.points.push_back(create_point32(p3)); |
| 74 | + polygon.points.push_back(create_point32(p4)); |
| 75 | + |
| 76 | + return polygon; |
| 77 | +} |
| 78 | +} // namespace |
| 79 | + |
37 | 80 | namespace autoware::behavior_path_planner
|
38 | 81 | {
|
39 | 82 | using autoware::behavior_path_planner::Direction;
|
40 | 83 | using autoware::behavior_path_planner::LaneChangeModuleType;
|
41 | 84 | using autoware::behavior_path_planner::ObjectInfo;
|
42 | 85 | using autoware::behavior_path_planner::Point2d;
|
43 |
| -using autoware::behavior_path_planner::utils::lane_change::debug::createExecutionArea; |
44 |
| -namespace utils = autoware::behavior_path_planner::utils; |
45 | 86 |
|
46 | 87 | AvoidanceByLaneChange::AvoidanceByLaneChange(
|
47 | 88 | const std::shared_ptr<LaneChangeParameters> & parameters,
|
@@ -83,9 +124,9 @@ bool AvoidanceByLaneChange::specialRequiredCheck() const
|
83 | 124 |
|
84 | 125 | const auto & nearest_object = data.target_objects.front();
|
85 | 126 | const auto minimum_avoid_length = calcMinAvoidanceLength(nearest_object);
|
86 |
| - const auto minimum_lane_change_length = calcMinimumLaneChangeLength(); |
| 127 | + const auto minimum_lane_change_length = calc_minimum_dist_buffer(); |
87 | 128 |
|
88 |
| - lane_change_debug_.execution_area = createExecutionArea( |
| 129 | + lane_change_debug_.execution_area = create_execution_area( |
89 | 130 | getCommonParam().vehicle_info, getEgoPose(),
|
90 | 131 | std::max(minimum_lane_change_length, minimum_avoid_length), calcLateralOffset());
|
91 | 132 |
|
@@ -274,16 +315,11 @@ double AvoidanceByLaneChange::calcMinAvoidanceLength(const ObjectData & nearest_
|
274 | 315 | return avoidance_helper_->getMinAvoidanceDistance(shift_length);
|
275 | 316 | }
|
276 | 317 |
|
277 |
| -double AvoidanceByLaneChange::calcMinimumLaneChangeLength() const |
| 318 | +double AvoidanceByLaneChange::calc_minimum_dist_buffer() const |
278 | 319 | {
|
279 |
| - const auto current_lanes = get_current_lanes(); |
280 |
| - if (current_lanes.empty()) { |
281 |
| - RCLCPP_DEBUG(logger_, "no empty lanes"); |
282 |
| - return std::numeric_limits<double>::infinity(); |
283 |
| - } |
284 |
| - |
285 |
| - return utils::lane_change::calculation::calc_minimum_lane_change_length( |
286 |
| - getRouteHandler(), current_lanes.back(), *lane_change_parameters_, direction_); |
| 320 | + const auto [_, dist_buffer] = utils::lane_change::calculation::calc_lc_length_and_dist_buffer( |
| 321 | + common_data_ptr_, get_current_lanes()); |
| 322 | + return dist_buffer.min; |
287 | 323 | }
|
288 | 324 |
|
289 | 325 | double AvoidanceByLaneChange::calcLateralOffset() const
|
|
0 commit comments