Carma-platform v4.2.0
CARMA Platform is built on robot operating system (ROS) and utilizes open source software (OSS) that enables Cooperative Driving Automation (CDA) features to allow Automated Driving Systems to interact and cooperate with infrastructure and other vehicles through communication.
visualize_xodr.py
Go to the documentation of this file.
1"""
2
3Purpose:
4This script parses an OpenDRIVE (.xodr) map file and visualizes the basic road geometries using matplotlib.
5
6Key Features:
7
8- Loads and parses an .xodr file using xml.etree.ElementTree.
9- Extracts position, heading, and length for each road geometry segment.
10- Plots each road segment as an arrow on a 2D plane.
11- Optionally overlays road names on the visualization for identification.
12
13Use Case:
14Quick inspection and debugging of road layouts from .xodr files in a readable 2D plot.
15
16"""
17
18
19import matplotlib
20matplotlib.use('Agg') # Use this on headless systems
21
22import matplotlib.pyplot as plt
23import xml.etree.ElementTree as ET
24import numpy as np
25
26# === Load and parse the XODR file ===
27xodr_file_path = "xodr_map.xodr" # TODO: Change this to your actual xodr file path
28tree = ET.parse(xodr_file_path)
29root = tree.getroot()
30
31fig, ax = plt.subplots(figsize=(10, 10))
32
33# === Go through each road geometry ===
34for road in root.findall(".//road"):
35 road_name = road.get("name", "")
36 for geometry in road.findall(".//geometry"):
37 try:
38 x = float(geometry.get("x"))
39 y = float(geometry.get("y"))
40 hdg = float(geometry.get("hdg"))
41 length = float(geometry.get("length"))
42
43 dx = length * np.cos(hdg)
44 dy = length * np.sin(hdg)
45
46 ax.arrow(x, y, dx, dy, head_width=1.0, length_includes_head=True)
47
48 if road_name:
49 ax.text(x, y, road_name, fontsize=6)
50 except Exception as e:
51 print("Error in geometry:", ET.tostring(geometry, encoding='unicode'))
52 print("Reason:", e)
53
54# === Plot Settings ===
55ax.set_title("Basic Road Geometry Visualization (XODR)")
56ax.set_xlabel("X [m]")
57ax.set_ylabel("Y [m]")
58ax.set_aspect("equal")
59plt.grid(True)
60plt.tight_layout()
61plt.show()