Skip to content
This repository has been archived by the owner on Jul 1, 2024. It is now read-only.

Commit

Permalink
feat(lanelet2_extension): consider lane-ego angle difference in lane …
Browse files Browse the repository at this point in the history
…following module

Signed-off-by: Mehmet Dogru <42mehmetdogru42@gmail.com>
  • Loading branch information
mehmetdogru committed Mar 12, 2023
1 parent 34338c0 commit dad9b92
Show file tree
Hide file tree
Showing 2 changed files with 96 additions and 0 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -238,6 +238,12 @@ bool getClosestLanelet(
const ConstLanelets & lanelets, const geometry_msgs::msg::Pose & search_pose,
ConstLanelet * closest_lanelet_ptr);

bool getClosestLaneletWithConstrains(
const ConstLanelets & lanelets, const geometry_msgs::msg::Pose & search_pose,
ConstLanelet * closest_lanelet_ptr,
const double dist_threshold = std::numeric_limits<double>::max(),
const double yaw_threshold = std::numeric_limits<double>::max());

bool getCurrentLanelets(
const ConstLanelets & lanelets, const geometry_msgs::msg::Pose & search_pose,
ConstLanelets * current_lanelets_ptr);
Expand Down
90 changes: 90 additions & 0 deletions tmp/lanelet2_extension/lib/query.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -794,6 +794,96 @@ bool query::getClosestLanelet(
return found;
}

bool query::getClosestLaneletWithConstrains(
const ConstLanelets & lanelets, const geometry_msgs::msg::Pose & search_pose,
ConstLanelet * closest_lanelet_ptr, const double dist_threshold, const double yaw_threshold)
{
bool found = false;

if (closest_lanelet_ptr == nullptr) {
std::cerr << "argument closest_lanelet_ptr is null! Failed to find closest lanelet"
<< std::endl;
return found;
}

if (lanelets.empty()) {
return found;
}

lanelet::BasicPoint2d search_point(search_pose.position.x, search_pose.position.y);

// find by distance
std::vector<std::pair<lanelet::ConstLanelet, double>> candidate_lanelets;
{
for (const auto & llt : lanelets) {
double distance =
boost::geometry::comparable_distance(llt.polygon2d().basicPolygon(), search_point);

if (distance <= dist_threshold) {
candidate_lanelets.emplace_back(llt, distance);
}
}

if (!candidate_lanelets.empty()) {
// sort by distance
std::sort(
candidate_lanelets.begin(), candidate_lanelets.end(),
[](
const std::pair<lanelet::ConstLanelet, double> & x,
std::pair<lanelet::ConstLanelet, double> & y) { return x.second < y.second; });
} else {
std::cerr << "there are no lanelets close enough!" << std::endl;
return found;
}
}

std::cout << "************************" << std::endl;
for (const auto & llt_pair : candidate_lanelets) {
std::cout << "llt_pair.first.id: " << llt_pair.first.id() << std::endl;
}
std::cout << "************************" << std::endl;

// find closest lanelet within yaw_threshold
{
double min_angle = std::numeric_limits<double>::max();
double min_distance = std::numeric_limits<double>::max();
double pose_yaw = tf2::getYaw(search_pose.orientation);
for (const auto & llt_pair : candidate_lanelets) {
const auto & distance = llt_pair.second;

std::cout << "llt_id: " << llt_pair.first.id() << std::endl;
std::cout << "distance: " << llt_pair.second << std::endl;

lanelet::ConstLineString3d segment =
getClosestSegment(search_point, llt_pair.first.centerline());
double segment_angle = std::atan2(
segment.back().y() - segment.front().y(), segment.back().x() - segment.front().x());
double angle_diff = std::abs(autoware_utils::normalize_radian(segment_angle - pose_yaw));

std::cout << "angle_diff [deg]: " << angle_diff * 180 / M_PI << std::endl;
std::cout << "min_angle [deg]: " << min_angle * 180 / M_PI << std::endl;
std::cout << "yaw_threshold [deg]: " << yaw_threshold * 180 / M_PI << std::endl;
std::cout << "min_distance: " << min_distance << std::endl;

if (angle_diff > std::abs(yaw_threshold)) continue;

if (min_distance < distance) break;

if (angle_diff < min_angle) {
min_angle = angle_diff;
min_distance = distance;
*closest_lanelet_ptr = llt_pair.first;
found = true;
std::cout << "*** closest_lanelet_id: " << llt_pair.first.id() << std::endl;
}
}
}

std::cout << "-----------------------------" << std::endl;

return found;
}

bool query::getCurrentLanelets(
const ConstLanelets & lanelets, const geometry_msgs::msg::Pose & search_pose,
ConstLanelets * current_lanelets_ptr)
Expand Down

0 comments on commit dad9b92

Please sign in to comment.