Skip to content

Commit

Permalink
tweak
Browse files Browse the repository at this point in the history
  • Loading branch information
strasdat committed Jun 12, 2024
1 parent 3f54775 commit c28ee7d
Show file tree
Hide file tree
Showing 3 changed files with 19 additions and 19 deletions.
4 changes: 2 additions & 2 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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()

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

0 comments on commit c28ee7d

Please sign in to comment.