Closed ligonap closed 1 year ago
To find the following lanelet I tested the following from tutorial.py:
projector = lanelet2.projection.UtmProjector(lanelet2.io.Origin(49, 8.4))
map = lanelet2.io.load('mapping_example.osm', projector)
traffic_rules = lanelet2.traffic_rules.create(lanelet2.traffic_rules.Locations.Germany,
lanelet2.traffic_rules.Participants.Vehicle)
graph = lanelet2.routing.RoutingGraph(map, traffic_rules)
lanelet = map.laneletLayer[4984315]
print(graph.following(lanelet))
There is one element in the output. So far so good.
If I test this with my map (Origin(0, 0)), where actually no TrafficRules are intended (I used the same TrafficRules), because this is a kind of highway, I get no element. But in my map there are 591 lanelets. The highway has three lanes of 197 lanelets each. Somehow the routine cannot be reproduced with other cards.
Well, looks like your map is incorrect then. Make sure the lanelets are properly tagged as road lanelets (see here), otherwise they won't become part of the vehicle routing graph.
My lanelets are defined as follows:
<tag k="location" v="urban" />
<tag k="one_way" v="yes" />
<tag k="participant" v="vehicle:robot" />
<tag k="region" v="de" />
<tag k="subtype" v="raceway" />
<tag k="type" v="lanelet" />
Is it the vehicle:robot
?
To find the following lanelet, I helped myself with a dictionary { lanelet_id : (left_line_id, right_line_id) }
.
Is it the vehicle:robot?
Yes. This means: This road is only for robots. subtype=raceway
is also an undefined value, so it's assumed to be a non-drivable lanelet.
I have changed the entries as follows:
<tag k="location" v="nonurban" />
<tag k="one_way" v="yes" />
<tag k="region" v="de" />
<tag k="subtype" v="highway" />
<tag k="type" v="lanelet" />
And the following code successfully gives me the ID of the following lanelet.
traffic_rules = lanelet2.traffic_rules.create(lanelet2.traffic_rules.Locations.Germany, lanelet2.traffic_rules.Participants.Vehicle)
graph = lanelet2.routing.RoutingGraph(self.lmap, traffic_rules)
following_Lanelet_id = (graph.following(lanelet))[0].id
Thank you for the tips.
This issue is stale because it has been open for 90 days with no activity. Is this issue still work in progress? If yes, mark it as "WIP" or comment, otherwise it will be closed in 30 days.
This issue was closed because it has been stalled for 30 days with no activity.
Hello! I have two questions about the Python implementation of Lanelet2.
1) How can the immediately following lanelet be determined based on a lanelet? The neighbouring lanelets can be determined using
leftBound
andrightBound
, whereby the original lanelet is also returned. E.g.:lmap.laneletLayer.findUsages(lanelet.rightBound)
Alanelet.frontBound
is somehow missing.2) How can I determine or return the linestrings or points of a lanelet? So that I get the start points of following lineStrings via the lineStrings and the end points and thereby the following lanelet.