Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix missing dependencies on ci #544

Merged
merged 4 commits into from
Jun 12, 2024
Merged
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
6 changes: 3 additions & 3 deletions .github/workflows/pybind.yml
Original file line number Diff line number Diff line change
Expand Up @@ -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:
Expand All @@ -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
Expand All @@ -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
Expand Down
5 changes: 4 additions & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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)
Expand Down
1 change: 0 additions & 1 deletion setup.py
Original file line number Diff line number Diff line change
Expand Up @@ -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 = []
Expand Down
2 changes: 2 additions & 0 deletions sophus/average.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,8 @@

#include <complex>

#include <Eigen/Eigenvalues>

#include "cartesian.hpp"
#include "common.hpp"
#include "rxso2.hpp"
Expand Down
20 changes: 10 additions & 10 deletions sophus_pybind/SE3PyBind.h
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ struct type_caster<Sophus::SE3<double>> {
PYBIND11_TYPE_CASTER(Sophus::SE3<double>, _("SE3"));

// converting from python -> c++ type
bool load(handle src, bool convert) {
bool load(handle src, bool /*convert*/) {
try {
Sophus::SE3Group<double>& ref = src.cast<Sophus::SE3Group<double>&>();
if (ref.size() != 1) {
Expand Down Expand Up @@ -103,7 +103,7 @@ PybindSE3Type<Scalar> exportSE3Transformation(pybind11::module& module,

SE3Group<Scalar> 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<const Eigen::Matrix<Scalar, 4, 4, Eigen::RowMajor>> mat(
matrices.data(i, 0, 0));
output.push_back(Sophus::SE3<Scalar>::fitToSE3(mat));
Expand All @@ -129,7 +129,7 @@ PybindSE3Type<Scalar> exportSE3Transformation(pybind11::module& module,

SE3Group<Scalar> 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<const Eigen::Matrix<Scalar, 3, 4, Eigen::RowMajor>> mat(
matrices.data(i, 0, 0));
output.push_back(Sophus::SE3<Scalar>(
Expand Down Expand Up @@ -161,7 +161,7 @@ PybindSE3Type<Scalar> exportSE3Transformation(pybind11::module& module,
-> SE3Group<Scalar> {
SE3Group<Scalar> 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<Scalar, 6, 1>{translational_parts(i, 0),
translational_parts(i, 1),
Expand Down Expand Up @@ -192,8 +192,8 @@ PybindSE3Type<Scalar> exportSE3Transformation(pybind11::module& module,
[](const std::vector<Scalar>& x_vec,
const Eigen::Matrix<Scalar, -1, 3>& xyz_vec,
const Eigen::Matrix<Scalar, -1, 3>& translations) -> SE3Group<Scalar> {
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 = {}",
Expand Down Expand Up @@ -413,7 +413,7 @@ PybindSE3Type<Scalar> exportSE3Transformation(pybind11::module& module,
}

Eigen::Matrix<Scalar, 3, Eigen::Dynamic> 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;
Expand Down Expand Up @@ -442,7 +442,7 @@ PybindSE3Type<Scalar> exportSE3Transformation(pybind11::module& module,
SE3Group<Scalar> result;
for (const auto index : index_list) {
const auto intIndex = pybind11::cast<int>(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]);
Expand All @@ -451,7 +451,7 @@ PybindSE3Type<Scalar> exportSE3Transformation(pybind11::module& module,
} else if (pybind11::isinstance<pybind11::int_>(
index_or_slice_or_list)) {
int index = index_or_slice_or_list.cast<int>();
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];
Expand Down Expand Up @@ -499,7 +499,7 @@ PybindSE3Type<Scalar> exportSE3Transformation(pybind11::module& module,
}
} else if (pybind11::isinstance<pybind11::int_>(index_or_slice_or_list)) {
int index = index_or_slice_or_list.cast<int>();
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) {
Expand Down
14 changes: 7 additions & 7 deletions sophus_pybind/SO3PyBind.h
Original file line number Diff line number Diff line change
Expand Up @@ -92,7 +92,7 @@ PybindSO3Group<Scalar> exportSO3Group(pybind11::module& module,
-> SO3Group<Scalar> {
SO3Group<Scalar> 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<Scalar>::exp(rotvecs.row(i)));
}
return output;
Expand All @@ -113,7 +113,7 @@ PybindSO3Group<Scalar> exportSO3Group(pybind11::module& module,
"from_quat",
[](const std::vector<Scalar>& x_vec,
const Eigen::Matrix<Scalar, -1, 3>& xyz_vec) -> SO3Group<Scalar> {
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()));
Expand Down Expand Up @@ -147,7 +147,7 @@ PybindSO3Group<Scalar> exportSO3Group(pybind11::module& module,

SO3Group<Scalar> 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<const Eigen::Matrix<Scalar, 3, 3, Eigen::RowMajor>> mat(
matrices.data(i, 0, 0));
output.push_back(Sophus::SO3<Scalar>::fitToSO3(mat));
Expand Down Expand Up @@ -298,7 +298,7 @@ PybindSO3Group<Scalar> exportSO3Group(pybind11::module& module,
}

Eigen::Matrix<Scalar, 3, Eigen::Dynamic> 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;
Expand Down Expand Up @@ -327,7 +327,7 @@ PybindSO3Group<Scalar> exportSO3Group(pybind11::module& module,
SO3Group<Scalar> result;
for (const auto index : index_list) {
const auto intIndex = pybind11::cast<int>(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]);
Expand All @@ -336,7 +336,7 @@ PybindSO3Group<Scalar> exportSO3Group(pybind11::module& module,
} else if (pybind11::isinstance<pybind11::int_>(
index_or_slice_or_list)) {
int index = index_or_slice_or_list.cast<int>();
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];
Expand Down Expand Up @@ -384,7 +384,7 @@ PybindSO3Group<Scalar> exportSO3Group(pybind11::module& module,
}
} else if (pybind11::isinstance<pybind11::int_>(index_or_slice_or_list)) {
int index = index_or_slice_or_list.cast<int>();
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) {
Expand Down
Loading