diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 39ddd7a6..53037c09 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -30,7 +30,12 @@ jobs: # run tests on both mac and ubuntu, across all python versions test: runs-on: ${{ matrix.os }} + # We turn off stub generations, as there is some strange bug on github actions + # where an editable install with stubs obscures the _cpp.so module and it can't be imported + env: + SKBUILD_CMAKE_DEFINE: EVALIO_PYTHON_STUBS=OFF strategy: + fail-fast: false matrix: os: - ubuntu-latest @@ -48,7 +53,7 @@ jobs: python-version: ${{ matrix.python-version }} enable-cache: true - name: Install the project - run: uv sync --dev + run: uv sync --dev --verbose - name: Run tests run: uv run pytest -v @@ -62,12 +67,6 @@ jobs: steps: - uses: actions/checkout@v4 name: Checkout - # If things fail, this allows us to ssh in to fix things - # - name: Setup tmate session - # uses: mxschmitt/action-tmate@v3 - # if: runner.debug == '1' - # with: - # detached: true # Let vcpkg store caches in github actions - name: Export GitHub Actions cache environment variables diff --git a/CMakeLists.txt b/CMakeLists.txt index a6465689..899e6bc7 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -14,6 +14,15 @@ set(CMAKE_CXX_STANDARD 20) set(CMAKE_EXPORT_COMPILE_COMMANDS ON) include(FetchContent) +# Make build a release build unless otherwise specified +if(NOT CMAKE_BUILD_TYPE AND NOT CMAKE_CONFIGURATION_TYPES) + set(CMAKE_BUILD_TYPE Release CACHE STRING "Choose the type of build." FORCE) + set_property( + CACHE CMAKE_BUILD_TYPE + PROPERTY STRINGS "Debug" "Release" "MinSizeRel" "RelWithDebInfo" + ) +endif() + # ------------------------- Dependencies ------------------------- # # Pull eigen if it's not available already FetchContent_Declare( diff --git a/cpp/bindings/CMakeLists.txt b/cpp/bindings/CMakeLists.txt index d80a69f1..761d8f38 100644 --- a/cpp/bindings/CMakeLists.txt +++ b/cpp/bindings/CMakeLists.txt @@ -35,33 +35,49 @@ endif() message("###############################################################") # ------------------------- Make Python Bindings ------------------------- # -set(PYBIND11_FINDPYTHON ON) +find_package( + Python + 3.11 + REQUIRED + COMPONENTS Interpreter Development.Module + OPTIONAL_COMPONENTS Development.SABIModule +) + FetchContent_Declare( - pybind11 - GIT_REPOSITORY https://github.com/pybind/pybind11.git - GIT_TAG v2.13.6 - FIND_PACKAGE_ARGS # uses find_package first, git if it fails + nanobind + GIT_REPOSITORY https://github.com/wjakob/nanobind + GIT_TAG v2.7.0 + FIND_PACKAGE_ARGS + CONFIG # uses find_package first, git if it fails ) -FetchContent_MakeAvailable(pybind11) +FetchContent_MakeAvailable(nanobind) -pybind11_add_module(_cpp main.cpp) +# Add the Python module +nanobind_add_module(_cpp STABLE_ABI NB_STATIC main.cpp) target_link_libraries(_cpp PRIVATE ${LIBS}) target_compile_definitions(_cpp PRIVATE ${DEF}) install(TARGETS _cpp DESTINATION evalio) +# handle stubs +function(module_subs MOD FILE) + message(STATUS "Adding ${MOD} stubs") + nanobind_add_stub( + ${MOD}_stubs + INSTALL_TIME + MODULE evalio.${MOD} + OUTPUT evalio/_cpp/${FILE} # install directly to final location + PYTHON_PATH "." + ) +endfunction() + +# option for github actions +# see ci.yml +option(EVALIO_PYTHON_STUBS "Build Python bindings with stubs" ON) +if(EVALIO_PYTHON_STUBS) + module_subs(_cpp __init__.pyi) + module_subs(_cpp.pipelines pipelines.pyi) + module_subs(_cpp.types types.pyi) +endif() + # install licenses as well install(DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/../../licenses DESTINATION .) - -# Build stubs -# TODO: Something about this breaks python 3.12 and 3.13 builds -# add_custom_command( -# TARGET _cpp -# POST_BUILD -# COMMAND -# "${Python_EXECUTABLE}" -m pybind11_stubgen _cpp -o -# "${CMAKE_CURRENT_BINARY_DIR}" --numpy-array-wrap-with-annotated -# WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR} -# COMMENT "Generating pybind11 stubs" -# VERBATIM -# ) -# install(DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}/_cpp DESTINATION evalio) diff --git a/cpp/bindings/main.cpp b/cpp/bindings/main.cpp index 0596b415..83b7f0bd 100644 --- a/cpp/bindings/main.cpp +++ b/cpp/bindings/main.cpp @@ -1,14 +1,18 @@ -#include -#include -#include -#include +#include +#include "bindings/pipeline.h" #include "bindings/pipelines/bindings.h" #include "bindings/ros_pc2.h" #include "bindings/types.h" -#include "evalio/bindings.h" -PYBIND11_MODULE(_cpp, m) { +namespace nb = nanobind; + +NB_MODULE(_cpp, m) { + m.def( + "abi_tag", []() { return nb::detail::abi_tag(); }, + "Get the ABI tag of the current module. Useful for debugging when adding " + "external pipelines."); + auto m_types = m.def_submodule( "types", "Common types used for conversion between datasets and pipelines."); diff --git a/cpp/bindings/pipeline.h b/cpp/bindings/pipeline.h new file mode 100644 index 00000000..d15abd49 --- /dev/null +++ b/cpp/bindings/pipeline.h @@ -0,0 +1,68 @@ +#pragma once + +#include +#include +#include +#include +#include +#include +#include +#include + +#include "evalio/pipeline.h" + +namespace nb = nanobind; +using namespace nb::literals; + +namespace evalio { + +class PyPipeline : public evalio::Pipeline { +public: + NB_TRAMPOLINE(Pipeline, 9); + + // Getters + const evalio::SE3 pose() override { NB_OVERRIDE_PURE(pose); } + const std::vector map() override { NB_OVERRIDE_PURE(map); } + + // Setters + void set_imu_params(evalio::ImuParams params) override { + NB_OVERRIDE_PURE(set_imu_params, params); + } + void set_lidar_params(evalio::LidarParams params) override { + NB_OVERRIDE_PURE(set_lidar_params, params); + } + void set_imu_T_lidar(evalio::SE3 T) override { + NB_OVERRIDE_PURE(set_imu_T_lidar, T); + } + void set_params(std::map params) override { + NB_OVERRIDE_PURE(set_params, params); + } + + // Doers + void initialize() override { NB_OVERRIDE_PURE(initialize); } + void add_imu(evalio::ImuMeasurement mm) override { + NB_OVERRIDE_PURE(add_imu, mm); + } + std::vector add_lidar(evalio::LidarMeasurement mm) override { + NB_OVERRIDE_PURE(add_lidar, mm); + } +}; + +inline void makeBasePipeline(nb::module_ &m) { + nb::class_(m, "Pipeline") + .def(nb::init<>()) + .def_static("name", &evalio::Pipeline::name) + .def_static("url", &evalio::Pipeline::url) + .def_static("default_params", &evalio::Pipeline::default_params) + .def("pose", &evalio::Pipeline::pose) + .def("map", &evalio::Pipeline::map) + .def("initialize", &evalio::Pipeline::initialize) + .def("add_imu", &evalio::Pipeline::add_imu, "mm"_a) + .def("add_lidar", &evalio::Pipeline::add_lidar, "mm"_a) + .def("set_params", &evalio::Pipeline::set_params, "params"_a) + .def("set_imu_params", &evalio::Pipeline::set_imu_params, "params"_a) + .def("set_lidar_params", &evalio::Pipeline::set_lidar_params, "params"_a) + .def("set_imu_T_lidar", &evalio::Pipeline::set_imu_T_lidar, "T"_a); +} + +} // namespace evalio \ No newline at end of file diff --git a/cpp/bindings/pipelines/bindings.h b/cpp/bindings/pipelines/bindings.h index ad6fc5f5..69a8fd0c 100644 --- a/cpp/bindings/pipelines/bindings.h +++ b/cpp/bindings/pipelines/bindings.h @@ -1,14 +1,11 @@ #pragma once -#include -#include -#include -#include +#include #include "evalio/pipeline.h" -namespace py = pybind11; -using namespace pybind11::literals; +namespace nb = nanobind; +using namespace nb::literals; #ifdef EVALIO_KISS_ICP #include "bindings/pipelines/kiss_icp.h" @@ -19,11 +16,11 @@ using namespace pybind11::literals; #endif namespace evalio { -inline void makePipelines(py::module &m) { +inline void makePipelines(nb::module_ &m) { // List all the pipelines here #ifdef EVALIO_KISS_ICP - py::class_(m, "KissICP") - .def(py::init<>()) + nb::class_(m, "KissICP") + .def(nb::init<>()) .def_static("name", &KissICP::name) .def_static("url", &KissICP::url) .def_static("default_params", &KissICP::default_params); @@ -31,8 +28,8 @@ inline void makePipelines(py::module &m) { #endif #ifdef EVALIO_LIO_SAM - py::class_(m, "LioSAM") - .def(py::init<>()) + nb::class_(m, "LioSAM") + .def(nb::init<>()) .def_static("name", &LioSam::name) .def_static("url", &LioSam::url) .def_static("default_params", &LioSam::default_params); diff --git a/cpp/bindings/ros_pc2.h b/cpp/bindings/ros_pc2.h index 9ef2f4d3..2a86d79f 100644 --- a/cpp/bindings/ros_pc2.h +++ b/cpp/bindings/ros_pc2.h @@ -1,17 +1,18 @@ #pragma once #include #include -#include -#include -#include -#include +#include +#include +#include +#include +#include #include #include "evalio/types.h" -namespace py = pybind11; -using namespace pybind11::literals; +namespace nb = nanobind; +using namespace nb::literals; namespace evalio { @@ -363,8 +364,8 @@ inline LidarMeasurement helipr_bin_to_evalio(const std::string &filename, } // ---------------------- Create python bindings ---------------------- // -inline void makeConversions(py::module &m) { - py::enum_(m, "DataType") +inline void makeConversions(nb::module_ &m) { + nb::enum_(m, "DataType") .value("UINT8", DataType::UINT8) .value("INT8", DataType::INT8) .value("UINT16", DataType::UINT16) @@ -374,29 +375,31 @@ inline void makeConversions(py::module &m) { .value("FLOAT32", DataType::FLOAT32) .value("FLOAT64", DataType::FLOAT64); - py::class_(m, "Field") - .def(py::init(), py::kw_only(), "name"_a, + nb::class_(m, "Field") + .def(nb::init(), nb::kw_only(), "name"_a, "datatype"_a, "offset"_a) - .def_readwrite("name", &Field::name) - .def_readwrite("datatype", &Field::datatype) - .def_readwrite("offset", &Field::offset); + .def_rw("name", &Field::name) + .def_rw("datatype", &Field::datatype) + .def_rw("offset", &Field::offset); - py::class_(m, "PointCloudMetadata") - .def(py::init(), - py::kw_only(), "stamp"_a, "width"_a, "height"_a, "point_step"_a, + nb::class_(m, "PointCloudMetadata") + .def(nb::init(), + nb::kw_only(), "stamp"_a, "width"_a, "height"_a, "point_step"_a, "row_step"_a, "is_bigendian"_a, "is_dense"_a) - .def_readwrite("stamp", &PointCloudMetadata::stamp) - .def_readwrite("width", &PointCloudMetadata::width) - .def_readwrite("height", &PointCloudMetadata::height) - .def_readwrite("point_step", &PointCloudMetadata::point_step) - .def_readwrite("row_step", &PointCloudMetadata::row_step) - .def_readwrite("is_bigendian", &PointCloudMetadata::is_bigendian) - .def_readwrite("is_dense", &PointCloudMetadata::is_dense); - - m.def("pc2_to_evalio", [](const PointCloudMetadata &msg, - const std::vector &fields, char *c) { - return pc2_to_evalio(msg, fields, reinterpret_cast(c)); - }); + .def_rw("stamp", &PointCloudMetadata::stamp) + .def_rw("width", &PointCloudMetadata::width) + .def_rw("height", &PointCloudMetadata::height) + .def_rw("point_step", &PointCloudMetadata::point_step) + .def_rw("row_step", &PointCloudMetadata::row_step) + .def_rw("is_bigendian", &PointCloudMetadata::is_bigendian) + .def_rw("is_dense", &PointCloudMetadata::is_dense); + + m.def("pc2_to_evalio", + [](const PointCloudMetadata &msg, const std::vector &fields, + nb::bytes c) -> evalio::LidarMeasurement { + return pc2_to_evalio(msg, fields, + reinterpret_cast(c.c_str())); + }); m.def("fill_col_row_major", &fill_col_row_major); m.def("fill_col_col_major", &fill_col_col_major); diff --git a/cpp/bindings/types.h b/cpp/bindings/types.h index 41b18a8a..7ad51535 100644 --- a/cpp/bindings/types.h +++ b/cpp/bindings/types.h @@ -1,208 +1,187 @@ #pragma once #include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include #include "evalio/types.h" -namespace py = pybind11; -using namespace pybind11::literals; +namespace nb = nanobind; +using namespace nb::literals; namespace evalio { -inline void makeTypes(py::module &m) { - py::class_(m, "Duration") - .def(py::init(), py::kw_only(), "sec"_a) +// TODO: Check if copy/deepcopy works or not + +inline void makeTypes(nb::module_ &m) { + nb::class_(m, "Duration") .def_static("from_sec", &Duration::from_sec) .def_static("from_nsec", &Duration::from_nsec) .def("to_sec", &Duration::to_sec) .def("to_nsec", &Duration::to_nsec) - .def_readonly("nsec", &Duration::nsec) - .def(py::self < py::self) - .def(py::self > py::self) - .def(py::self == py::self) - .def(py::self != py::self) - .def(py::self - py::self) - .def(py::self + py::self) + .def_ro("nsec", &Duration::nsec) + .def(nb::self < nb::self) + .def(nb::self > nb::self) + .def(nb::self == nb::self) + .def(nb::self != nb::self) + .def(nb::self - nb::self) + .def(nb::self + nb::self) .def("__repr__", &Duration::toString) .def("__copy__", [](const Duration &self) { return Duration(self); }) .def( "__deepcopy__", - [](const Duration &self, py::dict) { return Duration(self); }, + [](const Duration &self, nb::dict) { return Duration(self); }, "memo"_a) - .def(py::pickle( - [](const Duration &p) { // __getstate__ - /* Return a tuple that fully encodes the state of the object */ - return py::make_tuple(p.nsec); - }, - [](py::tuple t) { // __setstate__ - if (t.size() != 1) - throw std::runtime_error("Invalid state when unpickling Stamp!"); - /* Create a new C++ instance */ - Duration p{.nsec = t[0].cast()}; - return p; - })); + .def("__getstate__", + [](const Duration &p) { return nb::make_tuple(p.nsec); }) + .def("__setstate__", [](Duration &p, std::tuple t) { + new (&p) Duration{.nsec = std::get<0>(t)}; + }); - py::class_(m, "Stamp") - .def(py::init(), py::kw_only(), "sec"_a, "nsec"_a) + nb::class_(m, "Stamp") + .def(nb::init(), nb::kw_only(), "sec"_a, "nsec"_a) .def_static("from_sec", &Stamp::from_sec) .def_static("from_nsec", &Stamp::from_nsec) .def("to_sec", &Stamp::to_sec) .def("to_nsec", &Stamp::to_nsec) - .def_readonly("sec", &Stamp::sec) - .def_readonly("nsec", &Stamp::nsec) - .def(py::self < py::self) - .def(py::self > py::self) - .def(py::self == py::self) - .def(py::self != py::self) - .def(py::self - py::self) - .def(py::self + Duration()) - .def(py::self - Duration()) + .def_ro("sec", &Stamp::sec) + .def_ro("nsec", &Stamp::nsec) + .def(nb::self < nb::self) + .def(nb::self > nb::self) + .def(nb::self == nb::self) + .def(nb::self != nb::self) + .def(nb::self - nb::self) + .def(nb::self + Duration()) + .def(nb::self - Duration()) .def("__repr__", &Stamp::toString) .def("__copy__", [](const Stamp &self) { return Stamp(self); }) .def( "__deepcopy__", - [](const Stamp &self, py::dict) { return Stamp(self); }, "memo"_a) - .def(py::pickle( - [](const Stamp &p) { // __getstate__ - /* Return a tuple that fully encodes the state of the object */ - return py::make_tuple(p.sec, p.nsec); - }, - [](py::tuple t) { // __setstate__ - if (t.size() != 2) - throw std::runtime_error("Invalid state when unpickling Stamp!"); - /* Create a new C++ instance */ - Stamp p{.sec = t[0].cast(), - .nsec = t[1].cast()}; - return p; - })); + [](const Stamp &self, nb::dict) { return Stamp(self); }, "memo"_a) + .def("__getstate__", + [](const Stamp &p) { return nb::make_tuple(p.sec, p.nsec); }) + .def("__setstate__", [](Stamp &p, std::tuple t) { + new (&p) Stamp{.sec = std::get<0>(t), .nsec = std::get<1>(t)}; + }); + ; // Lidar - py::class_(m, "Point") - .def(py::init(m, "Point") + .def(nb::init(), - py::kw_only(), "x"_a = 0, "y"_a = 0, "z"_a = 0, "intensity"_a = 0, + nb::kw_only(), "x"_a = 0, "y"_a = 0, "z"_a = 0, "intensity"_a = 0, "t"_a = Duration::from_sec(0.0), "range"_a = 0, "row"_a = 0, "col"_a = 0) - .def_readwrite("x", &Point::x) - .def_readwrite("y", &Point::y) - .def_readwrite("z", &Point::z) - .def_readwrite("intensity", &Point::intensity) - .def_readwrite("range", &Point::range) - .def_readwrite("t", &Point::t) - .def_readwrite("row", &Point::row) - .def_readwrite("col", &Point::col) - .def(py::self == py::self) - .def(py::self != py::self) + .def_rw("x", &Point::x) + .def_rw("y", &Point::y) + .def_rw("z", &Point::z) + .def_rw("intensity", &Point::intensity) + .def_rw("range", &Point::range) + .def_rw("t", &Point::t) + .def_rw("row", &Point::row) + .def_rw("col", &Point::col) + .def(nb::self == nb::self) + .def(nb::self != nb::self) .def("__repr__", &Point::toString) - .def(py::pickle( - [](const Point &p) { // __getstate__ - /* Return a tuple that fully encodes the state of the object */ - return py::make_tuple(p.x, p.y, p.z, p.intensity, p.t, p.range, - p.row, p.col); - }, - [](py::tuple t) { // __setstate__ - if (t.size() != 8) - throw std::runtime_error("Invalid state when unpickling Point!"); - /* Create a new C++ instance */ - return Point{.x = t[0].cast(), - .y = t[1].cast(), - .z = t[2].cast(), - .intensity = t[3].cast(), - .t = t[4].cast(), - .range = t[5].cast(), - .row = t[6].cast(), - .col = t[7].cast()}; - })); - ; + .def("__getstate__", + [](const Point &p) { + return std::make_tuple(p.x, p.y, p.z, p.intensity, p.t, p.range, + p.row, p.col); + }) + .def("__setstate__", + [](Point &p, std::tuple + t) { + new (&p) Point{.x = std::get<0>(t), + .y = std::get<1>(t), + .z = std::get<2>(t), + .intensity = std::get<3>(t), + .t = std::get<4>(t), + .range = std::get<5>(t), + .row = std::get<6>(t), + .col = std::get<7>(t)}; + }); - py::class_(m, "LidarMeasurement") - .def(py::init(), "stamp"_a) - .def(py::init>(), "stamp"_a, "points"_a) - .def_readwrite("stamp", &LidarMeasurement::stamp) - .def_readwrite("points", &LidarMeasurement::points) + nb::class_(m, "LidarMeasurement") + .def(nb::init(), "stamp"_a) + .def(nb::init>(), "stamp"_a, "points"_a) + .def_rw("stamp", &LidarMeasurement::stamp) + .def_rw("points", &LidarMeasurement::points) .def("to_vec_positions", &LidarMeasurement::to_vec_positions) .def("to_vec_stamps", &LidarMeasurement::to_vec_stamps) - .def(py::self == py::self) - .def(py::self != py::self) + .def(nb::self == nb::self) + .def(nb::self != nb::self) .def("__repr__", &LidarMeasurement::toString) - .def(py::pickle( - [](const LidarMeasurement &p) { // __getstate__ - /* Return a tuple that fully encodes the state of the object */ - return py::make_tuple(p.stamp, p.points); - }, - [](py::tuple t) { // __setstate__ - if (t.size() != 2) - throw std::runtime_error( - "Invalid state when unpickling LidarMeasurement!"); - /* Create a new C++ instance */ - return LidarMeasurement(t[0].cast(), - t[1].cast>()); - })); + .def("__getstate__", + [](const LidarMeasurement &p) { + return std::make_tuple(p.stamp, p.points); + }) + .def("__setstate__", + [](LidarMeasurement &p, std::tuple> t) { + new (&p) LidarMeasurement(std::get<0>(t), std::get<1>(t)); + }); - py::class_(m, "LidarParams") - .def(py::init(), py::kw_only(), + nb::class_(m, "LidarParams") + .def(nb::init(), nb::kw_only(), "num_rows"_a, "num_columns"_a, "min_range"_a, "max_range"_a, "rate"_a = 10.0) - .def_readonly("num_rows", &LidarParams::num_rows) - .def_readonly("num_columns", &LidarParams::num_columns) - .def_readonly("min_range", &LidarParams::min_range) - .def_readonly("max_range", &LidarParams::max_range) - .def_readonly("rate", &LidarParams::rate) + .def_ro("num_rows", &LidarParams::num_rows) + .def_ro("num_columns", &LidarParams::num_columns) + .def_ro("min_range", &LidarParams::min_range) + .def_ro("max_range", &LidarParams::max_range) + .def_ro("rate", &LidarParams::rate) .def("delta_time", &LidarParams::delta_time) .def("__repr__", &LidarParams::toString); // Imu - py::class_(m, "ImuMeasurement") - .def(py::init(), "stamp"_a, + nb::class_(m, "ImuMeasurement") + .def(nb::init(), "stamp"_a, "gyro"_a, "accel"_a) - .def_readonly("stamp", &ImuMeasurement::stamp) - .def_readonly("gyro", &ImuMeasurement::gyro) - .def_readonly("accel", &ImuMeasurement::accel) - .def(py::self == py::self) - .def(py::self != py::self) + .def_ro("stamp", &ImuMeasurement::stamp) + .def_ro("gyro", &ImuMeasurement::gyro) + .def_ro("accel", &ImuMeasurement::accel) + .def(nb::self == nb::self) + .def(nb::self != nb::self) .def("__repr__", &ImuMeasurement::toString) - .def(py::pickle( - [](const ImuMeasurement &p) { // __getstate__ - /* Return a tuple that fully encodes the state of the object */ - return py::make_tuple(p.stamp, p.gyro, p.accel); - }, - [](py::tuple t) { // __setstate__ - if (t.size() != 3) - throw std::runtime_error( - "Invalid state when unpickling ImuMeasurement!"); - /* Create a new C++ instance */ - return ImuMeasurement{.stamp = t[0].cast(), - .gyro = t[1].cast(), - .accel = t[2].cast()}; - })); + .def("__getstate__", + [](const ImuMeasurement &p) { + return std::make_tuple(p.stamp, p.gyro, p.accel); + }) + .def("__setstate__", + [](ImuMeasurement &p, + std::tuple t) { + new (&p) ImuMeasurement{.stamp = std::get<0>(t), + .gyro = std::get<1>(t), + .accel = std::get<2>(t)}; + }); - py::class_(m, "ImuParams") - .def(py::init(m, "ImuParams") + .def(nb::init(), - py::kw_only(), "gyro"_a = 1e-5, "accel"_a = 1e-5, + nb::kw_only(), "gyro"_a = 1e-5, "accel"_a = 1e-5, "gyro_bias"_a = 1e-6, "accel_bias"_a = 1e-6, "bias_init"_a = 1e-7, "integration"_a = 1e-7, "gravity"_a = Eigen::Vector3d(0, 0, 9.81)) .def_static("up", &ImuParams::up) .def_static("down", &ImuParams::down) - .def_readwrite("gyro", &ImuParams::gyro) - .def_readwrite("accel", &ImuParams::accel) - .def_readwrite("gyro_bias", &ImuParams::gyro_bias) - .def_readwrite("accel_bias", &ImuParams::accel_bias) - .def_readwrite("bias_init", &ImuParams::bias_init) - .def_readwrite("integration", &ImuParams::integration) - .def_readwrite("gravity", &ImuParams::gravity) + .def_rw("gyro", &ImuParams::gyro) + .def_rw("accel", &ImuParams::accel) + .def_rw("gyro_bias", &ImuParams::gyro_bias) + .def_rw("accel_bias", &ImuParams::accel_bias) + .def_rw("bias_init", &ImuParams::bias_init) + .def_rw("integration", &ImuParams::integration) + .def_rw("gravity", &ImuParams::gravity) .def("__repr__", &ImuParams::toString); - py::class_(m, "SO3") - .def(py::init(), py::kw_only(), "qx"_a, + nb::class_(m, "SO3") + .def(nb::init(), nb::kw_only(), "qx"_a, "qy"_a, "qz"_a, "qw"_a) - .def_readonly("qx", &SO3::qx) - .def_readonly("qy", &SO3::qy) - .def_readonly("qz", &SO3::qz) - .def_readonly("qw", &SO3::qw) + .def_ro("qx", &SO3::qx) + .def_ro("qy", &SO3::qy) + .def_ro("qz", &SO3::qz) + .def_ro("qw", &SO3::qw) .def_static("identity", &SO3::identity) .def_static("fromMat", &SO3::fromMat) .def_static("exp", &SO3::exp) @@ -210,48 +189,43 @@ inline void makeTypes(py::module &m) { .def("log", &SO3::log) .def("toMat", &SO3::toMat) .def("rotate", &SO3::rotate) - .def(py::self * py::self) + .def(nb::self * nb::self) .def("__repr__", &SO3::toString) .def("__copy__", [](const SO3 &self) { return SO3(self); }) .def( - "__deepcopy__", [](const SO3 &self, py::dict) { return SO3(self); }, + "__deepcopy__", [](const SO3 &self, nb::dict) { return SO3(self); }, "memo"_a); - py::class_(m, "SE3") - .def(py::init(), "rot"_a, "trans"_a) + nb::class_(m, "SE3") + .def(nb::init(), "rot"_a, "trans"_a) .def_static("identity", &SE3::identity) .def_static("fromMat", &SE3::fromMat) - .def_readonly("rot", &SE3::rot) - .def_readonly("trans", &SE3::trans) + .def_ro("rot", &SE3::rot) + .def_ro("trans", &SE3::trans) .def("toMat", &SE3::toMat) .def("inverse", &SE3::inverse) - .def(py::self * py::self) + .def(nb::self * nb::self) .def("__repr__", &SE3::toString) .def("__copy__", [](const SE3 &self) { return SE3(self); }) .def( - "__deepcopy__", [](const SE3 &self, py::dict) { return SE3(self); }, + "__deepcopy__", [](const SE3 &self, nb::dict) { return SE3(self); }, "memo"_a) - .def(py::pickle( - [](const SE3 &p) { // __getstate__ - /* Return a tuple that fully encodes the state of the object */ - return py::make_tuple(p.rot.qx, p.rot.qy, p.rot.qz, p.rot.qw, - p.trans[0], p.trans[1], p.trans[2]); - }, - [](py::tuple t) { // __setstate__ - if (t.size() != 7) - throw std::runtime_error("Invalid state when unpickling SE3!"); - /* Create a new C++ instance */ - double qx = t[0].cast(); - double qy = t[1].cast(); - double qz = t[2].cast(); - double qw = t[3].cast(); - double x = t[4].cast(); - double y = t[5].cast(); - double z = t[6].cast(); - SE3 p(SO3{.qx = qx, .qy = qy, .qz = qz, .qw = qw}, - Eigen::Vector3d(x, y, z)); - return p; - })); + .def("__getstate__", + [](const SE3 &p) { + return nb::make_tuple(p.rot.qx, p.rot.qy, p.rot.qz, p.rot.qw, + p.trans[0], p.trans[1], p.trans[2]); + }) + .def("__setstate__", + [](SE3 &p, + std::tuple + t) { + new (&p) SE3(SO3{.qx = std::get<0>(t), + .qy = std::get<1>(t), + .qz = std::get<2>(t), + .qw = std::get<3>(t)}, + Eigen::Vector3d{std::get<4>(t), std::get<5>(t), + std::get<6>(t)}); + }); } } // namespace evalio \ No newline at end of file diff --git a/cpp/evalio/bindings.h b/cpp/evalio/bindings.h deleted file mode 100644 index 2a511502..00000000 --- a/cpp/evalio/bindings.h +++ /dev/null @@ -1,85 +0,0 @@ -#pragma once - -#include -#include -#include -#include - -#include "evalio/pipeline.h" - -namespace py = pybind11; -using namespace pybind11::literals; - -namespace evalio { - -class PyPipeline : public evalio::Pipeline { -public: - using evalio::Pipeline::Pipeline; - - // Getters - const evalio::SE3 pose() override { - PYBIND11_OVERRIDE_PURE(const evalio::SE3, evalio::Pipeline, pose); - } - const std::vector map() override { - PYBIND11_OVERRIDE_PURE(const std::vector, evalio::Pipeline, - map); - } - - // Setters - void set_imu_params(evalio::ImuParams params) override { - PYBIND11_OVERRIDE_PURE(void, evalio::Pipeline, set_imu_params, params); - } - void set_lidar_params(evalio::LidarParams params) override { - PYBIND11_OVERRIDE_PURE(void, evalio::Pipeline, set_lidar_params, params); - } - void set_imu_T_lidar(evalio::SE3 T) override { - PYBIND11_OVERRIDE_PURE(void, evalio::Pipeline, set_imu_T_lidar, T); - } - void set_params(std::map params) override { - PYBIND11_OVERRIDE_PURE(void, evalio::Pipeline, set_params, params); - } - - // Doers - void initialize() override { - PYBIND11_OVERRIDE_PURE(void, evalio::Pipeline, initialize); - } - void add_imu(evalio::ImuMeasurement mm) override { - PYBIND11_OVERRIDE_PURE(void, evalio::Pipeline, add_imu, mm); - } - std::vector add_lidar(evalio::LidarMeasurement mm) override { - PYBIND11_OVERRIDE_PURE(std::vector, evalio::Pipeline, add_lidar, mm); - } -}; - -inline void makeBasePipeline(py::module &m) { - py::class_(m, "Pipeline") - .def(py::init<>()) - .def_static("name", &evalio::Pipeline::name) - .def_static("url", &evalio::Pipeline::url) - .def_static("default_params", &evalio::Pipeline::default_params) - .def("pose", &evalio::Pipeline::pose) - .def("map", &evalio::Pipeline::map) - .def("initialize", &evalio::Pipeline::initialize) - .def("add_imu", &evalio::Pipeline::add_imu, "mm"_a) - .def("add_lidar", &evalio::Pipeline::add_lidar, "mm"_a) - .def("set_params", &evalio::Pipeline::set_params, "params"_a) - .def("set_imu_params", &evalio::Pipeline::set_imu_params, "params"_a) - .def("set_lidar_params", &evalio::Pipeline::set_lidar_params, "params"_a) - .def("set_imu_T_lidar", &evalio::Pipeline::set_imu_T_lidar, "T"_a); -} - -inline void setup(py::module &m) { - // NOTE: typeid are not guaranteed to be unique across building from different - // compilers - // https://github.com/pybind/pybind11/issues/877#issuecomment-304464896 - // Ideally, if built using the same compiler as evalio (unlikely), this should - // work import the original wrapper for Pipeline - py::module evalio = py::module::import("evalio"); - // Otherwise, build a new pipeline base class - // This should be fine, as pipelines are all exclusively used in python - if (py::detail::get_type_info(typeid(evalio::Pipeline)) == nullptr) { - evalio::makeBasePipeline(m); - }; -} - -} // namespace evalio \ No newline at end of file diff --git a/cpp/evalio/types.h b/cpp/evalio/types.h index 5a563251..b4b8a916 100644 --- a/cpp/evalio/types.h +++ b/cpp/evalio/types.h @@ -31,7 +31,6 @@ struct Duration { bool operator>(const Duration &other) const { return nsec > other.nsec; } - // Check equality using nsec to avoid floating point error bool operator==(const Duration &other) const { return nsec == other.nsec; } bool operator!=(const Duration &other) const { return !(*this == other); } diff --git a/justfile b/justfile index 4a1b13b8..4e7741f0 100644 --- a/justfile +++ b/justfile @@ -1,10 +1,10 @@ pybuild: touch pyproject.toml uv --verbose sync --all-extras - uv run pybind11-stubgen --numpy-array-wrap-with-annotated evalio._cpp -o python --ignore-all-errors + cp -r .venv/lib/python3.12/site-packages/evalio/_cpp python/evalio stubs: - uv run pybind11-stubgen --numpy-array-wrap-with-annotated evalio._cpp -o python --ignore-all-errors + cp -r .venv/lib/python3.12/site-packages/evalio/_cpp python/evalio bump-minor: uv run bump-my-version minor diff --git a/pyproject.toml b/pyproject.toml index 1973042b..c0e369dd 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -30,7 +30,7 @@ license = { file = "LICENSE.txt" } vis = ["rerun-sdk>=0.18.2"] [build-system] -requires = ["scikit-build-core>=0.8", "pybind11", "pybind11-stubgen", "numpy"] +requires = ["scikit-build-core>=0.8", "nanobind>=2.7.0", "numpy"] build-backend = "scikit_build_core.build" [project.scripts] @@ -45,7 +45,6 @@ sdist.include = ["cpp/bindings/pipelines-src/*"] [tool.scikit-build.cmake.define] EVALIO_BUILD_PYTHON = true -CMAKE_BUILD_TYPE = "Release" VCPKG_INSTALLED_DIR = "./.vcpkg_installed" # VCPKG_INSTALL_OPTIONS = "--debug" @@ -69,7 +68,6 @@ MACOSX_DEPLOYMENT_TARGET = "11" dev-dependencies = [ "cmake>=3.30.3", "compdb>=0.2.0", - "pybind11-stubgen>=2.5.1", "ruff>=0.6.8", "types-pyyaml>=6.0.12.20240917", "types-tabulate>=0.9.0.20240106", @@ -78,6 +76,7 @@ dev-dependencies = [ "scipy>=1.15.2", "scipy-stubs>=1.15.2.1", "bump-my-version>=1.1.1", + "nanobind>=2.7.0", ] [tool.ruff] diff --git a/python/evalio/__init__.py b/python/evalio/__init__.py index 4c232edd..48154678 100644 --- a/python/evalio/__init__.py +++ b/python/evalio/__init__.py @@ -1,7 +1,23 @@ from . import _cpp, datasets, pipelines, types, utils +from ._cpp import abi_tag as _abi_tag + +# remove false nanobind reference leak warnings +# https://github.com/wjakob/nanobind/discussions/13 +import atexit + + +def cleanup(): + import typing + + for cleanup in typing._cleanups: # type: ignore + cleanup() + + +atexit.register(cleanup) __version__ = "0.2.0" __all__ = [ + "_abi_tag", "datasets", "_cpp", "pipelines", diff --git a/uv.lock b/uv.lock index bedf4b72..13416dc8 100644 --- a/uv.lock +++ b/uv.lock @@ -244,7 +244,7 @@ wheels = [ [[package]] name = "evalio" -version = "0.1.1" +version = "0.2.0" source = { editable = "." } dependencies = [ { name = "argcomplete" }, @@ -267,7 +267,7 @@ dev = [ { name = "bump-my-version" }, { name = "cmake" }, { name = "compdb" }, - { name = "pybind11-stubgen" }, + { name = "nanobind" }, { name = "pytest" }, { name = "ruff" }, { name = "scipy" }, @@ -295,7 +295,7 @@ dev = [ { name = "bump-my-version", specifier = ">=1.1.1" }, { name = "cmake", specifier = ">=3.30.3" }, { name = "compdb", specifier = ">=0.2.0" }, - { name = "pybind11-stubgen", specifier = ">=2.5.1" }, + { name = "nanobind", specifier = ">=2.7.0" }, { name = "pytest", specifier = ">=8.3.5" }, { name = "ruff", specifier = ">=0.6.8" }, { name = "scipy", specifier = ">=1.15.2" }, @@ -431,6 +431,15 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/b3/38/89ba8ad64ae25be8de66a6d463314cf1eb366222074cfda9ee839c56a4b4/mdurl-0.1.2-py3-none-any.whl", hash = "sha256:84008a41e51615a49fc9966191ff91509e3c40b939176e643fd50a5c2196b8f8", size = 9979 }, ] +[[package]] +name = "nanobind" +version = "2.7.0" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/d8/7d/f77f2bc2e2a210502a164556f8a742cd0f72f39061b97cb9d73bbd3ff0ab/nanobind-2.7.0.tar.gz", hash = "sha256:f9f1b160580c50dcf37b6495a0fd5ec61dc0d95dae5f8004f87dd9ad7eb46b34", size = 976093 } +wheels = [ + { url = "https://files.pythonhosted.org/packages/96/14/989883082b395146120d34ca7e484a2b24cb73b0e428576a3a4249bd4082/nanobind-2.7.0-py3-none-any.whl", hash = "sha256:73b12d0e751d140d6c1bf4b215e18818a8debfdb374f08dc3776ad208d808e74", size = 241690 }, +] + [[package]] name = "numpy" version = "2.2.4" @@ -605,15 +614,6 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/ed/bd/54907846383dcc7ee28772d7e646f6c34276a17da740002a5cefe90f04f7/pyarrow-19.0.1-cp313-cp313t-manylinux_2_28_x86_64.whl", hash = "sha256:58d9397b2e273ef76264b45531e9d552d8ec8a6688b7390b5be44c02a37aade8", size = 42085744 }, ] -[[package]] -name = "pybind11-stubgen" -version = "2.5.3" -source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/67/c6/2c695a3f94a9dfa1920a40dc6b36e9d4d0e1ac089b7e35d7237a29f4c400/pybind11_stubgen-2.5.3.tar.gz", hash = "sha256:72d6122749ed95dfcdd121cc3b8f493cbadb4755f38a0682e2265b5a041c25cb", size = 24756 } -wheels = [ - { url = "https://files.pythonhosted.org/packages/cd/c3/fb2e68bf0b0bb1c233854f4f9ad7c388c7497d80a60597efc1640356ab7a/pybind11_stubgen-2.5.3-py3-none-any.whl", hash = "sha256:7c6a642027e5dcb6a734822cac0cc8600ceadccd9b0339e1fab0da632c3de0fa", size = 29894 }, -] - [[package]] name = "pycparser" version = "2.22"