diff --git a/CMakeLists.txt b/CMakeLists.txt index 3a7dae44..ebe479a3 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -30,13 +30,13 @@ if(SOPHUS_MASTER_PROJECT) set(CMAKE_CXX_FLAGS_DEBUG "-O0 -g") set(CMAKE_CXX_FLAGS_RELEASE "-O3") set(CMAKE_CXX_FLAGS - "${CMAKE_CXX_FLAGS} -Wall -Wno-error -Wextra -Wno-deprecated-register -Qunused-arguments -fcolor-diagnostics" + "${CMAKE_CXX_FLAGS} -Wall -Werror -Wextra -Wno-deprecated-register -Qunused-arguments -fcolor-diagnostics" ) elseif("${CMAKE_CXX_COMPILER_ID}" STREQUAL "GNU") set(CMAKE_CXX_FLAGS_DEBUG "-O0 -g") set(CMAKE_CXX_FLAGS_RELEASE "-O3") set(CMAKE_CXX_FLAGS - "${CMAKE_CXX_FLAGS} -Wall -Wno-error -Wextra -std=c++14 -Wno-deprecated-declarations -ftemplate-backtrace-limit=0 -Wno-array-bounds" + "${CMAKE_CXX_FLAGS} -Wall -Werror -Wextra -std=c++14 -Wno-deprecated-declarations -ftemplate-backtrace-limit=0 -Wno-array-bounds" ) endif() 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) {