21
21
#include " behavior_path_planner_common/utils/traffic_light_utils.hpp"
22
22
#include " tier4_autoware_utils/geometry/boost_polygon_utils.hpp"
23
23
24
+ #include < lanelet2_extension/utility/message_conversion.hpp>
24
25
#include < tier4_autoware_utils/geometry/geometry.hpp>
25
26
#include < tier4_autoware_utils/ros/uuid_helper.hpp>
26
27
@@ -476,11 +477,11 @@ bool isObjectOnRoadShoulder(
476
477
ObjectData & object, const std::shared_ptr<RouteHandler> & route_handler,
477
478
const std::shared_ptr<AvoidanceParameters> & parameters)
478
479
{
479
- using boost::geometry::return_centroid;
480
480
using boost::geometry::within;
481
481
using lanelet::geometry::distance2d;
482
482
using lanelet::geometry::toArcCoordinates;
483
483
using lanelet::utils::to2D;
484
+ using lanelet::utils::conversion::toLaneletPoint;
484
485
485
486
// assume that there are no parked vehicles in intersection.
486
487
std::string turn_direction = object.overhang_lanelet .attributeOr (" turn_direction" , " else" );
@@ -498,13 +499,9 @@ bool isObjectOnRoadShoulder(
498
499
// +: object position
499
500
// o: nearest point on centerline
500
501
501
- lanelet::BasicPoint2d object_centroid (object.centroid .x (), object.centroid .y ());
502
-
503
502
const auto & object_pose = object.object .kinematics .initial_pose_with_covariance .pose ;
504
- const auto centerline_pose =
505
- lanelet::utils::getClosestCenterPose (object.overhang_lanelet , object_pose.position );
506
- lanelet::BasicPoint3d centerline_point (
507
- centerline_pose.position .x , centerline_pose.position .y , centerline_pose.position .z );
503
+ const auto centerline_pos =
504
+ lanelet::utils::getClosestCenterPose (object.overhang_lanelet , object_pose.position ).position ;
508
505
509
506
bool is_left_side_parked_vehicle = false ;
510
507
if (!isOnRight (object)) {
@@ -526,8 +523,9 @@ bool isObjectOnRoadShoulder(
526
523
}
527
524
}
528
525
529
- const auto center_to_left_boundary =
530
- distance2d (to2D (most_left_lanelet.leftBound ().basicLineString ()), to2D (centerline_point));
526
+ const auto center_to_left_boundary = distance2d (
527
+ to2D (most_left_lanelet.leftBound ().basicLineString ()),
528
+ to2D (toLaneletPoint (centerline_pos)).basicPoint ());
531
529
532
530
return std::make_pair (
533
531
center_to_left_boundary - 0.5 * object.object .shape .dimensions .y , sub_type);
@@ -538,7 +536,8 @@ bool isObjectOnRoadShoulder(
538
536
}
539
537
540
538
const auto arc_coordinates = toArcCoordinates (
541
- to2D (object.overhang_lanelet .centerline ().basicLineString ()), object_centroid);
539
+ to2D (object.overhang_lanelet .centerline ().basicLineString ()),
540
+ to2D (toLaneletPoint (object_pose.position )).basicPoint ());
542
541
object.shiftable_ratio = arc_coordinates.distance / object_shiftable_distance;
543
542
544
543
is_left_side_parked_vehicle = object.shiftable_ratio > parameters->object_check_shiftable_ratio ;
@@ -564,8 +563,9 @@ bool isObjectOnRoadShoulder(
564
563
}
565
564
}
566
565
567
- const auto center_to_right_boundary =
568
- distance2d (to2D (most_right_lanelet.rightBound ().basicLineString ()), to2D (centerline_point));
566
+ const auto center_to_right_boundary = distance2d (
567
+ to2D (most_right_lanelet.rightBound ().basicLineString ()),
568
+ to2D (toLaneletPoint (centerline_pos)).basicPoint ());
569
569
570
570
return std::make_pair (
571
571
center_to_right_boundary - 0.5 * object.object .shape .dimensions .y , sub_type);
@@ -576,7 +576,8 @@ bool isObjectOnRoadShoulder(
576
576
}
577
577
578
578
const auto arc_coordinates = toArcCoordinates (
579
- to2D (object.overhang_lanelet .centerline ().basicLineString ()), object_centroid);
579
+ to2D (object.overhang_lanelet .centerline ().basicLineString ()),
580
+ to2D (toLaneletPoint (object_pose.position )).basicPoint ());
580
581
object.shiftable_ratio = -1.0 * arc_coordinates.distance / object_shiftable_distance;
581
582
582
583
is_right_side_parked_vehicle =
@@ -754,6 +755,8 @@ bool isSatisfiedWithVehicleCondition(
754
755
const std::shared_ptr<AvoidanceParameters> & parameters)
755
756
{
756
757
using boost::geometry::within;
758
+ using lanelet::utils::to2D;
759
+ using lanelet::utils::conversion::toLaneletPoint;
757
760
758
761
object.behavior = getObjectBehavior (object, parameters);
759
762
object.is_within_intersection = isWithinIntersection (object, planner_data->route_handler );
@@ -764,9 +767,10 @@ bool isSatisfiedWithVehicleCondition(
764
767
}
765
768
766
769
// check vehicle shift ratio
767
- lanelet::BasicPoint2d object_centroid (object.centroid .x (), object.centroid .y ());
768
- const auto on_ego_driving_lane =
769
- within (object_centroid, object.overhang_lanelet .polygon2d ().basicPolygon ());
770
+ const auto & object_pos = object.object .kinematics .initial_pose_with_covariance .pose .position ;
771
+ const auto on_ego_driving_lane = within (
772
+ to2D (toLaneletPoint (object_pos)).basicPoint (),
773
+ object.overhang_lanelet .polygon2d ().basicPolygon ());
770
774
if (on_ego_driving_lane) {
771
775
if (isObjectOnRoadShoulder (object, planner_data->route_handler , parameters)) {
772
776
return true ;
0 commit comments