@@ -61,32 +61,30 @@ bool isCentroidWithinLanelet(
61
61
const PredictedObject & object, const lanelet::ConstLanelet & lanelet, const double yaw_threshold)
62
62
{
63
63
const auto & object_pose = object.kinematics .initial_pose_with_covariance .pose ;
64
- const auto closest_pose = lanelet::utils::getClosestCenterPose (lanelet, object_pose. position );
65
- if (
66
- std::abs ( autoware::universe_utils::calcYawDeviation (closest_pose, object_pose)) >
67
- yaw_threshold ) {
64
+ if (! boost::geometry::within (
65
+ lanelet::utils::to2D ( lanelet::utils::conversion::toLaneletPoint (object_pose. position ))
66
+ . basicPoint (),
67
+ lanelet. polygon2d (). basicPolygon ()) ) {
68
68
return false ;
69
69
}
70
70
71
- return boost::geometry::within (
72
- lanelet::utils::to2D (lanelet::utils::conversion::toLaneletPoint (object_pose.position ))
73
- .basicPoint (),
74
- lanelet.polygon2d ().basicPolygon ());
71
+ const auto closest_pose = lanelet::utils::getClosestCenterPose (lanelet, object_pose.position );
72
+ return std::abs (autoware::universe_utils::calcYawDeviation (closest_pose, object_pose)) <
73
+ yaw_threshold;
75
74
}
76
75
77
76
bool isPolygonOverlapLanelet (
78
77
const PredictedObject & object, const lanelet::ConstLanelet & lanelet, const double yaw_threshold)
79
78
{
80
- const auto & object_pose = object.kinematics .initial_pose_with_covariance .pose ;
81
- const auto closest_pose = lanelet::utils::getClosestCenterPose (lanelet, object_pose.position );
82
- if (
83
- std::abs (autoware::universe_utils::calcYawDeviation (closest_pose, object_pose)) >
84
- yaw_threshold) {
79
+ const auto lanelet_polygon = utils::toPolygon2d (lanelet);
80
+ if (!isPolygonOverlapLanelet (object, lanelet_polygon)) {
85
81
return false ;
86
82
}
87
83
88
- const auto lanelet_polygon = utils::toPolygon2d (lanelet);
89
- return isPolygonOverlapLanelet (object, lanelet_polygon);
84
+ const auto & object_pose = object.kinematics .initial_pose_with_covariance .pose ;
85
+ const auto closest_pose = lanelet::utils::getClosestCenterPose (lanelet, object_pose.position );
86
+ return std::abs (autoware::universe_utils::calcYawDeviation (closest_pose, object_pose)) <
87
+ yaw_threshold;
90
88
}
91
89
92
90
bool isPolygonOverlapLanelet (
0 commit comments