diff --git a/.github/workflows/pybind.yml b/.github/workflows/pybind.yml index 42f15068..32fca984 100644 --- a/.github/workflows/pybind.yml +++ b/.github/workflows/pybind.yml @@ -12,7 +12,7 @@ jobs: runs-on: ${{ matrix.os }} strategy: matrix: - os: [ubuntu-20.04, macos-13] + os: [ubuntu-22.04, macos-13] fail-fast: false steps: @@ -33,7 +33,7 @@ jobs: sudo apt install -y libunwind-dev # Generic dependencies - sudo apt-get install cmake + sudo apt-get install cmake libeigen3-dev libfmt-dev # Clean APT cache sudo apt-get clean @@ -42,7 +42,7 @@ jobs: # Install system deps with Homebrew brew install cmake # VRS dependencies - brew install fmt lz4 zstd xxhash + brew install eigen fmt lz4 zstd xxhash else echo "$RUNNER_OS not supported" exit 1 diff --git a/CMakeLists.txt b/CMakeLists.txt index 9dfc48f8..ebe479a3 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -111,6 +111,9 @@ endif() # Build python sophus bindings option(BUILD_PYTHON_BINDINGS "Build python sophus bindings." OFF) if(BUILD_PYTHON_BINDINGS) + if(NOT TARGET fmt::fmt) + find_package(fmt REQUIRED) + endif() include(FetchContent) FetchContent_Declare( pybind11 @@ -121,7 +124,7 @@ if(BUILD_PYTHON_BINDINGS) add_subdirectory(${pybind11_SOURCE_DIR} ${CMAKE_CURRENT_BINARY_DIR}/pybind) pybind11_add_module(sophus_pybind ${CMAKE_CURRENT_SOURCE_DIR}/sophus_pybind/bindings.cpp) - target_link_libraries(sophus_pybind PUBLIC sophus) + target_link_libraries(sophus_pybind PUBLIC sophus fmt::fmt) endif(BUILD_PYTHON_BINDINGS) if(SOPHUS_INSTALL) diff --git a/setup.py b/setup.py index 05bf4db8..d030bee4 100644 --- a/setup.py +++ b/setup.py @@ -43,7 +43,6 @@ def build_extension(self, ext): cmake_args = [ "-DBUILD_PYTHON_BINDINGS=ON", - "-DBUILD_SOPHUS_EXAMPLES=OFF", "-DBUILD_SOPHUS_TESTS=OFF", ] build_args = [] diff --git a/sophus/average.hpp b/sophus/average.hpp index 8bbe5571..f10558a0 100644 --- a/sophus/average.hpp +++ b/sophus/average.hpp @@ -5,6 +5,8 @@ #include +#include + #include "cartesian.hpp" #include "common.hpp" #include "rxso2.hpp" diff --git a/sophus_pybind/SE3PyBind.h b/sophus_pybind/SE3PyBind.h index cca162d1..1b3d5bf1 100644 --- a/sophus_pybind/SE3PyBind.h +++ b/sophus_pybind/SE3PyBind.h @@ -42,7 +42,7 @@ struct type_caster> { PYBIND11_TYPE_CASTER(Sophus::SE3, _("SE3")); // converting from python -> c++ type - bool load(handle src, bool convert) { + bool load(handle src, bool /*convert*/) { try { Sophus::SE3Group& ref = src.cast&>(); if (ref.size() != 1) { @@ -103,7 +103,7 @@ PybindSE3Type exportSE3Transformation(pybind11::module& module, SE3Group output; output.reserve(matrices.shape(0)); - for (size_t i = 0; i < matrices.shape(0); ++i) { + for (int i = 0; i < matrices.shape(0); ++i) { Eigen::Map> mat( matrices.data(i, 0, 0)); output.push_back(Sophus::SE3::fitToSE3(mat)); @@ -129,7 +129,7 @@ PybindSE3Type exportSE3Transformation(pybind11::module& module, SE3Group output; output.reserve(matrices.shape(0)); - for (size_t i = 0; i < matrices.shape(0); ++i) { + for (int i = 0; i < matrices.shape(0); ++i) { Eigen::Map> mat( matrices.data(i, 0, 0)); output.push_back(Sophus::SE3( @@ -161,7 +161,7 @@ PybindSE3Type exportSE3Transformation(pybind11::module& module, -> SE3Group { SE3Group output; output.reserve(rotvecs.rows()); - for (size_t i = 0; i < rotvecs.rows(); ++i) { + for (int i = 0; i < rotvecs.rows(); ++i) { auto tangentVec = Eigen::Matrix{translational_parts(i, 0), translational_parts(i, 1), @@ -192,8 +192,8 @@ PybindSE3Type exportSE3Transformation(pybind11::module& module, [](const std::vector& x_vec, const Eigen::Matrix& xyz_vec, const Eigen::Matrix& translations) -> SE3Group { - if (x_vec.size() != xyz_vec.rows() || - x_vec.size() != translations.rows()) { + if (int(x_vec.size()) != xyz_vec.rows() || + int(x_vec.size()) != translations.rows()) { throw std::domain_error( fmt::format("Size of the input variables are not the same: x_vec " "= {}, xyz_vec = {}, translation = {}", @@ -413,7 +413,7 @@ PybindSE3Type exportSE3Transformation(pybind11::module& module, } Eigen::Matrix result(3, matrix.cols()); - for (size_t i = 0; i < matrix.cols(); ++i) { + for (int i = 0; i < matrix.cols(); ++i) { result.col(i) = transformations[0] * matrix.col(i); } return result; @@ -442,7 +442,7 @@ PybindSE3Type exportSE3Transformation(pybind11::module& module, SE3Group result; for (const auto index : index_list) { const auto intIndex = pybind11::cast(index); - if (intIndex < 0 || intIndex >= se3Vec.size()) { + if (intIndex < 0 || intIndex >= int(se3Vec.size())) { throw std::out_of_range("Index out of range"); } result.push_back(se3Vec[intIndex]); @@ -451,7 +451,7 @@ PybindSE3Type exportSE3Transformation(pybind11::module& module, } else if (pybind11::isinstance( index_or_slice_or_list)) { int index = index_or_slice_or_list.cast(); - if (index < 0 || index >= se3Vec.size()) { + if (index < 0 || index >= int(se3Vec.size())) { throw std::out_of_range("Index out of range"); } return se3Vec[index]; @@ -499,7 +499,7 @@ PybindSE3Type exportSE3Transformation(pybind11::module& module, } } else if (pybind11::isinstance(index_or_slice_or_list)) { int index = index_or_slice_or_list.cast(); - if (index < 0 || index >= se3Vec.size()) { + if (index < 0 || index >= int(se3Vec.size())) { throw std::out_of_range("Index out of range"); } if (value.size() != 1) { diff --git a/sophus_pybind/SO3PyBind.h b/sophus_pybind/SO3PyBind.h index 74f02faf..c4cd7283 100644 --- a/sophus_pybind/SO3PyBind.h +++ b/sophus_pybind/SO3PyBind.h @@ -92,7 +92,7 @@ PybindSO3Group exportSO3Group(pybind11::module& module, -> SO3Group { SO3Group output; output.reserve(rotvecs.rows()); - for (size_t i = 0; i < rotvecs.rows(); ++i) { + for (int i = 0; i < rotvecs.rows(); ++i) { output.emplace_back(Sophus::SO3::exp(rotvecs.row(i))); } return output; @@ -113,7 +113,7 @@ PybindSO3Group exportSO3Group(pybind11::module& module, "from_quat", [](const std::vector& x_vec, const Eigen::Matrix& xyz_vec) -> SO3Group { - if (x_vec.size() != xyz_vec.rows()) { + if (int(x_vec.size()) != xyz_vec.rows()) { throw std::runtime_error(fmt::format( "Size of the real and imagery part is not the same: {} {}", x_vec.size(), xyz_vec.rows())); @@ -147,7 +147,7 @@ PybindSO3Group exportSO3Group(pybind11::module& module, SO3Group output; output.reserve(matrices.shape(0)); - for (size_t i = 0; i < matrices.shape(0); ++i) { + for (int i = 0; i < matrices.shape(0); ++i) { Eigen::Map> mat( matrices.data(i, 0, 0)); output.push_back(Sophus::SO3::fitToSO3(mat)); @@ -298,7 +298,7 @@ PybindSO3Group exportSO3Group(pybind11::module& module, } Eigen::Matrix result(3, matrix.cols()); - for (size_t i = 0; i < matrix.cols(); ++i) { + for (int i = 0; i < matrix.cols(); ++i) { result.col(i) = rotations[0] * matrix.col(i); } return result; @@ -327,7 +327,7 @@ PybindSO3Group exportSO3Group(pybind11::module& module, SO3Group result; for (const auto index : index_list) { const auto intIndex = pybind11::cast(index); - if (intIndex < 0 || intIndex >= so3Vec.size()) { + if (intIndex < 0 || intIndex >= int(so3Vec.size())) { throw std::out_of_range("Index out of range"); } result.push_back(so3Vec[intIndex]); @@ -336,7 +336,7 @@ PybindSO3Group exportSO3Group(pybind11::module& module, } else if (pybind11::isinstance( index_or_slice_or_list)) { int index = index_or_slice_or_list.cast(); - if (index < 0 || index >= so3Vec.size()) { + if (index < 0 || index >= int(so3Vec.size())) { throw std::out_of_range("Index out of range"); } return so3Vec[index]; @@ -384,7 +384,7 @@ PybindSO3Group exportSO3Group(pybind11::module& module, } } else if (pybind11::isinstance(index_or_slice_or_list)) { int index = index_or_slice_or_list.cast(); - if (index < 0 || index >= so3Vec.size()) { + if (index < 0 || index >= int(so3Vec.size())) { throw std::out_of_range("Index out of range"); } if (value.size() != 1) {