udut.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2015 CNRS
3 //
4 // This file is part of Pinocchio
5 // Pinocchio is free software: you can redistribute it
6 // and/or modify it under the terms of the GNU Lesser General Public
7 // License as published by the Free Software Foundation, either version
8 // 3 of the License, or (at your option) any later version.
9 //
10 // Pinocchio is distributed in the hope that it will be
11 // useful, but WITHOUT ANY WARRANTY; without even the implied warranty
12 // of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
13 // General Lesser Public License for more details. You should have
14 // received a copy of the GNU Lesser General Public License along with
15 // Pinocchio If not, see
16 // <http://www.gnu.org/licenses/>.
17 
18 #include <iostream>
19 #include <Eigen/Core>
20 #include <pinocchio/spatial/skew.hpp>
21 
22 #include <boost/test/unit_test.hpp>
23 
24 template<int N>
25 void udut( Eigen::Matrix<double,N,N> & M )
26 {
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;
31 
32  VectorNd tmp;
33  D_t D = M.diagonal();
34  U_t U = M.template triangularView<Eigen::StrictlyUpper>();
35 
36  for(int j=N-1;j>=0;--j )
37  {
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) );
40 
41  D[j] -= M.row(j).tail(N-j-1).dot(DUt);
42 
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]; }
45  }
46  }
47 
48 BOOST_AUTO_TEST_SUITE ( BOOST_TEST_MODULE )
49 
51 {
52  using namespace Eigen;
53 
54  Matrix<double,6,6> A = Matrix<double,6,6>::Random(); A = A*A.transpose();
55  double m = A(1,1);
56  Matrix3d I = A.bottomRightCorner<3,3>();
57  Vector3d c = A.block<3,1>(0,3);
58 
59  A.topLeftCorner<3,3>() = Matrix3d::Identity()*m;
60  A.topRightCorner<3,3>() = se3::skew(c).transpose();
61  A.bottomLeftCorner<3,3>() = se3::skew(c);
62  A.bottomRightCorner<3,3>() -= A.bottomLeftCorner<3,3>()*A.bottomLeftCorner<3,3>();
63 
64  std::cout << "A = [\n" << A << "];" << std::endl;
65  udut(A);
66  std::cout << "U = [\n" << A << "];" << std::endl;
67 }
68 
69 BOOST_AUTO_TEST_SUITE_END()
c
Definition: ocp.py:61
D
BOOST_AUTO_TEST_CASE(udut)
Definition: udut.cpp:50
U
Definition: ocp.py:61
void udut(Eigen::Matrix< double, N, N > &M)
Definition: udut.cpp:25
A


pinocchio
Author(s):
autogenerated on Tue Jun 1 2021 02:45:05