7 if __name__ ==
"__main__":
8 parser = argparse.ArgumentParser()
9 parser.add_argument(
"filename", help=
"Path to the input osm file")
10 parser.add_argument(
"output", help=
"Path to resulting debug routing graph")
13 help=
"traffic participant type (one of vehicle, bicycle, pedestrian, train",
17 parser.add_argument(
"--lat", help=
"Lateral position of origin", type=float, default=49)
18 parser.add_argument(
"--lon", help=
"Longitudinal position of origin", type=float, default=8)
19 args = parser.parse_args()
21 rules_map = {
"vehicle": lanelet2.traffic_rules.Participants.Vehicle,
22 "bicycle": lanelet2.traffic_rules.Participants.Bicycle,
23 "pedestrian": lanelet2.traffic_rules.Participants.Pedestrian,
24 "train": lanelet2.traffic_rules.Participants.Train}
25 proj = lanelet2.projection.UtmProjector(lanelet2.io.Origin(args.lat, args.lon))
26 laneletmap = lanelet2.io.load(args.filename, proj)
28 routing_cost = lanelet2.routing.RoutingCostDistance(0.)
29 traffic_rules = lanelet2.traffic_rules.create(lanelet2.traffic_rules.Locations.Germany,
30 rules_map[args.participant])
31 graph = lanelet2.routing.RoutingGraph(laneletmap, traffic_rules, [routing_cost])
32 debug_map = graph.getDebugLaneletMap()
34 lanelet2.io.write(args.output, debug_map, proj)