Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 3 additions & 0 deletions .gitmodules
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
[submodule "pybind11"]
path = pybind11
url = https://github.com/pybind/pybind11.git
68 changes: 61 additions & 7 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,9 @@ include(GNUInstallDirs)
include(CMakePackageConfigHelpers)

option(OPENDRIVE_BUILD_TESTS "Build OpenDrive tests" OFF)
option(BUILD_PYTHON_BINDINGS "Build Python bindings for libOpenDRIVE" OFF)

# Try to use an installed pugixml first; otherwise fetch it
find_package(pugixml QUIET CONFIG)
if(NOT TARGET pugixml::pugixml)
if(TARGET pugixml)
Expand All @@ -23,6 +25,7 @@ if(NOT TARGET pugixml::pugixml)
endif()
endif()

# Define libOpenDRIVE sources
set(SOURCES
src/Geometries/Arc.cpp
src/Geometries/CubicSpline.cpp
Expand All @@ -45,13 +48,15 @@ set(SOURCES
src/RoutingGraph.cpp
)

# Build libOpenDRIVE
add_library(OpenDrive ${SOURCES})
add_library(OpenDrive::OpenDrive ALIAS OpenDrive)
set_target_properties(OpenDrive PROPERTIES
CXX_STANDARD 17
CXX_STANDARD_REQUIRED ON
POSITION_INDEPENDENT_CODE ON
)

if(MSVC)
target_compile_options(OpenDrive PRIVATE /W3 /EHsc)
target_compile_definitions(OpenDrive PRIVATE _USE_MATH_DEFINES)
Expand All @@ -67,14 +72,20 @@ target_include_directories(
$<INSTALL_INTERFACE:${CMAKE_INSTALL_INCLUDEDIR}>
)

# Tests (optional)
if(OPENDRIVE_BUILD_TESTS)
include(CTest)
FetchContent_Declare(
Catch2
GIT_REPOSITORY https://github.com/catchorg/Catch2.git
GIT_TAG v3.4.0
)
FetchContent_MakeAvailable(Catch2)

# Prefer an installed Catch2, fallback to fetching it
find_package(Catch2 QUIET CONFIG)
if(NOT TARGET Catch2::Catch2WithMain)
FetchContent_Declare(
Catch2
GIT_REPOSITORY https://github.com/catchorg/Catch2.git
GIT_TAG v3.4.0
)
FetchContent_MakeAvailable(Catch2)
endif()
include(Catch)

add_executable(tests tests/test.cpp)
Expand All @@ -86,6 +97,49 @@ if(OPENDRIVE_BUILD_TESTS)
catch_discover_tests(tests WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/tests)
endif()

# Add Python bindings (optional, controlled by option)
if(BUILD_PYTHON_BINDINGS)
find_package(Python3 COMPONENTS Interpreter Development REQUIRED)
find_package(pybind11 CONFIG REQUIRED)

# Define binding sources
set(BINDING_SOURCES
bindings/bindings.cpp
bindings/opendrivemap.cpp
bindings/junction.cpp
bindings/lane.cpp
bindings/lanesection.cpp
bindings/road.cpp
bindings/refline.cpp
bindings/mesh.cpp
bindings/routinggraph.cpp
bindings/roadmark.cpp
bindings/roadnetworkmesh.cpp
bindings/roadobject.cpp
bindings/lanevalidityrecord.cpp
bindings/roadsignal.cpp
bindings/math.cpp
bindings/xml_node.cpp
# Add other binding files as needed
)

# Create Python module
pybind11_add_module(open_drive ${BINDING_SOURCES})
target_link_libraries(open_drive PRIVATE OpenDrive)

# Public include dir for the module (OpenDrive already exposes its include dir)
target_include_directories(
open_drive PRIVATE
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
)

# Install Python module
install(TARGETS open_drive
LIBRARY DESTINATION ${Python3_SITELIB}
)
endif()

# Installation
install(
TARGETS OpenDrive
EXPORT OpenDriveTargets
Expand Down Expand Up @@ -120,4 +174,4 @@ install(FILES
"${CMAKE_CURRENT_BINARY_DIR}/OpenDriveConfig.cmake"
"${CMAKE_CURRENT_BINARY_DIR}/OpenDriveConfigVersion.cmake"
DESTINATION ${CMAKE_INSTALL_LIBDIR}/cmake/OpenDrive
)
)
40 changes: 40 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,46 @@ If requiring a shared library, use:
cmake -DBUILD_SHARED_LIBS=ON ..
```

### Python Bindings with pybind11

To build the Python bindings using pybind11 and enable installation via pip in editable mode (`pip install -e .`), follow these steps:

1. **Create and enter the build directory:**

```bash
mkdir build
cd build

2. **Configure the build with Python bindings enabled, specifying your Python interpreter:**

```
cmake -DBUILD_SHARED_LIBS=ON -DBUILD_PYTHON_BINDINGS=ON -DPython3_EXECUTABLE=$(which python) ..
```

3. **Build the project:**
```
make
```

4. **Install the Python package in editable mode:**
From the root directory of the repository (not inside `build`), run:

```
pip install -e .
```
This command uses the generated Python bindings and sets up the package in your environment so that changes to the source code reflect immediately without reinstalling.

5. **Import and use the package in Python:**
After installation, you can import the opendrive module in Python:

```
import opendrive

# Example: List available attributes
print(dir(opendrive))
```
This verifies the bindings are available and provides an overview of the exposed classes and functions.

## Viewer
Check out the viewer at [odrviewer.io](https://odrviewer.io) which uses this library. Use the [odrviewer project](https://github.com/pageldev/odrviewer) to post issues and feature requests for odrviewer.io.

Expand Down
37 changes: 37 additions & 0 deletions bindings/bindings.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,37 @@
#include "bindings.h"
#include <pybind11/pybind11.h>
#include <pybind11/stl.h>
#include <OpenDriveMap.h>
#include <Road.h> // For RoadLink::ContactPoint

namespace py = pybind11;

PYBIND11_MODULE(opendrive, m) {
m.doc() = "Python bindings for libOpenDRIVE";

// RoadLink depends on XmlNode
init_xml_node(m);

// Bind ContactPoint enum
py::enum_<odr::RoadLink::ContactPoint>(m, "ContactPoint")
.value("None", odr::RoadLink::ContactPoint::ContactPoint_None)
.value("Start", odr::RoadLink::ContactPoint::ContactPoint_Start)
.value("End", odr::RoadLink::ContactPoint::ContactPoint_End)
.export_values();

// Initialize other modules
init_opendrivemap(m);
init_mesh(m);
init_junction(m);
init_lane(m);
init_lanesection(m);
init_road(m);
init_refline(m);
init_routinggraph(m);
init_roadmark(m);
init_roadnetworkmesh(m);
init_roadobject(m);
init_lanevalidityrecord(m);
init_roadsignal(m);
init_math(m);
}
20 changes: 20 additions & 0 deletions bindings/bindings.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
#pragma once
#include <pybind11/pybind11.h>

namespace py = pybind11;

void init_opendrivemap(py::module_ &);
void init_mesh(py::module_ &);
void init_junction(py::module_ &);
void init_lane(py::module_ &);
void init_lanesection(py::module_ &);
void init_road(py::module_ &);
void init_routinggraph(py::module_ &);
void init_roadmark(py::module_ &);
void init_roadnetworkmesh(py::module_ &);
void init_roadobject(py::module_ &);
void init_lanevalidityrecord(py::module_ &);
void init_refline(py::module_ &);
void init_roadsignal(py::module_ &);
void init_math(py::module_ &);
void init_xml_node(py::module_ &m);
56 changes: 56 additions & 0 deletions bindings/junction.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,56 @@
#include <pybind11/pybind11.h>
#include <pybind11/stl.h>
#include "XmlNode.h"
#include <Junction.h>


namespace py = pybind11;

void init_junction(py::module_ &m) {
// Bind JunctionLaneLink
py::class_<odr::JunctionLaneLink>(m, "JunctionLaneLink")
.def(py::init<int, int>(),
py::arg("from"), py::arg("to"),
"Constructs a JunctionLaneLink with from and to lane IDs")
.def_readwrite("from", &odr::JunctionLaneLink::from, "Source lane ID")
.def_readwrite("to", &odr::JunctionLaneLink::to, "Destination lane ID");

// Bind JunctionConnection
py::class_<odr::JunctionConnection>(m, "JunctionConnection")
.def(py::init<std::string, std::string, std::string, odr::JunctionConnection::ContactPoint>(),
py::arg("id"), py::arg("incoming_road"), py::arg("connecting_road"), py::arg("contact_point"),
"Constructs a JunctionConnection with ID, roads, and contact point")
.def_readwrite("id", &odr::JunctionConnection::id, "Connection ID")
.def_readwrite("incoming_road", &odr::JunctionConnection::incoming_road, "Incoming road ID")
.def_readwrite("connecting_road", &odr::JunctionConnection::connecting_road, "Connecting road ID")
.def_readwrite("contact_point", &odr::JunctionConnection::contact_point, "Contact point (None, Start, End)")
.def_readwrite("lane_links", &odr::JunctionConnection::lane_links, "Set of lane links");

// Bind JunctionPriority
py::class_<odr::JunctionPriority>(m, "JunctionPriority")
.def(py::init<std::string, std::string>(),
py::arg("high"), py::arg("low"),
"Constructs a JunctionPriority with high and low priority road IDs")
.def_readwrite("high", &odr::JunctionPriority::high, "High priority road ID")
.def_readwrite("low", &odr::JunctionPriority::low, "Low priority road ID");

// Bind JunctionController
py::class_<odr::JunctionController>(m, "JunctionController")
.def(py::init<std::string, std::string, std::uint32_t>(),
py::arg("id"), py::arg("type"), py::arg("sequence"),
"Constructs a JunctionController with ID, type, and sequence")
.def_readwrite("id", &odr::JunctionController::id, "Controller ID")
.def_readwrite("type", &odr::JunctionController::type, "Controller type")
.def_readwrite("sequence", &odr::JunctionController::sequence, "Controller sequence number");

// Bind Junction
py::class_<odr::Junction>(m, "Junction")
.def(py::init<std::string, std::string>(),
py::arg("name"), py::arg("id"),
"Constructs a Junction with name and ID")
.def_readwrite("name", &odr::Junction::name, "Junction name")
.def_readwrite("id", &odr::Junction::id, "Junction ID")
.def_readwrite("id_to_connection", &odr::Junction::id_to_connection, "Map of connection IDs to JunctionConnection objects")
.def_readwrite("id_to_controller", &odr::Junction::id_to_controller, "Map of controller IDs to JunctionController objects")
.def_readwrite("priorities", &odr::Junction::priorities, "Set of JunctionPriority objects");
}
59 changes: 59 additions & 0 deletions bindings/lane.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,59 @@
#include <pybind11/pybind11.h>
#include <pybind11/stl.h>
#include <Lane.h>

namespace py = pybind11;

// Forward declarations for opaque types
namespace odr {
struct CubicSpline;
struct RoadMark;
struct RoadMarkGroup;
}

void init_lane(py::module_ &m) {
// Bind HeightOffset
py::class_<odr::HeightOffset>(m, "HeightOffset")
.def(py::init<double, double>(),
py::arg("inner"), py::arg("outer"),
"Constructs a HeightOffset with inner and outer offsets")
.def_readwrite("inner", &odr::HeightOffset::inner, "Inner height offset")
.def_readwrite("outer", &odr::HeightOffset::outer, "Outer height offset");

// Bind LaneKey
py::class_<odr::LaneKey>(m, "LaneKey")
.def(py::init<std::string, double, int>(),
py::arg("road_id"), py::arg("lanesection_s0"), py::arg("lane_id"),
"Constructs a LaneKey with road ID, lane section s0, and lane ID")
.def_readwrite("road_id", &odr::LaneKey::road_id, "Road ID")
.def_readwrite("lanesection_s0", &odr::LaneKey::lanesection_s0, "Lane section s0")
.def_readwrite("lane_id", &odr::LaneKey::lane_id, "Lane ID")
.def("to_string", &odr::LaneKey::to_string, "Returns a string representation of the LaneKey")
.def(" __eq__", [](const odr::LaneKey& a, const odr::LaneKey& b) { return a == b; }, "Equality comparison");

// Bind opaque types
py::class_<odr::CubicSpline>(m, "CubicSpline");

// Bind Lane
py::class_<odr::Lane>(m, "Lane")
.def(py::init<std::string, double, int, bool, std::string>(),
py::arg("road_id"), py::arg("lanesection_s0"), py::arg("id"),
py::arg("level"), py::arg("type"),
"Constructs a Lane with road ID, lane section s0, ID, level, and type")
.def_readwrite("key", &odr::Lane::key, "Lane key")
.def_readwrite("id", &odr::Lane::id, "Lane ID")
.def_readwrite("level", &odr::Lane::level, "Level flag")
.def_readwrite("predecessor", &odr::Lane::predecessor, "Predecessor lane ID")
.def_readwrite("successor", &odr::Lane::successor, "Successor lane ID")
.def_readwrite("type", &odr::Lane::type, "Lane type")
.def_readwrite("lane_width", &odr::Lane::lane_width, "Cubic spline for lane width")
.def_readwrite("outer_border", &odr::Lane::outer_border, "Cubic spline for outer border")
.def_readwrite("s_to_height_offset", &odr::Lane::s_to_height_offset,
"Map of s-coordinates to height offsets")
.def_readwrite("roadmark_groups", &odr::Lane::roadmark_groups,
"Set of road mark groups")
.def("get_roadmarks", &odr::Lane::get_roadmarks,
py::arg("s_start"), py::arg("s_end"),
py::return_value_policy::move,
"Returns road marks between s_start and s_end");
}
30 changes: 30 additions & 0 deletions bindings/lanesection.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@
#include <pybind11/pybind11.h>
#include <pybind11/stl.h>
#include <LaneSection.h>

namespace py = pybind11;

void init_lanesection(py::module_ &m) {
// Bind LaneSection
py::class_<odr::LaneSection>(m, "LaneSection")
.def(py::init<std::string, double>(),
py::arg("road_id"), py::arg("s0"),
"Constructs a LaneSection with road ID and start position s0")
.def_readwrite("road_id", &odr::LaneSection::road_id, "Road ID")
.def_readwrite("s0", &odr::LaneSection::s0, "Start position (s-coordinate)")
.def_readwrite("id_to_lane", &odr::LaneSection::id_to_lane, "Map of lane IDs to Lane objects")
.def("get_lanes", &odr::LaneSection::get_lanes,
py::return_value_policy::move,
"Returns a list of lanes")
.def("get_lane_id", &odr::LaneSection::get_lane_id,
py::arg("s"), py::arg("t"),
"Returns the lane ID at position (s, t), favoring the inner lane on boundaries")
.def("get_lane", py::overload_cast<int>(&odr::LaneSection::get_lane, py::const_),
py::arg("id"),
py::return_value_policy::copy,
"Returns the lane with the given ID")
.def("get_lane", py::overload_cast<double, double>(&odr::LaneSection::get_lane, py::const_),
py::arg("s"), py::arg("t"),
py::return_value_policy::copy,
"Returns the lane at position (s, t)");
}
15 changes: 15 additions & 0 deletions bindings/lanevalidityrecord.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
#include <pybind11/pybind11.h>
#include <pybind11/stl.h>
#include <LaneValidityRecord.h>

namespace py = pybind11;

void init_lanevalidityrecord(py::module_ &m) {
// Bind LaneValidityRecord
py::class_<odr::LaneValidityRecord>(m, "LaneValidityRecord")
.def(py::init<int, int>(),
py::arg("from_lane"), py::arg("to_lane"),
"Constructs a LaneValidityRecord with from_lane and to_lane")
.def_readwrite("from_lane", &odr::LaneValidityRecord::from_lane, "Starting lane ID")
.def_readwrite("to_lane", &odr::LaneValidityRecord::to_lane, "Ending lane ID");
}
Loading