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 (#148)

* feat(lanelet2_extension): consider lane-ego angle difference in lane following module

Signed-off-by: Mehmet Dogru <[email protected]>

* remove debug prints

Signed-off-by: Mehmet Dogru <[email protected]>

* include limits

Signed-off-by: Mehmet Dogru <[email protected]>

* style(pre-commit): autofix

* fix: use bg:distance

Signed-off-by: Mehmet Dogru <[email protected]>

* refactor: replace with getLaneletAngle

Signed-off-by: Mehmet Dogru <[email protected]>

---------

Signed-off-by: Mehmet Dogru <[email protected]>
Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
  • Loading branch information
mehmetdogru and pre-commit-ci[bot] authored Mar 28, 2023
1 parent 150b926 commit d8444ee
Show file tree
Hide file tree
Showing 2 changed files with 75 additions and 0 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,7 @@
#include <lanelet2_core/primitives/Lanelet.h>
#include <lanelet2_routing/RoutingGraph.h>

#include <limits>
#include <memory>
#include <string>
#include <vector>
Expand Down Expand Up @@ -238,6 +239,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
68 changes: 68 additions & 0 deletions tmp/lanelet2_extension/lib/query.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -794,6 +794,74 @@ 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::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;
}
}

// 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;

double lanelet_angle = getLaneletAngle(llt_pair.first, search_pose.position);
double angle_diff = std::abs(autoware_utils::normalize_radian(lanelet_angle - pose_yaw));

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;
}
}
}

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 d8444ee

Please sign in to comment.