Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix(lanelet2_extension): fix getAngleDifference #264

13 changes: 1 addition & 12 deletions map/lanelet2_extension/lib/query.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,17 +34,6 @@
#include <vector>

using lanelet::utils::to2D;
namespace
{
double getAngleDifference(const double angle1, const double angle2)
{
const double normalized_angle1 = tier4_autoware_utils::normalizeRadian(angle1);
const double normalized_angle2 = tier4_autoware_utils::normalizeRadian(angle2);
const double diff_angle = std::fabs(normalized_angle1 - normalized_angle2);
return diff_angle;
}

} // namespace

namespace lanelet
{
Expand Down Expand Up @@ -727,7 +716,7 @@ bool query::getClosestLanelet(
lanelet::ConstLineString3d segment = getClosestSegment(search_point, llt.centerline());
double segment_angle = std::atan2(
segment.back().y() - segment.front().y(), segment.back().x() - segment.front().x());
double angle_diff = getAngleDifference(segment_angle, pose_yaw);
double angle_diff = std::abs(tier4_autoware_utils::normalizeRadian(segment_angle - pose_yaw));
if (angle_diff < min_angle) {
min_angle = angle_diff;
*closest_lanelet_ptr = llt;
Expand Down