Closed xiaozhi12345678 closed 5 years ago
The thing with the negative IDs is related to how JOSM works. New points always have a negative ID in JOSM since they are only temporary points because positive IDs can only be assigned by the central OSM server, to make sure they are no clashes.
Also JOSM does not provide a guarantee to keep negative IDs at their current value. They seem to change every time a file is saved or loaded. Therefore negative IDs that lanelet2 sees and that JOSM shows are never the same. To solve this problem, you could either set up you own map server or run the script make_ids_positive.py
in lanelet2_python
. It detects negative Ids and fixes them.
For your failed assertion, I can only guess, since I don't know what changes you have done to the map. If its related to negative IDs, I suppose that these issues should go away after that.
Thank you every much,your comments help me a lot. Here I want to ask some question, the first is the lanelet bound of left and right must be the same direction?I see some are in the opposite direction but it can also routing.The second is that I tried some lanelet with tag one_way=no, but it can not navit,how to deal with it? And some cases,for example from the lanelet id 45258 to 45260,you can see a clear path with our eyes,but it failed to navit.Is it right?Or there are some rules? Looking forward to your reply.
I am sorry to trouble you again,but I meet a question that our car knows GPS point,but it doesn't know the id of lanelet the car locates.How to solve it?Does the codes contain them?
And some cases,for example from the lanelet id 45258 to 45260,you can see a clear path with our eyes,but it failed to navit.Is it right?
I cannot reproduce your problem. There is a path between the two:
import lanelet2
pr = lanelet2.projection.UtmProjector(lanelet2.io.Origin(49,8.4))
map = lanelet2.io.load("res/mapping_example.osm", pr)
trafficRules = lanelet2.traffic_rules.create(lanelet2.traffic_rules.Locations.Germany, lanelet2.traffic_rules.Participants.Vehicle)
graph = lanelet2.routing.RoutingGraph(map, trafficRules)
ll1 = map.laneletLayer[45258]
ll2 = map.laneletLayer[45260]
for ll in graph.shortestPath(ll1, ll2):
print(ll)
This prints the lanelets 45258, 42440 and 45260. A path from 45260 to 45258 does not exist however, since this would be the wrong driving direction. You would have to tag all three lanelets as one_way=no
and search with the inverted lanelets.
Lanelet2 takes care of the orientation of the boundaries. When a left bound is wrongly oriented it is inverted before assigning it to a lanelet.
I am sorry to trouble you again,but I meet a question that our car knows GPS point,but it doesn't know the id of lanelet the car locates
Depending on how precise your GPS is, you can use the projectors in lanelet2 to get them into a local coordinate system. Then you could look it up the closest Lanelet with findNearest
.
If your GPS is not precise enough, you will have to implement you own solution. Maybe something that considers the past GPS points.
emmm,I am not understanding "You would have to tag all three lanelets as one_way=no and search with the inverted lanelets."For example the lanelet id 45262,45264,45268,and they have tag one_way=no,from 45262 to 45268 succeed but from 45268 to 45262 failed.Could you please explain it for me?Thank you!
Lanelets have an orientation. That a Lanelet is bidirectional does not mean you can search for a path that requires driving backwards. Lanelet 45268 is a lanelet that is oriented such that a vehicle on it can drive to the north. There is no way that this vehicle could reach lanelet 45262 without making a U-Turn, but the map does not allow such a U-Turn.
If you invert the Lanelet hovewer you get the sibling of this lanelet that is now oriented to the south. And for this lanelet there is now a way that can reach the (also inverted) lanelet 45262. Speaking in code that means:
# ... do the things from my last post
ll1 = map.laneletLayer[45268]
ll2 = map.laneletLayer[45262]
path = graph.shortestPath(ll1, ll2) # no result
path = graph.shortestPath(ll1.invert(), ll2.invert()) # yields 45268 (inverted), 45264 (inverted), 45262 (inverted)
I want to use the lanelet2 library in my project, but I don't know how to write CMakelist.txt in my project. I want it to be easy ,so I create my project in the lanelet2 library,because I want to refer to the lanelet2_examples folder,which just shows how to use the library ,and contains CMakelist.txt. I just modify something ,such as the project name.But it always shows that /home/gxf/catkin_ws/src/lanelet2/openstreetmap/src/readingAndWriting.cpp:1:46: fatal error: lanelet2_core/primitives/Lanelet.h: 没有那个文件或目录. I don't know how to modify my CMakelist.txt. Please help me,thank you. here is my CMakelist.txt below:
set(MRT_PKG_VERSION 2.8.12) cmake_minimum_required(VERSION 2.8.3) project(openstreetmap) @fzi-admin
###################
###################
find_package( catkin REQUIRED mrt_cmake_modules REQUIRED
roscpp rospy geometry_msgs sensor_msgs
nodelet
std_msgs nav_msgs oxford_gps_eth
mobileye
)
include_directories( include/openstreetmap ${mrt_INCLUDE_DIRS} ${catkin_INCLUDE_DIRS} ${EIGEN3_INCLUDE_DIR} ${OCTOMAP_INCLUDE_DIR}
)
link_directories( ${catkin_INCLUDE_DIRS} ${mrt_LIBRARY_DIRS} )
include(UseMrtStdCompilerFlags) include(UseMrtAutoTarget) include(GatherDeps)
mrt_add_to_ide(README.md .gitlab-ci.yml)
add_definitions(-DPKG_DIR="${CMAKE_CURRENT_LIST_DIR}") set(MRT_FORCE_PYTHON_COVERAGE 1)
########################
########################
mrt_python_module_setup()
###################################
###################################
######################################################################### generate_messages( DEPENDENCIES
)
catkin_package( INCLUDE_DIRS include LIBRARIES openstreetmap #################################
################################# DEPENDS system_lib message_runtime )
###########
###########
add_executable( openstreetmap
src/openstreetmap.cpp
src/globalVar.cpp
src/openstreetmaplib.cpp
src/readingAndWriting.cpp
)
target_link_libraries(openstreetmap ${catkin_LIBRARIES} libtinyxml.a) target_link_libraries(openstreetmap ${catkin_LIBRARIES})
add_dependencies(${PROJECT_NAME} ${catkin_EXPORTED_TARGETS})
glob_folders(SRC_DIRECTORIES "${CMAKE_CURRENT_SOURCE_DIR}/src") if (SRC_DIRECTORIES)
foreach(SRC_DIR ${SRC_DIRECTORIES})
mrt_add_executable(${SRC_DIR} FOLDER "src/${SRC_DIR}")
endforeach()
else()
mrt_add_executable(${PROJECT_NAME} FOLDER "src")
endif()
#############
#############
#############
#############
@xiaozhi12345678 @poggenhans
I don't know why some letters become bigger
I don't know why some letters become bigger
That's because of the Markdown support, please edit your comment: just add three backticks: ```
before and after the code.
See https://help.github.com/en/articles/basic-writing-and-formatting-syntax#quoting-code
I don't get the connection between the original question and this one. I'll close this because the original question has been answered. Please open a new one if you have any follow-up questions.
Our CMakeLists
are not meant to be copied and pasted because they use our internal mrt_cmake_modules
package. We can not guarantee that future changes to it would break your stuff. For a tutorial on how to use other catkin packages within your package, please refer to the official catkin documentation.
Sorry , there is no connection between my question and this original question .Just because I cannot write my question in new issue window.Sorry
hello,I have some questions there and I hope you can help me,thanks a lot. the first is after I paint some road using lanelet2 on JOSM,the object doesn't have id,and the id in .osm file is negative,is it correct?could you tell me how to produce id? the second is that I run the example code "06_routing" with the above file,the error comes "main.cpp:60: void part1CreatingAndUsingRoutingGraphs(): Assertion `!!routingGraph->right(lanelet)' failed."could you tell me how to solve it?