Skip to content

Commit

Permalink
[core] Remove O2 specific warnings
Browse files Browse the repository at this point in the history
  • Loading branch information
jorisv committed Jan 29, 2024
1 parent bea7367 commit e67b023
Show file tree
Hide file tree
Showing 7 changed files with 19 additions and 4 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -496,7 +496,7 @@ namespace pinocchio

typedef Eigen::Matrix<Scalar,3,1,_Options> Vector3;

JointModelPrismaticUnalignedTpl() {}
JointModelPrismaticUnalignedTpl(): axis(Vector3::UnitX()) {}
JointModelPrismaticUnalignedTpl(const Scalar & x,
const Scalar & y,
const Scalar & z)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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,
Expand Down
6 changes: 6 additions & 0 deletions include/pinocchio/multibody/liegroup/special-euclidean.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -222,9 +222,12 @@ namespace pinocchio
const Eigen::MatrixBase<ConfigR_t> & q1,
const Eigen::MatrixBase<Tangent_t> & 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));

Expand All @@ -236,9 +239,12 @@ namespace pinocchio
const Eigen::MatrixBase<ConfigR_t> & q1,
const Eigen::MatrixBase<JacobianOut_t>& 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));

Expand Down
3 changes: 3 additions & 0 deletions unittest/cartesian-product-liegroups.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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));

Expand Down
6 changes: 6 additions & 0 deletions unittest/explog.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();
Expand Down Expand Up @@ -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));
}
Expand Down
2 changes: 1 addition & 1 deletion unittest/spatial.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<N;++k )
BOOST_CHECK(jMi.act(Motion(iV.col(k))).toVector().isApprox(jV.col(k)));

Expand All @@ -780,6 +779,7 @@ PINOCCHIO_COMPILER_DIAGNOSTIC_POP

motionSet::se3ActionInverse(jMi.inverse(),iV,jVinv);
BOOST_CHECK(jVinv.isApprox(jV));
PINOCCHIO_COMPILER_DIAGNOSTIC_POP

Matrix6N iV2 = Matrix6N::Random();
jV_ref += jMi.toActionMatrix()*iV2;
Expand Down

0 comments on commit e67b023

Please sign in to comment.