fzi-forschungszentrum-informatik / Lanelet2

Map handling framework for automated driving
BSD 3-Clause "New" or "Revised" License
800 stars 327 forks source link

lanelet2.geometry.findNearest ArgumentError #104

Closed cbrewitt closed 4 years ago

cbrewitt commented 4 years ago

I am attempting to use lanelet2.geometry.findNearest to find the lanelet which a point is in. I've contructed a simple script which reproduces the issue based on the reply in this issue, and the python API tutorial:

import lanelet2
from lanelet2.core import Lanelet, LineString3d, Point3d, getId, LaneletMap
from lanelet2.projection import UtmProjector

def get_linestring_at_x(x):
    return LineString3d(getId(), [Point3d(getId(), x, i, 0) for i in range(0, 3)])

def get_linestring_at_y(y):
    return LineString3d(getId(), [Point3d(getId(), i, y, 0) for i in range(0, 3)])

def get_a_lanelet():
    return Lanelet(getId(), get_linestring_at_y(2), get_linestring_at_y(0))

myMap = LaneletMap()
lanelet = get_a_lanelet()
myMap.add(lanelet)
myProjector = UtmProjector(lanelet2.io.Origin(49, 8.4))

gpsPoint = lanelet2.core.GPSPoint(45,8)
plocal = myProjector.forward(gpsPoint)
lanelets = lanelet2.geometry.findNearest(myMap.laneletLayer, plocal, 1)

When running this script, I get the following error:

Traceback (most recent call last):
  File "reproduce_issue.py", line 25, in <module>
    lanelets = lanelet2.geometry.findNearest(myMap.laneletLayer, plocal, 1)
Boost.Python.ArgumentError: Python argument types in
    lanelet2.geometry.findNearest(LaneletLayer, BasicPoint3d, int)
did not match C++ signature:
    findNearest(lanelet::PrimitiveLayer<std::shared_ptr<lanelet::RegulatoryElement> > {lvalue}, Eigen::Matrix<double, 2, 1, 2, 2, 1>, unsigned int)
    findNearest(lanelet::PrimitiveLayer<lanelet::Area> {lvalue}, Eigen::Matrix<double, 2, 1, 2, 2, 1>, unsigned int)
    findNearest(lanelet::PrimitiveLayer<lanelet::Lanelet> {lvalue}, Eigen::Matrix<double, 2, 1, 2, 2, 1>, unsigned int)
    findNearest(lanelet::PrimitiveLayer<lanelet::Polygon3d> {lvalue}, Eigen::Matrix<double, 2, 1, 2, 2, 1>, unsigned int)
    findNearest(lanelet::PrimitiveLayer<lanelet::LineString3d> {lvalue}, Eigen::Matrix<double, 2, 1, 2, 2, 1>, unsigned int)
    findNearest(lanelet::PrimitiveLayer<lanelet::Point3d> {lvalue}, Eigen::Matrix<double, 2, 1, 2, 2, 1>, unsigned int)

Based on the example in the other issue, I would have assumed that a BasicPoint3d would be valid for the second argument but the error seems to suggest not.

poggenhans commented 4 years ago

findNearest works only in the 2D space. If you use a BasicPoint2d for your query, it should work fine.

cbrewitt commented 4 years ago

Thank you, BasicPoint2d has worked.

vadeshah commented 4 years ago

Hi there,

I've been using the findNearest function as well with the same intent that @cbrewitt had mentioned above. I was confused about the "count" parameter and how exactly it worked. The description in the code, which I've copied below, was difficult for me to understand. If you could provide a more detailed explanation on what the "count" parameter specifies, I would greatly appreciate it.

// Idea: nearestUntil passes us elements with increasing bounding box // distance. // If this distance is greater than the actual distance (between primitives) // of the count-th furthest current element, then we can stop, because all // succeding elements will be even further away.

When I run findNearest with count=1 for a predefined Point2d that lies in my .osm map, sometimes I get 6 or more lanelets from findNearest. These lanelets are adjacent, but it is not the case that they all share an overlapping region in which my point lies. Is there any way to only get the lanelets that the point lies in? Thank you in advance for your help.