20 #include <pinocchio/spatial/skew.hpp> 22 #include <boost/test/unit_test.hpp> 25 void udut( Eigen::Matrix<double,N,N> & M )
27 typedef Eigen::Matrix<double,N,N> MatrixNd;
28 typedef Eigen::Matrix<double,1,N> VectorNd;
29 typedef typename MatrixNd::DiagonalReturnType D_t;
30 typedef typename MatrixNd::template TriangularViewReturnType<Eigen::StrictlyUpper>::Type U_t;
34 U_t
U = M.template triangularView<Eigen::StrictlyUpper>();
36 for(
int j=
N-1;j>=0;--j )
38 typename VectorNd::SegmentReturnType DUt = tmp.tail(
N-j-1);
39 if( j<
N-1 ) DUt = M.row(j).tail(
N-j-1).transpose().cwiseProduct( D.tail(
N-j-1) );
41 D[j] -= M.row(j).tail(
N-j-1).dot(DUt);
43 for(
int i=j-1;
i>=0;--
i)
44 {
U(
i,j) -= M.row(
i).tail(
N-j-1).dot(DUt);
U(
i,j) /= D[j]; }
48 BOOST_AUTO_TEST_SUITE ( BOOST_TEST_MODULE )
52 using namespace Eigen;
54 Matrix<double,6,6>
A = Matrix<double,6,6>::Random();
A =
A*
A.transpose();
56 Matrix3d I =
A.bottomRightCorner<3,3>();
57 Vector3d
c =
A.block<3,1>(0,3);
59 A.topLeftCorner<3,3>() = Matrix3d::Identity()*m;
62 A.bottomRightCorner<3,3>() -=
A.bottomLeftCorner<3,3>()*
A.bottomLeftCorner<3,3>();
64 std::cout <<
"A = [\n" <<
A <<
"];" << std::endl;
66 std::cout <<
"U = [\n" <<
A <<
"];" << std::endl;
69 BOOST_AUTO_TEST_SUITE_END()
BOOST_AUTO_TEST_CASE(udut)
void udut(Eigen::Matrix< double, N, N > &M)