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

Question: How to create a map when 2 lanes merging into 1 lane? #358

Open
felixf4xu opened this issue Sep 3, 2024 · 3 comments
Open

Question: How to create a map when 2 lanes merging into 1 lane? #358

felixf4xu opened this issue Sep 3, 2024 · 3 comments

Comments

@felixf4xu
Copy link

Hi,

I would like to create a map like this: lanelet id 2 (circled in green) and lanelet id 3 (circled in yellow) are merging into lanelet id 1.
image

I would like to make lane change possible from lanelet 2 to lanelet 3, in this case, what is the relationship between id 2 and 3? I'm referrring to this type:

 enum class RelationType : uint8_t {
   None = 0,                 
   Successor = 0b1,          
   Left = 0b10,              
   Right = 0b100,            
   AdjacentLeft = 0b1000,    
   AdjacentRight = 0b10000,  
   Conflicting = 0b100000,   
   Area = 0b1000000          
 };
@poggenhans
Copy link
Contributor

2 and 3 will be conflicting, to indicate a vehicle on 2 would be in the path of a vehicle on 3 (or vica versa) and hence a collision is possible.

It's not possible to make a lane change from 2 to 3, since they don't share a common border. If you want to indicate that a vehicle on 2 can use the whole area when driving towards 1, you could increase the left border of 2 so that 2 covers the whole area of 3.

@felixf4xu
Copy link
Author

@poggenhans Thanks for the comment.

I tried to merge 2 and 3 into one new lanelet, but then I can't find a route from 4 (or 5) to 1. Lanelet 4 (or 5) does not take the new merged lanelet as its next lanelet.

I'm using RoutingGraph::getRoute() to get the route.

@poggenhans
Copy link
Contributor

Merging the two into a single lanelet won't work. But you could e.g. extend the right border of lanelet 3 so that it also includes the first point of the right border of lanelet 2. The result is that a vehicle coming from 5 and driving towards 1 has the full combined area of 2 and 3 at its disposal for driving.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

2 participants