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/special-euclidean.hpp b/include/pinocchio/multibody/liegroup/special-euclidean.hpp index 2e30987d6c..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,9 +239,12 @@ 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)); diff --git a/unittest/cartesian-product-liegroups.cpp b/unittest/cartesian-product-liegroups.cpp index 000767aae8..a035174982 100644 --- a/unittest/cartesian-product-liegroups.cpp +++ b/unittest/cartesian-product-liegroups.cpp @@ -72,9 +72,12 @@ 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)); diff --git a/unittest/explog.cpp b/unittest/explog.cpp index 16cd57c725..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(); @@ -334,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)); } diff --git a/unittest/spatial.cpp b/unittest/spatial.cpp index 56608fbc5e..0fec8fd14a 100644 --- a/unittest/spatial.cpp +++ b/unittest/spatial.cpp @@ -771,7 +771,6 @@ PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED // motionSet::se3Action motionSet::se3Action(jMi,iV,jV); -PINOCCHIO_COMPILER_DIAGNOSTIC_POP for( int k=0;k