|
21 | 21 | #include "behavior_path_start_planner_module/util.hpp"
|
22 | 22 | #include "motion_utils/trajectory/trajectory.hpp"
|
23 | 23 |
|
| 24 | +#include <lanelet2_extension/utility/message_conversion.hpp> |
24 | 25 | #include <lanelet2_extension/utility/query.hpp>
|
25 | 26 | #include <lanelet2_extension/utility/utilities.hpp>
|
26 | 27 | #include <magic_enum.hpp>
|
@@ -211,7 +212,8 @@ bool StartPlannerModule::receivedNewRoute() const
|
211 | 212 |
|
212 | 213 | bool StartPlannerModule::requiresDynamicObjectsCollisionDetection() const
|
213 | 214 | {
|
214 |
| - return parameters_->safety_check_params.enable_safety_check && status_.driving_forward; |
| 215 | + return parameters_->safety_check_params.enable_safety_check && status_.driving_forward && |
| 216 | + !isOverlapWithCenterLane(); |
215 | 217 | }
|
216 | 218 |
|
217 | 219 | bool StartPlannerModule::noMovingObjectsAround() const
|
@@ -278,6 +280,37 @@ bool StartPlannerModule::isCurrentPoseOnMiddleOfTheRoad() const
|
278 | 280 | return std::abs(lateral_distance_to_center_lane) < parameters_->th_distance_to_middle_of_the_road;
|
279 | 281 | }
|
280 | 282 |
|
| 283 | +bool StartPlannerModule::isOverlapWithCenterLane() const |
| 284 | +{ |
| 285 | + const Pose & current_pose = planner_data_->self_odometry->pose.pose; |
| 286 | + const auto current_lanes = utils::getCurrentLanes(planner_data_); |
| 287 | + const auto local_vehicle_footprint = vehicle_info_.createFootprint(); |
| 288 | + const auto vehicle_footprint = |
| 289 | + transformVector(local_vehicle_footprint, tier4_autoware_utils::pose2transform(current_pose)); |
| 290 | + for (const auto & current_lane : current_lanes) { |
| 291 | + std::vector<geometry_msgs::msg::Point> centerline_points; |
| 292 | + for (const auto & point : current_lane.centerline()) { |
| 293 | + geometry_msgs::msg::Point center_point = lanelet::utils::conversion::toGeomMsgPt(point); |
| 294 | + centerline_points.push_back(center_point); |
| 295 | + } |
| 296 | + |
| 297 | + for (size_t i = 0; i < centerline_points.size() - 1; ++i) { |
| 298 | + const auto & p1 = centerline_points.at(i); |
| 299 | + const auto & p2 = centerline_points.at(i + 1); |
| 300 | + for (size_t j = 0; j < vehicle_footprint.size() - 1; ++j) { |
| 301 | + const auto p3 = tier4_autoware_utils::toMsg(vehicle_footprint[j].to_3d()); |
| 302 | + const auto p4 = tier4_autoware_utils::toMsg(vehicle_footprint[j + 1].to_3d()); |
| 303 | + const auto intersection = tier4_autoware_utils::intersect(p1, p2, p3, p4); |
| 304 | + |
| 305 | + if (intersection.has_value()) { |
| 306 | + return true; |
| 307 | + } |
| 308 | + } |
| 309 | + } |
| 310 | + } |
| 311 | + return false; |
| 312 | +} |
| 313 | + |
281 | 314 | bool StartPlannerModule::isCloseToOriginalStartPose() const
|
282 | 315 | {
|
283 | 316 | const Pose start_pose = planner_data_->route_handler->getOriginalStartPose();
|
@@ -935,8 +968,8 @@ std::vector<Pose> StartPlannerModule::searchPullOutStartPoseCandidates(
|
935 | 968 | pull_out_lanes, start_pose.position, parameters_->th_moving_object_velocity, 0,
|
936 | 969 | std::numeric_limits<double>::max());
|
937 | 970 |
|
938 |
| - // Set the maximum backward distance less than the distance from the vehicle's base_link to the |
939 |
| - // lane's rearmost point to prevent lane departure. |
| 971 | + // Set the maximum backward distance less than the distance from the vehicle's base_link to |
| 972 | + // the lane's rearmost point to prevent lane departure. |
940 | 973 | const double current_arc_length =
|
941 | 974 | lanelet::utils::getArcCoordinates(pull_out_lanes, start_pose).length;
|
942 | 975 | const double allowed_backward_distance = std::clamp(
|
@@ -1224,8 +1257,8 @@ bool StartPlannerModule::isGoalBehindOfEgoInSameRouteSegment() const
|
1224 | 1257 | {
|
1225 | 1258 | const auto & rh = planner_data_->route_handler;
|
1226 | 1259 |
|
1227 |
| - // Check if the goal and ego are in the same route segment. If not, this is out of scope of this |
1228 |
| - // function. Return false. |
| 1260 | + // Check if the goal and ego are in the same route segment. If not, this is out of scope of |
| 1261 | + // this function. Return false. |
1229 | 1262 | lanelet::ConstLanelet ego_lanelet;
|
1230 | 1263 | rh->getClosestLaneletWithinRoute(getEgoPose(), &ego_lanelet);
|
1231 | 1264 | const auto is_ego_in_goal_route_section = rh->isInGoalRouteSection(ego_lanelet);
|
|
0 commit comments