Skip to content

Commit

Permalink
[UnitTest] Avoid the external call to BOOST_CHECK macros, to obtain e…
Browse files Browse the repository at this point in the history
…xplicit messages.

Remove
  • Loading branch information
nmansard authored and nmansard committed Jun 16, 2015
1 parent 763e6ae commit 8deb921
Show file tree
Hide file tree
Showing 13 changed files with 223 additions and 261 deletions.
1 change: 0 additions & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,6 @@ SET(${PROJECT_NAME}_MATH_HEADERS

SET(${PROJECT_NAME}_TOOLS_HEADERS
tools/timer.hpp
tools/matrix-comparison.hpp
)

SET(${PROJECT_NAME}_SPATIAL_HEADERS
Expand Down
39 changes: 0 additions & 39 deletions src/tools/matrix-comparison.hpp

This file was deleted.

16 changes: 8 additions & 8 deletions unittest/cholesky.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,31 +70,31 @@ BOOST_AUTO_TEST_CASE ( test_cholesky )
std::cout << "D = [\n" << D.transpose() << "];" << std::endl;
#endif

is_matrix_absolutely_closed(M, U*D.asDiagonal()*U.transpose() , 1e-12);
BOOST_CHECK( M.isApprox(U*D.asDiagonal()*U.transpose() ,1e-12) );

Eigen::VectorXd v = Eigen::VectorXd::Random(model.nv);
// std::cout << "v = [" << v.transpose() << "]';" << std::endl;

Eigen::VectorXd Uv = v; se3::cholesky::Uv(model,data,Uv);
is_matrix_absolutely_closed(Uv, U*v, 1e-12);
BOOST_CHECK( Uv.isApprox(U*v,1e-12) );

Eigen::VectorXd Utv = v; se3::cholesky::Utv(model,data,Utv);
is_matrix_absolutely_closed(Utv, U.transpose()*v, 1e-12);
BOOST_CHECK( Utv.isApprox(U.transpose()*v,1e-12) );

Eigen::VectorXd Uiv = v; se3::cholesky::Uiv(model,data,Uiv);
is_matrix_absolutely_closed(Uiv, U.inverse()*v, 1e-12);
BOOST_CHECK( Uiv.isApprox(U.inverse()*v,1e-12) );


Eigen::VectorXd Utiv = v; se3::cholesky::Utiv(model,data,Utiv);
is_matrix_absolutely_closed(Utiv, U.transpose().inverse()*v, 1e-12);
BOOST_CHECK( Utiv.isApprox(U.transpose().inverse()*v,1e-12) );

Eigen::VectorXd Miv = v; se3::cholesky::solve(model,data,Miv);
is_matrix_absolutely_closed(Miv, M.inverse()*v, 1e-12);
BOOST_CHECK( Miv.isApprox(M.inverse()*v,1e-12) );

Eigen::VectorXd Mv = v; se3::cholesky::Mv(model,data,Mv,true);
is_matrix_absolutely_closed(Mv, M*v, 1e-12);
BOOST_CHECK( Mv.isApprox(M*v,1e-12) );
Mv = v; se3::cholesky::Mv(model,data,Mv,false);
is_matrix_absolutely_closed(Mv, M*v, 1e-12);
BOOST_CHECK( Mv.isApprox(M*v,1e-12) );
}


Expand Down
6 changes: 3 additions & 3 deletions unittest/com.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,17 +51,17 @@ BOOST_AUTO_TEST_CASE ( test_com )

/* Test COM against CRBA*/
Vector3d com = centerOfMass(model,data,q);
is_matrix_absolutely_closed(data.com[0], getComFromCrba(model,data), 1e-12);
BOOST_CHECK( data.com[0].isApprox(getComFromCrba(model,data),1e-12) );


/* Test COM against Jcom (both use different way of compute the COM. */
com = centerOfMass(model,data,q);
jacobianCenterOfMass(model,data,q);
is_matrix_absolutely_closed(com, data.com[0], 1e-12);
BOOST_CHECK( com.isApprox(data.com[0],1e-12) );

/* Test Jcom against CRBA */
Eigen::MatrixXd Jcom = jacobianCenterOfMass(model,data,q);
is_matrix_absolutely_closed(Jcom, getJacobianComFromCrba(model,data), 1e-12);
BOOST_CHECK( Jcom.isApprox(getJacobianComFromCrba(model,data),1e-12) );


std::cout << "com = [ " << data.com[0].transpose() << " ];" << std::endl;
Expand Down
28 changes: 16 additions & 12 deletions unittest/compute-all-terms.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -72,9 +72,10 @@ BOOST_AUTO_TEST_CASE ( test_against_algo )
crba(model,data_other,q);
computeJacobians(model,data_other,q);

is_matrix_absolutely_closed (data.nle, data_other.nle);
is_matrix_absolutely_closed (data.M.triangularView<Eigen::Upper>(), data_other.M.triangularView<Eigen::Upper>());
is_matrix_absolutely_closed (data.J, data_other.J);
BOOST_CHECK( data.nle.isApprox(data_other.nle,1e-12) );
BOOST_CHECK( Eigen::MatrixXd(data.M.triangularView<Eigen::Upper>())
.isApprox(Eigen::MatrixXd(data_other.M.triangularView<Eigen::Upper>()),1e-12) );
BOOST_CHECK( data.J.isApprox(data_other.J,1e-12) );

// -------
q.setZero ();
Expand All @@ -86,9 +87,10 @@ BOOST_AUTO_TEST_CASE ( test_against_algo )
crba(model,data_other,q);
computeJacobians(model,data_other,q);

is_matrix_absolutely_closed (data.nle, data_other.nle);
is_matrix_absolutely_closed (data.M.triangularView<Eigen::Upper>(), data_other.M.triangularView<Eigen::Upper>());
is_matrix_absolutely_closed (data.J, data_other.J);
BOOST_CHECK( data.nle.isApprox(data_other.nle,1e-12) );
BOOST_CHECK( Eigen::MatrixXd(data.M.triangularView<Eigen::Upper>())
.isApprox(Eigen::MatrixXd(data_other.M.triangularView<Eigen::Upper>()),1e-12) );
BOOST_CHECK( data.J.isApprox(data_other.J,1e-12) );

// -------
q.setOnes ();
Expand All @@ -100,9 +102,10 @@ BOOST_AUTO_TEST_CASE ( test_against_algo )
crba(model,data_other,q);
computeJacobians(model,data_other,q);

is_matrix_absolutely_closed (data.nle, data_other.nle);
is_matrix_absolutely_closed (data.M.triangularView<Eigen::Upper>(), data_other.M.triangularView<Eigen::Upper>());
is_matrix_absolutely_closed (data.J, data_other.J);
BOOST_CHECK( data.nle.isApprox(data_other.nle,1e-12) );
BOOST_CHECK( Eigen::MatrixXd(data.M.triangularView<Eigen::Upper>())
.isApprox(Eigen::MatrixXd(data_other.M.triangularView<Eigen::Upper>()),1e-12) );
BOOST_CHECK( data.J.isApprox(data_other.J,1e-12) );

// -------
q.setRandom ();
Expand All @@ -114,9 +117,10 @@ BOOST_AUTO_TEST_CASE ( test_against_algo )
crba(model,data_other,q);
computeJacobians(model,data_other,q);

is_matrix_absolutely_closed (data.nle, data_other.nle);
is_matrix_absolutely_closed (data.M.triangularView<Eigen::Upper>(), data_other.M.triangularView<Eigen::Upper>());
is_matrix_absolutely_closed (data.J, data_other.J);
BOOST_CHECK( data.nle.isApprox(data_other.nle,1e-12) );
BOOST_CHECK( Eigen::MatrixXd(data.M.triangularView<Eigen::Upper>())
.isApprox(Eigen::MatrixXd(data_other.M.triangularView<Eigen::Upper>()),1e-12) );
BOOST_CHECK( data.J.isApprox(data_other.J,1e-12) );
}

BOOST_AUTO_TEST_SUITE_END ()
18 changes: 8 additions & 10 deletions unittest/constraint.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,22 +56,21 @@ BOOST_AUTO_TEST_CASE ( test_ForceSet )
ForceSet F3(Eigen::Matrix<double,3,12>::Random(),Eigen::Matrix<double,3,12>::Random());
ForceSet F4 = amb.act(F3);
SE3::Matrix6 aXb= amb;
is_matrix_absolutely_closed((aXb.transpose().inverse()*F3.matrix()), F4.matrix(), 1e-12);
BOOST_CHECK( (aXb.transpose().inverse()*F3.matrix()).isApprox(F4.matrix(),1e-12) );


ForceSet bF = bmc.act(F3);
ForceSet aF = amb.act(bF);
ForceSet aF2 = amc.act(F3);
is_matrix_absolutely_closed(aF.matrix(), aF2.matrix(), 1e-12);
BOOST_CHECK( aF.matrix().isApprox(aF2.matrix(),1e-12) );

ForceSet F36 = amb.act(F3.block(3,6));
is_matrix_absolutely_closed((aXb.transpose().inverse()*F3.matrix().block(0,3,6,6)), F36.matrix(), 1e-12);
BOOST_CHECK( (aXb.transpose().inverse()*F3.matrix().block(0,3,6,6)).isApprox(F36.matrix(),1e-12) );


ForceSet F36full(12); F36full.block(3,6) = amb.act(F3.block(3,6));
is_matrix_absolutely_closed((aXb.transpose().inverse()*F3.matrix().block(0,3,6,6)),
F36full.matrix().block(0,3,6,6),
1e-12);
BOOST_CHECK( aXb.transpose().inverse()*F3.matrix().block(0,3,6,6)
.isApprox(F36full.matrix().block(0,3,6,6),1e-12) );
}

BOOST_AUTO_TEST_CASE ( test_ConstraintRX )
Expand All @@ -87,13 +86,12 @@ BOOST_AUTO_TEST_CASE ( test_ConstraintRX )
ForceSet F(1); F.block(0,1) = Y*S;
std::cout << "Y*S = \n" << (Y*S).matrix() << std::endl;
std::cout << "F=Y*S = \n" << F.matrix() << std::endl;
is_matrix_absolutely_closed(F.matrix(), Y.toMatrix().col(3), 1e-12);
BOOST_CHECK( F.matrix().isApprox(Y.toMatrix().col(3),1e-12) );

ForceSet F2( Eigen::Matrix<double,3,9>::Random(),Eigen::Matrix<double,3,9>::Random() );
Eigen::MatrixXd StF2 = S.transpose()*F2.block(5,3);
is_matrix_absolutely_closed(StF2,
ConstraintXd(S).matrix().transpose()*F2.matrix().block(0,5,6,3),
1e-12);
BOOST_CHECK( StF2.isApprox
(ConstraintXd(S).matrix().transpose()*F2.matrix().block(0,5,6,3),1e-12) );
}

BOOST_AUTO_TEST_SUITE_END ()
Expand Down
2 changes: 1 addition & 1 deletion unittest/crba.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -82,7 +82,7 @@ BOOST_AUTO_TEST_CASE ( test_crba )

// std::cout << "Mcrb = [ " << data.M << " ];" << std::endl;
// std::cout << "Mrne = [ " << M << " ]; " << std::endl;
is_matrix_absolutely_closed(M,data.M,1e-12);
BOOST_CHECK( M.isApprox(data.M,1e-12) );

std::cout << "(the time score in debug mode is not relevant) " ;

Expand Down
6 changes: 3 additions & 3 deletions unittest/jacobian.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,20 +53,20 @@ BOOST_AUTO_TEST_CASE ( test_jacobian )
VectorXd qddot = VectorXd::Zero(model.nv);
rnea( model,data,q,qdot,qddot );
Motion v = data.oMi[(std::size_t)idx].act( data.v[(std::size_t)idx] );
is_matrix_absolutely_closed(v.toVector(),Jrh*qdot,1e-12);
BOOST_CHECK( v.toVector().isApprox(Jrh*qdot,1e-12) );


/* Test local jacobian: rhJrh == rhXo oJrh */
MatrixXd rhJrh(6,model.nv); rhJrh.fill(0);
getJacobian<true>(model,data,idx,rhJrh);
MatrixXd XJrh(6,model.nv);
motionSet::se3Action( data.oMi[(std::size_t)idx].inverse(), Jrh,XJrh );
is_matrix_absolutely_closed(XJrh,rhJrh,1e-12);
BOOST_CHECK( XJrh.isApprox(rhJrh,1e-12) );


data.J.fill(0);
XJrh = jacobian(model,data,q,idx);
is_matrix_absolutely_closed(XJrh,rhJrh,1e-12);
BOOST_CHECK( XJrh.isApprox(rhJrh,1e-12) );

}

Expand Down
Loading

0 comments on commit 8deb921

Please sign in to comment.