diff --git a/CHANGELOG.md b/CHANGELOG.md index a7ec90e329..52f4bfef3e 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -6,6 +6,12 @@ The format is based on [Keep a Changelog](https://keepachangelog.com/en/1.0.0/). ## [Unreleased] +### Changed +- Set NOMINMAX as a public definitions on Windows ([#2139](https://github.com/stack-of-tasks/pinocchio/pull/2139)) + +### Fixed +- Remove a lot of warnings ([#2139](https://github.com/stack-of-tasks/pinocchio/pull/2139)) + ## [2.7.0] - 2024-01-23 ### Added diff --git a/benchmark/CMakeLists.txt b/benchmark/CMakeLists.txt index 3d23cc158e..2a561644f1 100644 --- a/benchmark/CMakeLists.txt +++ b/benchmark/CMakeLists.txt @@ -5,10 +5,6 @@ # ---------------------------------------------------- # --- BENCHMARK -------------------------------------- # ---------------------------------------------------- -IF(WIN32) - ADD_DEFINITIONS("-DNOMINMAX") -ENDIF() - ADD_CUSTOM_TARGET(bench) MACRO(ADD_BENCH bench_name) diff --git a/bindings/python/CMakeLists.txt b/bindings/python/CMakeLists.txt index 72c88be6dd..4c37b0c789 100644 --- a/bindings/python/CMakeLists.txt +++ b/bindings/python/CMakeLists.txt @@ -44,10 +44,12 @@ IF(BUILD_PYTHON_INTERFACE) # Do not report: # -Wconversion as the BOOST_PYTHON_FUNCTION_OVERLOADS implicitly converts. # -Wcomment as latex equations have multi-line comments. - # -Wself-assign-overloaded as bp::self operations trigger this - IF(NOT WIN32) - TARGET_COMPILE_OPTIONS(${PYWRAP} PRIVATE -Wno-conversion -Wno-comment -Wno-self-assign-overloaded) - ENDIF(NOT WIN32) + # -Wself-assign-overloaded as bp::self operations trigger this (Clang only) + CXX_FLAGS_BY_COMPILER_FRONTEND( + GNU -Wno-conversion -Wno-comment -Wno-self-assign-overloaded + OUTPUT PRIVATE_OPTIONS + FILTER) + TARGET_COMPILE_OPTIONS(${PYWRAP} PRIVATE ${PRIVATE_OPTIONS}) SET_TARGET_PROPERTIES(${PYWRAP} PROPERTIES VERSION ${PROJECT_VERSION}) IF(BUILD_WITH_COMMIT_VERSION) @@ -61,7 +63,6 @@ IF(BUILD_PYTHON_INTERFACE) TARGET_COMPILE_DEFINITIONS(${PYWRAP} PRIVATE -DPINOCCHIO_PYTHON_INTERFACE_WITH_HPP_FCL_PYTHON_BINDINGS) ENDIF(BUILD_WITH_HPP_FCL_PYTHON_BINDINGS) IF(WIN32) - TARGET_COMPILE_DEFINITIONS(${PYWRAP} PRIVATE -DNOMINMAX) TARGET_LINK_LIBRARIES(${PYWRAP} PUBLIC ${PYTHON_LIBRARY}) ENDIF(WIN32) diff --git a/bindings/python/parsers/urdf/geometry.cpp b/bindings/python/parsers/urdf/geometry.cpp index 04b204554b..4078e4cbce 100644 --- a/bindings/python/parsers/urdf/geometry.cpp +++ b/bindings/python/parsers/urdf/geometry.cpp @@ -29,7 +29,10 @@ namespace pinocchio MeshLoaderPtr mesh_loader = MeshLoaderPtr(); if (!py_mesh_loader.is_none()) { #ifdef PINOCCHIO_WITH_HPP_FCL +PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH +PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED mesh_loader = bp::extract<::hpp::fcl::MeshLoaderPtr>(py_mesh_loader); +PINOCCHIO_COMPILER_DIAGNOSTIC_POP #else PyErr_WarnEx(PyExc_UserWarning, "Mesh loader is ignored because Pinocchio is not built with hpp-fcl", 1); #endif diff --git a/cmake b/cmake index fff972a050..5e91513ba7 160000 --- a/cmake +++ b/cmake @@ -1 +1 @@ -Subproject commit fff972a050d2f8812c3c55bea92b6a67d71f615b +Subproject commit 5e91513ba70fef30a67b2a8c4b8d8214b554949d diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index e8f6141724..ea2aa397b5 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -2,12 +2,21 @@ # Copyright (c) 2015-2022 CNRS INRIA # +# Compute flags outside the macro to avoid recomputing it for each tests +CXX_FLAGS_BY_COMPILER_FRONTEND( + MSVC _USE_MATH_DEFINES + OUTPUT EXAMPLE_PRIVATE_DEFINITIONS) + FUNCTION(ADD_PINOCCHIO_CPP_EXAMPLE EXAMPLE) GET_FILENAME_COMPONENT(EXAMPLE_NAME ${EXAMPLE} NAME) SET(EXAMPLE_NAME "example-cpp-${EXAMPLE_NAME}") ADD_UNIT_TEST(${EXAMPLE_NAME} "${EXAMPLE}.cpp") TARGET_LINK_LIBRARIES(${EXAMPLE_NAME} PUBLIC ${PROJECT_NAME}) + TARGET_COMPILE_DEFINITIONS(${EXAMPLE_NAME} + PRIVATE ${EXAMPLE_PRIVATE_DEFINITIONS} + PINOCCHIO_MODEL_DIR="${PINOCCHIO_MODEL_DIR}") + # There is no RPATH in Windows, then we must use the PATH to find the DLL IF(WIN32) STRING(REPLACE ";" "\\\;" _PATH "$ENV{PATH}") @@ -51,12 +60,6 @@ IF(hpp-fcl_FOUND) ENDIF() ENDIF(hpp-fcl_FOUND) -ADD_DEFINITIONS(-DPINOCCHIO_MODEL_DIR="${PINOCCHIO_MODEL_DIR}") - -IF(WIN32) - ADD_DEFINITIONS("-DNOMINMAX -D_USE_MATH_DEFINES") -ENDIF(WIN32) - FOREACH(EXAMPLE ${${PROJECT_NAME}_EXAMPLES}) ADD_PINOCCHIO_CPP_EXAMPLE(${EXAMPLE}) ENDFOREACH(EXAMPLE ${${PROJECT_NAME}_EXAMPLES}) diff --git a/examples/overview-lie.cpp b/examples/overview-lie.cpp index 74689e311a..168145d8d5 100644 --- a/examples/overview-lie.cpp +++ b/examples/overview-lie.cpp @@ -12,6 +12,7 @@ int main() SE2Operation aSE2; SE2Operation::ConfigVector_t pose_s,pose_g; SE2Operation::TangentVector_t delta_u; + delta_u.setZero(); // Starting configuration pose_s(0) = 1.0; pose_s(1) = 1.0; diff --git a/include/pinocchio/bindings/python/multibody/data.hpp b/include/pinocchio/bindings/python/multibody/data.hpp index 7698a5de6d..841c4022af 100644 --- a/include/pinocchio/bindings/python/multibody/data.hpp +++ b/include/pinocchio/bindings/python/multibody/data.hpp @@ -20,7 +20,9 @@ #include "pinocchio/bindings/python/utils/copyable.hpp" +#if EIGENPY_VERSION_AT_MOST(2,8,1) EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(pinocchio::Data) +#endif namespace pinocchio { diff --git a/include/pinocchio/bindings/python/multibody/geometry-data.hpp b/include/pinocchio/bindings/python/multibody/geometry-data.hpp index 099efd74fc..b8dcef27fe 100644 --- a/include/pinocchio/bindings/python/multibody/geometry-data.hpp +++ b/include/pinocchio/bindings/python/multibody/geometry-data.hpp @@ -15,7 +15,9 @@ #include "pinocchio/bindings/python/utils/std-vector.hpp" #include "pinocchio/bindings/python/serialization/serializable.hpp" +#if EIGENPY_VERSION_AT_MOST(2,8,1) EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(pinocchio::GeometryData) +#endif namespace pinocchio { diff --git a/include/pinocchio/bindings/python/multibody/geometry-model.hpp b/include/pinocchio/bindings/python/multibody/geometry-model.hpp index fe28d81311..70ee906e1e 100644 --- a/include/pinocchio/bindings/python/multibody/geometry-model.hpp +++ b/include/pinocchio/bindings/python/multibody/geometry-model.hpp @@ -11,7 +11,9 @@ #include "pinocchio/bindings/python/utils/copyable.hpp" #include "pinocchio/multibody/geometry.hpp" +#if EIGENPY_VERSION_AT_MOST(2,8,1) EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(pinocchio::GeometryModel) +#endif namespace pinocchio { diff --git a/include/pinocchio/bindings/python/multibody/geometry-object.hpp b/include/pinocchio/bindings/python/multibody/geometry-object.hpp index 5c44b2926e..e61f95cdac 100644 --- a/include/pinocchio/bindings/python/multibody/geometry-object.hpp +++ b/include/pinocchio/bindings/python/multibody/geometry-object.hpp @@ -11,7 +11,9 @@ #include "pinocchio/multibody/geometry.hpp" +#if EIGENPY_VERSION_AT_MOST(2,8,1) EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(pinocchio::GeometryObject) +#endif namespace pinocchio { diff --git a/include/pinocchio/bindings/python/multibody/model.hpp b/include/pinocchio/bindings/python/multibody/model.hpp index de7716e10a..976ff3c011 100644 --- a/include/pinocchio/bindings/python/multibody/model.hpp +++ b/include/pinocchio/bindings/python/multibody/model.hpp @@ -23,7 +23,9 @@ #include "pinocchio/bindings/python/utils/pickle-map.hpp" #include "pinocchio/bindings/python/utils/std-vector.hpp" +#if EIGENPY_VERSION_AT_MOST(2,8,1) EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(pinocchio::Model) +#endif namespace pinocchio { diff --git a/include/pinocchio/bindings/python/multibody/pool/geometry.hpp b/include/pinocchio/bindings/python/multibody/pool/geometry.hpp index 5505e18449..eb994d54bc 100644 --- a/include/pinocchio/bindings/python/multibody/pool/geometry.hpp +++ b/include/pinocchio/bindings/python/multibody/pool/geometry.hpp @@ -17,7 +17,9 @@ #include "pinocchio/bindings/python/utils/copyable.hpp" #include "pinocchio/bindings/python/utils/std-vector.hpp" +#if EIGENPY_VERSION_AT_MOST(2,8,1) EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(pinocchio::GeometryPool) +#endif namespace pinocchio { diff --git a/include/pinocchio/bindings/python/multibody/pool/model.hpp b/include/pinocchio/bindings/python/multibody/pool/model.hpp index e2191a9d3f..f3b418951d 100644 --- a/include/pinocchio/bindings/python/multibody/pool/model.hpp +++ b/include/pinocchio/bindings/python/multibody/pool/model.hpp @@ -17,7 +17,9 @@ #include "pinocchio/bindings/python/utils/copyable.hpp" #include "pinocchio/bindings/python/utils/std-vector.hpp" +#if EIGENPY_VERSION_AT_MOST(2,8,1) EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(pinocchio::ModelPool) +#endif namespace pinocchio { diff --git a/include/pinocchio/bindings/python/spatial/force.hpp b/include/pinocchio/bindings/python/spatial/force.hpp index 91459b653a..50e946bb22 100644 --- a/include/pinocchio/bindings/python/spatial/force.hpp +++ b/include/pinocchio/bindings/python/spatial/force.hpp @@ -16,7 +16,9 @@ #include "pinocchio/bindings/python/utils/copyable.hpp" #include "pinocchio/bindings/python/utils/printable.hpp" +#if EIGENPY_VERSION_AT_MOST(2,8,1) EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(pinocchio::Force) +#endif namespace pinocchio { diff --git a/include/pinocchio/bindings/python/spatial/inertia.hpp b/include/pinocchio/bindings/python/spatial/inertia.hpp index 3141572c56..e9f43d97a3 100644 --- a/include/pinocchio/bindings/python/spatial/inertia.hpp +++ b/include/pinocchio/bindings/python/spatial/inertia.hpp @@ -16,7 +16,9 @@ #include "pinocchio/bindings/python/utils/copyable.hpp" #include "pinocchio/bindings/python/utils/printable.hpp" +#if EIGENPY_VERSION_AT_MOST(2,8,1) EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(pinocchio::Inertia) +#endif namespace pinocchio { diff --git a/include/pinocchio/bindings/python/spatial/motion.hpp b/include/pinocchio/bindings/python/spatial/motion.hpp index 9458b6913f..6658b57cb7 100644 --- a/include/pinocchio/bindings/python/spatial/motion.hpp +++ b/include/pinocchio/bindings/python/spatial/motion.hpp @@ -17,7 +17,9 @@ #include "pinocchio/bindings/python/utils/copyable.hpp" #include "pinocchio/bindings/python/utils/printable.hpp" +#if EIGENPY_VERSION_AT_MOST(2,8,1) EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(pinocchio::Motion) +#endif namespace pinocchio { diff --git a/include/pinocchio/bindings/python/spatial/se3.hpp b/include/pinocchio/bindings/python/spatial/se3.hpp index 13404661c4..889aff59f0 100644 --- a/include/pinocchio/bindings/python/spatial/se3.hpp +++ b/include/pinocchio/bindings/python/spatial/se3.hpp @@ -20,7 +20,9 @@ #include "pinocchio/bindings/python/utils/copyable.hpp" #include "pinocchio/bindings/python/utils/printable.hpp" +#if EIGENPY_VERSION_AT_MOST(2,8,1) EIGENPY_DEFINE_STRUCT_ALLOCATOR_SPECIALIZATION(pinocchio::SE3) +#endif namespace pinocchio { diff --git a/include/pinocchio/container/aligned-vector.hpp b/include/pinocchio/container/aligned-vector.hpp index a6fe4cb5e7..e91e6fd851 100644 --- a/include/pinocchio/container/aligned-vector.hpp +++ b/include/pinocchio/container/aligned-vector.hpp @@ -39,8 +39,10 @@ namespace pinocchio aligned_vector(InputIterator first, InputIterator last, const allocator_type& a = allocator_type()) : vector_base(first, last, a) {} aligned_vector(const aligned_vector & c) : vector_base(c) {} - explicit aligned_vector(size_type num, const value_type & val = value_type()) + explicit aligned_vector(size_type num, const value_type & val) : vector_base(num, val) {} + explicit aligned_vector(size_type num) + : vector_base(num) {} aligned_vector(iterator start, iterator end) : vector_base(start, end) {} aligned_vector & operator=(const aligned_vector& x) { vector_base::operator=(x); return *this; } diff --git a/include/pinocchio/macros.hpp b/include/pinocchio/macros.hpp index ff268d8c2b..63842d126e 100644 --- a/include/pinocchio/macros.hpp +++ b/include/pinocchio/macros.hpp @@ -80,14 +80,21 @@ namespace pinocchio # define PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH _Pragma("GCC diagnostic push") # define PINOCCHIO_COMPILER_DIAGNOSTIC_POP _Pragma("GCC diagnostic pop") # define PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS _Pragma("GCC diagnostic ignored \"-Wdeprecated-declarations\"") +# if defined(__clang__) +# define PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED +# else +# define PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED _Pragma("GCC diagnostic ignored \"-Wmaybe-uninitialized\"") +# endif #elif defined (WIN32) # define PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH _Pragma("warning(push)") # define PINOCCHIO_COMPILER_DIAGNOSTIC_POP _Pragma("warning(pop)") # define PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS _Pragma("warning(disable : 4996)") +# define PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED #else # define PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH # define PINOCCHIO_COMPILER_DIAGNOSTIC_POP # define PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS +# define PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED #endif // __GNUC__ // Handle explicitely the GCC boring warning: 'anonymous variadic macros were introduced in C++11' diff --git a/include/pinocchio/math/quaternion.hpp b/include/pinocchio/math/quaternion.hpp index 218bb1d9f0..7c64a50f6d 100644 --- a/include/pinocchio/math/quaternion.hpp +++ b/include/pinocchio/math/quaternion.hpp @@ -105,7 +105,7 @@ namespace pinocchio /// Uniformly random quaternion sphere. template - void uniformRandom(const Eigen::QuaternionBase & q) + void uniformRandom(Eigen::QuaternionBase & q) { typedef typename Derived::Scalar Scalar; @@ -121,10 +121,10 @@ namespace pinocchio Scalar s2,c2; SINCOS(Scalar(2)*PI_value*u2,&s2,&c2); Scalar s3,c3; SINCOS(Scalar(2)*PI_value*u3,&s3,&c3); - PINOCCHIO_EIGEN_CONST_CAST(Derived,q).w() = mult1 * s2; - PINOCCHIO_EIGEN_CONST_CAST(Derived,q).x() = mult1 * c2; - PINOCCHIO_EIGEN_CONST_CAST(Derived,q).y() = mult2 * s3; - PINOCCHIO_EIGEN_CONST_CAST(Derived,q).z() = mult2 * c3; + q.w() = mult1 * s2; + q.x() = mult1 * c2; + q.y() = mult2 * s3; + q.z() = mult2 * c3; } namespace internal diff --git a/include/pinocchio/multibody/joint/joint-prismatic-unaligned.hpp b/include/pinocchio/multibody/joint/joint-prismatic-unaligned.hpp index a8445c89a0..a8098e4fd5 100644 --- a/include/pinocchio/multibody/joint/joint-prismatic-unaligned.hpp +++ b/include/pinocchio/multibody/joint/joint-prismatic-unaligned.hpp @@ -496,7 +496,7 @@ namespace pinocchio typedef Eigen::Matrix Vector3; - JointModelPrismaticUnalignedTpl() {} + JointModelPrismaticUnalignedTpl(): axis(Vector3::UnitX()) {} JointModelPrismaticUnalignedTpl(const Scalar & x, const Scalar & y, const Scalar & z) diff --git a/include/pinocchio/multibody/joint/joint-revolute-unaligned.hpp b/include/pinocchio/multibody/joint/joint-revolute-unaligned.hpp index 487a9eff71..871073b778 100644 --- a/include/pinocchio/multibody/joint/joint-revolute-unaligned.hpp +++ b/include/pinocchio/multibody/joint/joint-revolute-unaligned.hpp @@ -519,7 +519,7 @@ namespace pinocchio using Base::idx_v; using Base::setIndexes; - JointModelRevoluteUnalignedTpl() {} + JointModelRevoluteUnalignedTpl(): axis(Vector3::UnitX()) {} JointModelRevoluteUnalignedTpl(const Scalar & x, const Scalar & y, diff --git a/include/pinocchio/multibody/joint/joint-revolute-unbounded-unaligned.hpp b/include/pinocchio/multibody/joint/joint-revolute-unbounded-unaligned.hpp index 8d61a3030d..01928e653e 100644 --- a/include/pinocchio/multibody/joint/joint-revolute-unbounded-unaligned.hpp +++ b/include/pinocchio/multibody/joint/joint-revolute-unbounded-unaligned.hpp @@ -114,7 +114,7 @@ namespace pinocchio using Base::idx_v; using Base::setIndexes; - JointModelRevoluteUnboundedUnalignedTpl() {} + JointModelRevoluteUnboundedUnalignedTpl(): axis(Vector3::UnitX()) {} JointModelRevoluteUnboundedUnalignedTpl(const Scalar & x, const Scalar & y, diff --git a/include/pinocchio/multibody/liegroup/liegroup-base.hxx b/include/pinocchio/multibody/liegroup/liegroup-base.hxx index a1d554a5fa..a51c52f480 100644 --- a/include/pinocchio/multibody/liegroup/liegroup-base.hxx +++ b/include/pinocchio/multibody/liegroup/liegroup-base.hxx @@ -557,8 +557,11 @@ namespace pinocchio { const AssignmentOperatorType op) const { Index nv_ (nv()); +PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH +PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED JacobianMatrix_t J (nv_, nv_); dIntegrate(q, v, J, arg); +PINOCCHIO_COMPILER_DIAGNOSTIC_POP switch (op) { case SETTO: if(dIntegrateOnTheLeft) Jout = J * Jin; @@ -585,8 +588,11 @@ namespace pinocchio { const AssignmentOperatorType op) const { Index nv_ (nv()); +PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH +PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED JacobianMatrix_t J (nv_, nv_); dDifference(q0, q1, J); +PINOCCHIO_COMPILER_DIAGNOSTIC_POP switch (op) { case SETTO: if(dDifferenceOnTheLeft) Jout = J * Jin; @@ -627,8 +633,11 @@ namespace pinocchio { const Eigen::MatrixBase & q0, const Eigen::MatrixBase & q1) const { +PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH +PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED TangentVector_t t(nv()); difference(q0.derived(), q1.derived(), t); +PINOCCHIO_COMPILER_DIAGNOSTIC_POP return t.squaredNorm(); } diff --git a/include/pinocchio/multibody/liegroup/liegroup-generic.hpp b/include/pinocchio/multibody/liegroup/liegroup-generic.hpp index 616a01d9e2..b095d57830 100644 --- a/include/pinocchio/multibody/liegroup/liegroup-generic.hpp +++ b/include/pinocchio/multibody/liegroup/liegroup-generic.hpp @@ -43,15 +43,8 @@ namespace pinocchio : Base(lg_variant) {} - LieGroupGenericTpl(const LieGroupGenericTpl & lg_generic) - : Base(lg_generic) - {} - - LieGroupGenericTpl & operator=(const LieGroupGenericTpl & other) - { - static_cast(*this) = other.toVariant(); - return *this; - } + LieGroupGenericTpl(const LieGroupGenericTpl & lg_generic) = default; + LieGroupGenericTpl & operator=(const LieGroupGenericTpl & other) = default; const LieGroupVariant & toVariant() const { return static_cast(*this); } diff --git a/include/pinocchio/multibody/liegroup/special-euclidean.hpp b/include/pinocchio/multibody/liegroup/special-euclidean.hpp index c6e7ebe678..bffd27ab37 100644 --- a/include/pinocchio/multibody/liegroup/special-euclidean.hpp +++ b/include/pinocchio/multibody/liegroup/special-euclidean.hpp @@ -222,9 +222,12 @@ namespace pinocchio const Eigen::MatrixBase & q1, const Eigen::MatrixBase & d) { +PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH +PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED Matrix2 R0, R1; Vector2 t0, t1; forwardKinematics(R0, t0, q0); forwardKinematics(R1, t1, q1); +PINOCCHIO_COMPILER_DIAGNOSTIC_POP Matrix2 R (R0.transpose() * R1); Vector2 t (R0.transpose() * (t1 - t0)); @@ -236,15 +239,21 @@ namespace pinocchio const Eigen::MatrixBase & q1, const Eigen::MatrixBase& J) const { +PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH +PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED Matrix2 R0, R1; Vector2 t0, t1; forwardKinematics(R0, t0, q0); forwardKinematics(R1, t1, q1); +PINOCCHIO_COMPILER_DIAGNOSTIC_POP Matrix2 R (R0.transpose() * R1); Vector2 t (R0.transpose() * (t1 - t0)); if (arg == ARG0) { +PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH +PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED JacobianMatrix_t J1; Jlog (R, t, J1); +PINOCCHIO_COMPILER_DIAGNOSTIC_POP // pcross = [ y1-y0, - (x1 - x0) ] Vector2 pcross (q1(1) - q0(1), q0(0) - q1(0)); @@ -267,10 +276,13 @@ namespace pinocchio { ConfigOut_t & out = PINOCCHIO_EIGEN_CONST_CAST(ConfigOut_t,qout); +PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH +PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED Matrix2 R0, R; Vector2 t0, t; forwardKinematics(R0, t0, q); exp(v, R, t); +PINOCCHIO_COMPILER_DIAGNOSTIC_POP out.template head<2>().noalias() = R0 * t + t0; out.template tail<2>().noalias() = R0 * R.col(0); @@ -300,9 +312,12 @@ namespace pinocchio { JacobianOut_t & Jout = PINOCCHIO_EIGEN_CONST_CAST(JacobianOut_t,J); +PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH +PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED Matrix2 R; Vector2 t; exp(v, R, t); +PINOCCHIO_COMPILER_DIAGNOSTIC_POP toInverseActionMatrix(R, t, Jout, op); } @@ -316,8 +331,11 @@ namespace pinocchio JacobianOut_t & Jout = PINOCCHIO_EIGEN_CONST_CAST(JacobianOut_t,J); // TODO sparse version MotionTpl nu; nu.toVector() << v.template head<2>(), 0, 0, 0, v[2]; +PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH +PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED Eigen::Matrix Jtmp6; Jexp6(nu, Jtmp6); +PINOCCHIO_COMPILER_DIAGNOSTIC_POP switch(op) { @@ -350,9 +368,12 @@ namespace pinocchio const Eigen::MatrixBase & J_out) const { JacobianOut_t & Jout = PINOCCHIO_EIGEN_CONST_CAST(JacobianOut_t,J_out); +PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH +PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED Matrix2 R; Vector2 t; exp(v, R, t); +PINOCCHIO_COMPILER_DIAGNOSTIC_POP Vector2 tinv = (R.transpose() * t).reverse(); tinv[0] *= Scalar(-1.); @@ -371,8 +392,11 @@ namespace pinocchio JacobianOut_t & Jout = PINOCCHIO_EIGEN_CONST_CAST(JacobianOut_t,J_out); MotionTpl nu; nu.toVector() << v.template head<2>(), 0, 0, 0, v[2]; +PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH +PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED Eigen::Matrix Jtmp6; Jexp6(nu, Jtmp6); +PINOCCHIO_COMPILER_DIAGNOSTIC_POP Jout.template topRows<2>().noalias() = Jtmp6.template topLeftCorner<2,2>() * Jin.template topRows<2>(); @@ -391,9 +415,12 @@ namespace pinocchio const Eigen::MatrixBase & J) const { Jacobian_t & Jout = PINOCCHIO_EIGEN_CONST_CAST(Jacobian_t,J); +PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH +PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED Matrix2 R; Vector2 t; exp(v, R, t); +PINOCCHIO_COMPILER_DIAGNOSTIC_POP Vector2 tinv = (R.transpose() * t).reverse(); tinv[0] *= Scalar(-1); @@ -411,8 +438,11 @@ namespace pinocchio Jacobian_t & Jout = PINOCCHIO_EIGEN_CONST_CAST(Jacobian_t,J); MotionTpl nu; nu.toVector() << v.template head<2>(), 0, 0, 0, v[2]; +PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH +PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED Eigen::Matrix Jtmp6; Jexp6(nu, Jtmp6); +PINOCCHIO_COMPILER_DIAGNOSTIC_POP //TODO: Remove aliasing Jout.template topRows<2>() = Jtmp6.template topLeftCorner<2,2>() * Jout.template topRows<2>(); @@ -570,8 +600,11 @@ namespace pinocchio * SE3(R1, q1.template head<3>())); if (arg == ARG0) { +PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH +PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED JacobianMatrix_t J1; Jlog6 (M, J1); +PINOCCHIO_COMPILER_DIAGNOSTIC_POP const Vector3 p1_p0 = R1.transpose()*(q1.template head<3>() - q0.template head<3>()); @@ -638,6 +671,8 @@ namespace pinocchio typedef Eigen::Matrix Jacobian43; typedef SE3Tpl SE3; +PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH +PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED Jacobian43 Jexp3QuatCoeffWise; Scalar theta; @@ -645,6 +680,7 @@ namespace pinocchio quaternion::Jexp3CoeffWise(v,Jexp3QuatCoeffWise); typename SE3::Matrix3 Jlog; Jlog3(theta,v,Jlog); +PINOCCHIO_COMPILER_DIAGNOSTIC_POP // std::cout << "Jexp3QuatCoeffWise\n" << Jexp3QuatCoeffWise << std::endl; // std::cout << "Jlog\n" << Jlog << std::endl; @@ -729,8 +765,11 @@ namespace pinocchio const Eigen::MatrixBase & J_out) const { JacobianOut_t & Jout = PINOCCHIO_EIGEN_CONST_CAST(JacobianOut_t,J_out); +PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH +PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED Eigen::Matrix Jtmp6; Jexp6(MotionRef(v.derived()), Jtmp6); +PINOCCHIO_COMPILER_DIAGNOSTIC_POP Jout.template topRows<3>().noalias() = Jtmp6.template topLeftCorner<3,3>() * Jin.template topRows<3>(); @@ -765,8 +804,11 @@ namespace pinocchio const Eigen::MatrixBase & J_out) const { Jacobian_t & Jout = PINOCCHIO_EIGEN_CONST_CAST(Jacobian_t,J_out); +PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH +PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED Eigen::Matrix Jtmp6; Jexp6(MotionRef(v.derived()), Jtmp6); +PINOCCHIO_COMPILER_DIAGNOSTIC_POP Jout.template topRows<3>() = Jtmp6.template topLeftCorner<3,3>() * Jout.template topRows<3>(); @@ -780,8 +822,11 @@ namespace pinocchio static Scalar squaredDistance_impl(const Eigen::MatrixBase & q0, const Eigen::MatrixBase & q1) { +PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH +PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED TangentVector_t t; difference_impl(q0, q1, t); +PINOCCHIO_COMPILER_DIAGNOSTIC_POP return t.squaredNorm(); } diff --git a/include/pinocchio/multibody/liegroup/special-orthogonal.hpp b/include/pinocchio/multibody/liegroup/special-orthogonal.hpp index 9884de93b3..b6e81b5918 100644 --- a/include/pinocchio/multibody/liegroup/special-orthogonal.hpp +++ b/include/pinocchio/multibody/liegroup/special-orthogonal.hpp @@ -401,8 +401,11 @@ namespace pinocchio const Quaternion_t quat_diff = quat0.conjugate() * quat1; if (arg == ARG0) { +PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH +PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED JacobianMatrix_t J1; quaternion::Jlog3(quat_diff, J1); +PINOCCHIO_COMPILER_DIAGNOSTIC_POP const Matrix3 R = (quat_diff).matrix(); PINOCCHIO_EIGEN_CONST_CAST(JacobianOut_t,J).noalias() = - J1 * R.transpose(); @@ -439,6 +442,8 @@ namespace pinocchio ConstQuaternionMap_t quat_map(q.derived().data()); assert(quaternion::isNormalized(quat_map,RealScalar(PINOCCHIO_DEFAULT_QUATERNION_NORM_TOLERANCE_VALUE))); +PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH +PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED Eigen::Matrix Jexp3QuatCoeffWise; Scalar theta; @@ -446,6 +451,7 @@ namespace pinocchio quaternion::Jexp3CoeffWise(v,Jexp3QuatCoeffWise); Matrix3 Jlog; Jlog3(theta,v,Jlog); +PINOCCHIO_COMPILER_DIAGNOSTIC_POP // if(quat_map.w() >= 0.) // comes from the log3 for quaternions which may change the sign. if(quat_map.coeffs()[3] >= 0.) // comes from the log3 for quaternions which may change the sign. @@ -523,8 +529,11 @@ namespace pinocchio { typedef typename SE3::Matrix3 Matrix3; JacobianOut_t & Jout = PINOCCHIO_EIGEN_CONST_CAST(JacobianOut_t,J_out); +PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH +PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED Matrix3 Jtmp3; Jexp3(v, Jtmp3); +PINOCCHIO_COMPILER_DIAGNOSTIC_POP Jout.noalias() = Jtmp3 * Jin; } @@ -546,8 +555,11 @@ namespace pinocchio { typedef typename SE3::Matrix3 Matrix3; Jacobian_t & Jout = PINOCCHIO_EIGEN_CONST_CAST(Jacobian_t,J_out); +PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH +PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED Matrix3 Jtmp3; Jexp3(v, Jtmp3); +PINOCCHIO_COMPILER_DIAGNOSTIC_POP Jout = Jtmp3 * Jout; } @@ -573,8 +585,11 @@ namespace pinocchio static Scalar squaredDistance_impl(const Eigen::MatrixBase & q0, const Eigen::MatrixBase & q1) { +PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH +PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED TangentVector_t t; difference_impl(q0, q1, t); +PINOCCHIO_COMPILER_DIAGNOSTIC_POP return t.squaredNorm(); } diff --git a/include/pinocchio/spatial/explog.hpp b/include/pinocchio/spatial/explog.hpp index 5403961a79..3200d14456 100644 --- a/include/pinocchio/spatial/explog.hpp +++ b/include/pinocchio/spatial/explog.hpp @@ -485,8 +485,11 @@ namespace pinocchio } case ADDTO: { +PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH +PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED Matrix3 Jtmp3; Jexp3(w, Jtmp3); +PINOCCHIO_COMPILER_DIAGNOSTIC_POP Jout.template bottomRightCorner<3,3>() += Jtmp3; Jout.template topLeftCorner<3,3>() += Jtmp3; const Vector3 p = Jtmp3.transpose() * v; @@ -502,8 +505,11 @@ namespace pinocchio } case RMTO: { +PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH +PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED Matrix3 Jtmp3; Jexp3(w, Jtmp3); +PINOCCHIO_COMPILER_DIAGNOSTIC_POP Jout.template bottomRightCorner<3,3>() -= Jtmp3; Jout.template topLeftCorner<3,3>() -= Jtmp3; const Vector3 p = Jtmp3.transpose() * v; diff --git a/include/pinocchio/spatial/motion-tpl.hpp b/include/pinocchio/spatial/motion-tpl.hpp index 18613847f1..e34f98b16f 100644 --- a/include/pinocchio/spatial/motion-tpl.hpp +++ b/include/pinocchio/spatial/motion-tpl.hpp @@ -79,11 +79,22 @@ namespace pinocchio : m_data(clone.toVector()) {} - template + // Same explanation as converting constructor from MotionBase + template , MotionTpl>::value, + bool>::type = true> explicit MotionTpl(const MotionDense & clone) { linear() = clone.linear(); angular() = clone.angular(); } - template + // MotionBase implement a conversion function to PlainReturnType. + // Usually, PlainReturnType is defined as MotionTpl. + // In this case, this converting constructor is redundant and + // create a warning with -Wconversion + template , MotionTpl>::value, + bool>::type = true> explicit MotionTpl(const MotionBase & clone) { *this = clone; } diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt index f2c3095893..cf46e21919 100644 --- a/src/CMakeLists.txt +++ b/src/CMakeLists.txt @@ -44,17 +44,21 @@ MODERNIZE_TARGET_LINK_LIBRARIES(${PROJECT_NAME}_headers SCOPE INTERFACE INCLUDE_DIRS ${Boost_INCLUDE_DIRS}) TARGET_INCLUDE_DIRECTORIES(${PROJECT_NAME}_headers INTERFACE $) -IF(MSVC) - TARGET_COMPILE_OPTIONS(${PROJECT_NAME} PUBLIC "/bigobj") -ENDIF() +CXX_FLAGS_BY_COMPILER_FRONTEND( + MSVC "/bigobj" + OUTPUT PUBLIC_OPTIONS + FILTER) +TARGET_COMPILE_OPTIONS(${PROJECT_NAME} PUBLIC ${PUBLIC_OPTIONS}) SET_TARGET_PROPERTIES(${PROJECT_NAME} PROPERTIES VERSION ${PROJECT_VERSION}) IF(BUILD_WITH_COMMIT_VERSION) TAG_LIBRARY_VERSION(${PROJECT_NAME}) ENDIF(BUILD_WITH_COMMIT_VERSION) -IF(WIN32) - TARGET_COMPILE_DEFINITIONS(${PROJECT_NAME} PRIVATE -DNOMINMAX) -ENDIF(WIN32) + +CXX_FLAGS_BY_COMPILER_FRONTEND( + MSVC "NOMINMAX" + OUTPUT PUBLIC_DEFINITIONS) +TARGET_COMPILE_DEFINITIONS(${PROJECT_NAME} PUBLIC ${PUBLIC_DEFINITIONS}) MODERNIZE_TARGET_LINK_LIBRARIES(${PROJECT_NAME} SCOPE PUBLIC TARGETS Eigen3::Eigen diff --git a/unittest/CMakeLists.txt b/unittest/CMakeLists.txt index d2e71d578e..d0b87bc1f4 100644 --- a/unittest/CMakeLists.txt +++ b/unittest/CMakeLists.txt @@ -7,8 +7,15 @@ # --- MACROS ------------------------------------------------------------------ # --- MACROS ------------------------------------------------------------------ -MACRO(ADD_TEST_CFLAGS target flag) - SET_PROPERTY(TARGET "test-cpp-${target}" APPEND_STRING PROPERTY COMPILE_FLAGS " ${flag}") +# Compute flags outside the macro to avoid recomputing it for each tests +CXX_FLAGS_BY_COMPILER_FRONTEND( + MSVC _USE_MATH_DEFINES + OUTPUT TEST_PRIVATE_DEFINITIONS) + +MACRO(ADD_TEST_CFLAGS target) + foreach(ARG ${ARGN}) + SET_PROPERTY(TARGET "test-cpp-${target}" APPEND_STRING PROPERTY COMPILE_FLAGS "${ARG} ") + endforeach() ENDMACRO(ADD_TEST_CFLAGS) MACRO(ADD_PINOCCHIO_UNIT_TEST NAME) @@ -23,6 +30,14 @@ MACRO(ADD_PINOCCHIO_UNIT_TEST NAME) SET(TEST_NAME "test-cpp-${NAME}") ADD_UNIT_TEST(${TEST_NAME} ${NAME}.cpp) + SET(MODULE_NAME "${NAME}Test") + STRING(REPLACE "-" "_" MODULE_NAME ${MODULE_NAME}) + TARGET_COMPILE_DEFINITIONS(${TEST_NAME} + PRIVATE ${TEST_PRIVATE_DEFINITIONS} + BOOST_TEST_DYN_LINK + BOOST_TEST_MODULE=${MODULE_NAME} + PINOCCHIO_MODEL_DIR=\"${PINOCCHIO_MODEL_DIR}\") + # There is no RPATH in Windows, then we must use the PATH to find the DLL IF(WIN32) STRING(REPLACE ";" "\\\;" _PATH "$ENV{PATH}") @@ -33,15 +48,6 @@ MACRO(ADD_PINOCCHIO_UNIT_TEST NAME) SET_TARGET_PROPERTIES(${TEST_NAME} PROPERTIES LINKER_LANGUAGE CXX) TARGET_INCLUDE_DIRECTORIES(${TEST_NAME} PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}) - ADD_TEST_CFLAGS(${NAME} "-DBOOST_TEST_DYN_LINK") - SET(MODULE_NAME "${NAME}Test") - STRING(REPLACE "-" "_" MODULE_NAME ${MODULE_NAME}) - ADD_TEST_CFLAGS(${NAME} "-DBOOST_TEST_MODULE=${MODULE_NAME}") - ADD_TEST_CFLAGS(${NAME} "-DPINOCCHIO_MODEL_DIR=\\\\\"${PINOCCHIO_MODEL_DIR}\\\\\"") - IF(WIN32) - ADD_TEST_CFLAGS(${NAME} "-DNOMINMAX -D_USE_MATH_DEFINES") - ENDIF(WIN32) - IF(NOT unit_test_HEADER_ONLY) TARGET_LINK_LIBRARIES(${TEST_NAME} PUBLIC ${PROJECT_NAME}) ENDIF(NOT unit_test_HEADER_ONLY) @@ -160,7 +166,16 @@ ADD_PINOCCHIO_UNIT_TEST(finite-differences) ADD_PINOCCHIO_UNIT_TEST(visitor) ADD_PINOCCHIO_UNIT_TEST(algo-check) +# Warning ignore with pragma doesn't work for +# a part of this test, so we ignore two warning +# globally +CXX_FLAGS_BY_COMPILER_FRONTEND( + GNU -Wno-maybe-uninitialized -Wuse-after-free=0 + OUTPUT LIEGROUPS_OPTIONS + FILTER) ADD_PINOCCHIO_UNIT_TEST(liegroups) +ADD_TEST_CFLAGS(liegroups ${LIEGROUPS_OPTIONS}) + ADD_PINOCCHIO_UNIT_TEST(cartesian-product-liegroups) ADD_PINOCCHIO_UNIT_TEST(regressor) ADD_PINOCCHIO_UNIT_TEST(version) diff --git a/unittest/cartesian-product-liegroups.cpp b/unittest/cartesian-product-liegroups.cpp index 30b53bdea7..a035174982 100644 --- a/unittest/cartesian-product-liegroups.cpp +++ b/unittest/cartesian-product-liegroups.cpp @@ -72,15 +72,21 @@ struct TestCartesianProduct ConfigVector q0 = lg.random(); ConfigVector q1 = lg.random(); TangentVector v = TangentVector_t::Random(lg.nv()); +PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH +PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED ConfigVector qout_ref(lg.nq()), qout(lg.nq()); lg.integrate(q0, v, qout_ref); cp.integrate(q0, v, qout); +PINOCCHIO_COMPILER_DIAGNOSTIC_POP BOOST_CHECK(qout.isApprox(qout_ref)); +PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH +PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED TangentVector v_diff_ref(lg.nv()), v_diff(lg.nv()); lg.difference(q0,q1,v_diff_ref); cp.difference(q0,q1,v_diff); +PINOCCHIO_COMPILER_DIAGNOSTIC_POP BOOST_CHECK(v_diff_ref.isApprox(v_diff)); BOOST_CHECK_EQUAL(lg.squaredDistance(q0, q1), cp.squaredDistance(q0, q1)); @@ -111,6 +117,8 @@ struct TestCartesianProduct BOOST_CHECK(J.isApprox(J_ref)); BOOST_CHECK(cp.isSameConfiguration(q0,q0)); +PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH +PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED ConfigVector q_rand; cp.random(q_rand); ConfigVector q_rand_copy = q_rand; @@ -123,6 +131,7 @@ struct TestCartesianProduct const ConfigVector ub( ConfigVector::Ones(lg.nq())); cp.randomConfiguration(lb, ub, q_rand); +PINOCCHIO_COMPILER_DIAGNOSTIC_POP } }; diff --git a/unittest/explog.cpp b/unittest/explog.cpp index 208637fdba..0e16d9ebec 100644 --- a/unittest/explog.cpp +++ b/unittest/explog.cpp @@ -161,8 +161,11 @@ BOOST_AUTO_TEST_CASE(Jlog3_fd) SE3 M(SE3::Random()); SE3::Matrix3 R (M.rotation()); +PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH +PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED SE3::Matrix3 Jfd, Jlog; Jlog3 (R, Jlog); +PINOCCHIO_COMPILER_DIAGNOSTIC_POP Jfd.setZero(); Motion::Vector3 dR; dR.setZero(); @@ -184,12 +187,15 @@ BOOST_AUTO_TEST_CASE(Jexp3_fd) Motion::Vector3 v = log3(R); +PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH +PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED SE3::Matrix3 Jexp_fd, Jexp; Jexp3(Motion::Vector3::Zero(), Jexp); BOOST_CHECK(Jexp.isIdentity()); Jexp3(v, Jexp); +PINOCCHIO_COMPILER_DIAGNOSTIC_POP Motion::Vector3 dv; dv.setZero(); const double eps = 1e-8; @@ -221,8 +227,11 @@ BOOST_AUTO_TEST_CASE(Jexp3_quat_fd) SE3::Quaternion quat; quaternion::exp3(w,quat); typedef Eigen::Matrix Matrix43; +PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH +PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED Matrix43 Jexp3, Jexp3_fd; quaternion::Jexp3CoeffWise(w,Jexp3); +PINOCCHIO_COMPILER_DIAGNOSTIC_POP SE3::Vector3 dw; dw.setZero(); const double eps = 1e-8; @@ -235,11 +244,14 @@ BOOST_AUTO_TEST_CASE(Jexp3_quat_fd) } BOOST_CHECK(Jexp3.isApprox(Jexp3_fd,sqrt(eps))); +PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH +PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED SE3::Matrix3 Jlog; pinocchio::Jlog3(quat.toRotationMatrix(),Jlog); Matrix43 Jexp_quat_local; Jexp3QuatLocal(quat,Jexp_quat_local); +PINOCCHIO_COMPILER_DIAGNOSTIC_POP Matrix43 Jcompositon = Jexp3 * Jlog; @@ -274,7 +286,10 @@ BOOST_AUTO_TEST_CASE(Jexp3_quat) typedef Eigen::Matrix Matrix76; Matrix76 Jexp6_fd, Jexp6_quat; Jexp6_quat.setZero(); typedef Eigen::Matrix Matrix43; +PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH +PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED Matrix43 Jexp3_quat; Jexp3QuatLocal(quat,Jexp3_quat); +PINOCCHIO_COMPILER_DIAGNOSTIC_POP SE3 M_next; Jexp6_quat.middleRows<3>(Motion::LINEAR).middleCols<3>(Motion::LINEAR) = M.rotation(); @@ -296,10 +311,13 @@ BOOST_AUTO_TEST_CASE(Jexplog3) { Motion v(Motion::Random()); +PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH +PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED Eigen::Matrix3d R (exp3(v.angular())), Jexp, Jlog; Jexp3 (v.angular(), Jexp); Jlog3 (R , Jlog); +PINOCCHIO_COMPILER_DIAGNOSTIC_POP BOOST_CHECK((Jlog * Jexp).isIdentity()); @@ -319,9 +337,12 @@ BOOST_AUTO_TEST_CASE(Jlog3_quat) SE3::Matrix3 R(quat.toRotationMatrix()); +PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH +PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED SE3::Matrix3 res, res_ref; quaternion::Jlog3(quat,res); Jlog3(R,res_ref); +PINOCCHIO_COMPILER_DIAGNOSTIC_POP BOOST_CHECK(res.isApprox(res_ref)); } @@ -341,8 +362,11 @@ BOOST_AUTO_TEST_CASE(Jlog6_fd) { SE3 M(SE3::Random()); +PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH +PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED SE3::Matrix6 Jfd, Jlog; Jlog6 (M, Jlog); +PINOCCHIO_COMPILER_DIAGNOSTIC_POP Jfd.setZero(); Motion dM; dM.setZero(); @@ -363,8 +387,11 @@ BOOST_AUTO_TEST_CASE(Jlog6_of_product_fd) SE3 Ma(SE3::Random()); SE3 Mb(SE3::Random()); +PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH +PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED SE3::Matrix6 Jlog, Ja, Jb, Jfda, Jfdb; Jlog6 (Ma.inverse() * Mb, Jlog); +PINOCCHIO_COMPILER_DIAGNOSTIC_POP Ja = - Jlog * (Ma.inverse() * Mb).toActionMatrixInverse(); Jb = Jlog; Jfda.setZero(); diff --git a/unittest/liegroups.cpp b/unittest/liegroups.cpp index 065a6566eb..ae554a7938 100644 --- a/unittest/liegroups.cpp +++ b/unittest/liegroups.cpp @@ -243,6 +243,8 @@ struct LieGroup_Jdifference{ ConfigVector_t q[2], q_dv[2]; q[0] = lg.random(); q[1] = lg.random(); +PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH +PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED TangentVector_t va, vb, dv; JacobianMatrix_t J[2]; dv.setZero(); @@ -269,6 +271,7 @@ struct LieGroup_Jdifference{ EIGEN_VECTOR_IS_APPROX (vb_va, J_dv, 1e-2); dv[i] = 0; } +PINOCCHIO_COMPILER_DIAGNOSTIC_POP } specificTests(lg); @@ -374,9 +377,12 @@ struct LieGroup_Jintegrate{ ConfigVector_t q_v = lg.integrate (q, v); +PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH +PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED JacobianMatrix_t Jq, Jv; lg.dIntegrate_dq (q, v, Jq); lg.dIntegrate_dv (q, v, Jv); +PINOCCHIO_COMPILER_DIAGNOSTIC_POP const Scalar eps = 1e-6; for (int i = 0; i < v.size(); ++i) @@ -409,6 +415,8 @@ struct LieGroup_JintegrateJdifference{ typedef typename T::TangentVector_t TangentVector_t; typedef typename T::JacobianMatrix_t JacobianMatrix_t; +PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH +PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED T lg; BOOST_TEST_MESSAGE (lg.name()); ConfigVector_t qa, qb (lg.nq()); @@ -421,6 +429,7 @@ struct LieGroup_JintegrateJdifference{ lg.template dDifference (qa, qb, Jd_qb); lg.template dIntegrate (qa, v , Ji_v ); +PINOCCHIO_COMPILER_DIAGNOSTIC_POP BOOST_CHECK_MESSAGE ((Jd_qb * Ji_v).isIdentity(), "Jd_qb\n" << diff --git a/unittest/spatial.cpp b/unittest/spatial.cpp index 0da7ce1946..0fec8fd14a 100644 --- a/unittest/spatial.cpp +++ b/unittest/spatial.cpp @@ -707,6 +707,8 @@ BOOST_AUTO_TEST_CASE ( test_ActOnSet ) Motion v = Motion::Random(); // Forcet SET +PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH +PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED Matrix6N iF = Matrix6N::Random(),jF,jFinv,jF_ref,jFinv_ref; // forceSet::se3Action @@ -719,6 +721,7 @@ BOOST_AUTO_TEST_CASE ( test_ActOnSet ) forceSet::se3ActionInverse(jMi.inverse(),iF,jFinv); BOOST_CHECK(jFinv.isApprox(jF)); +PINOCCHIO_COMPILER_DIAGNOSTIC_POP Matrix6N iF2 = Matrix6N::Random(); jF_ref += jMi.toDualActionMatrix() * iF2; @@ -762,6 +765,8 @@ BOOST_AUTO_TEST_CASE ( test_ActOnSet ) BOOST_CHECK(jF.isApprox(jF_ref)); // Motion SET +PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH +PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED Matrix6N iV = Matrix6N::Random(),jV,jV_ref,jVinv,jVinv_ref; // motionSet::se3Action @@ -774,6 +779,7 @@ BOOST_AUTO_TEST_CASE ( test_ActOnSet ) motionSet::se3ActionInverse(jMi.inverse(),iV,jVinv); BOOST_CHECK(jVinv.isApprox(jV)); +PINOCCHIO_COMPILER_DIAGNOSTIC_POP Matrix6N iV2 = Matrix6N::Random(); jV_ref += jMi.toActionMatrix()*iV2; diff --git a/unittest/symmetric.cpp b/unittest/symmetric.cpp index b0e4b365e6..2da18f81a4 100644 --- a/unittest/symmetric.cpp +++ b/unittest/symmetric.cpp @@ -29,11 +29,6 @@ #include #include - -#include -EIGEN_DEFINE_STL_VECTOR_SPECIALIZATION(Eigen::Matrix3d) -EIGEN_DEFINE_STL_VECTOR_SPECIALIZATION(pinocchio::Symmetric3) - void timeSym3(const pinocchio::Symmetric3 & S, const pinocchio::Symmetric3::Matrix3 & R, pinocchio::Symmetric3 & res) diff --git a/utils/CMakeLists.txt b/utils/CMakeLists.txt index 1981319721..27e9bfe32e 100644 --- a/utils/CMakeLists.txt +++ b/utils/CMakeLists.txt @@ -30,7 +30,4 @@ ADD_CUSTOM_TARGET(utils) IF(urdfdom_FOUND) ADD_UTIL(pinocchio_read_model pinocchio_read_model) - IF(WIN32) - TARGET_COMPILE_DEFINITIONS(pinocchio_read_model PRIVATE -DNOMINMAX) - ENDIF(WIN32) ENDIF(urdfdom_FOUND)