crba.cpp 5.63 KB
Newer Older
1
//
2
// Copyright (c) 2015-2017 CNRS
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
//
// This file is part of Pinocchio
// Pinocchio is free software: you can redistribute it
// and/or modify it under the terms of the GNU Lesser General Public
// License as published by the Free Software Foundation, either version
// 3 of the License, or (at your option) any later version.
//
// Pinocchio is distributed in the hope that it will be
// useful, but WITHOUT ANY WARRANTY; without even the implied warranty
// of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
// General Lesser Public License for more details. You should have
// received a copy of the GNU Lesser General Public License along with
// Pinocchio If not, see
// <http://www.gnu.org/licenses/>.

18
19
20
21
22
23
24
25
/*
 * Test the CRBA algorithm. The code validates both the computation times and
 * the value by comparing the results of the CRBA with the reconstruction of
 * the mass matrix using the RNEA.
 * For a strong timing benchmark, see benchmark/timings.
 *
 */

26
27
28
#include "pinocchio/multibody/model.hpp"
#include "pinocchio/algorithm/crba.hpp"
#include "pinocchio/algorithm/rnea.hpp"
29
#include "pinocchio/algorithm/center-of-mass.hpp"
30
#include "pinocchio/parsers/sample-models.hpp"
Nicolas Mansard's avatar
Nicolas Mansard committed
31
#include "pinocchio/tools/timer.hpp"
32
33
34

#include <iostream>

35
36
#include <boost/test/unit_test.hpp>
#include <boost/utility/binary.hpp>
37

38
BOOST_AUTO_TEST_SUITE ( BOOST_TEST_MODULE )
39

40
BOOST_AUTO_TEST_CASE ( test_crba )
Nicolas Mansard's avatar
Nicolas Mansard committed
41
42
43
44
{
  se3::Model model;
  se3::buildModels::humanoidSimple(model);
  se3::Data data(model);
45
46
  
  #ifdef NDEBUG
47
    #ifdef _INTENSE_TESTING_
48
      const size_t NBT = 1000*1000;
49
    #else
50
      const size_t NBT = 10;
51
    #endif
52

53
    Eigen::VectorXd q = Eigen::VectorXd::Zero(model.nq);
54
 
55
56
57
58
59
60
    StackTicToc timer(StackTicToc::US); timer.tic();
    SMOOTH(NBT)
      {
        crba(model,data,q);
      }
    timer.toc(std::cout,NBT);
61
62
  
  #else
63
    const size_t NBT = 1;
64
65
    using namespace Eigen;
    using namespace se3;
66

67
    Eigen::MatrixXd M(model.nv,model.nv);
68
69
    Eigen::VectorXd q = Eigen::VectorXd::Ones(model.nq);
    q.segment <4> (3).normalize();
70
71
72
73
    Eigen::VectorXd v = Eigen::VectorXd::Zero(model.nv);
    Eigen::VectorXd a = Eigen::VectorXd::Zero(model.nv);
    data.M.fill(0);  crba(model,data,q);
    data.M.triangularView<Eigen::StrictlyLower>() = data.M.transpose().triangularView<Eigen::StrictlyLower>();
74

75
76
77
    /* Joint inertia from iterative crba. */
    const Eigen::VectorXd bias = rnea(model,data,q,v,a);
    for(int i=0;i<model.nv;++i)
78
79
80
    {
      M.col(i) = rnea(model,data,q,v,Eigen::VectorXd::Unit(model.nv,i)) - bias;
    }
81

82
83
    // std::cout << "Mcrb = [ " << data.M << "  ];" << std::endl;
    // std::cout << "Mrne = [  " << M << " ]; " << std::endl;
84
    BOOST_CHECK(M.isApprox(data.M,1e-12));
85
86
87
88
89
90
91
    
    std::cout << "(the time score in debug mode is not relevant)  " ;
    
    q = Eigen::VectorXd::Zero(model.nq);
   
    StackTicToc timer(StackTicToc::US); timer.tic();
    SMOOTH(NBT)
92
93
94
    {
      crba(model,data,q);
    }
95
    timer.toc(std::cout,NBT);
96
  
97
  #endif // ifndef NDEBUG
98
99

}
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
  
BOOST_AUTO_TEST_CASE (test_ccrb)
{
  se3::Model model;
  se3::buildModels::humanoidSimple(model);
  se3::Data data(model), data_ref(model);
  
  Eigen::VectorXd q = Eigen::VectorXd::Ones(model.nq);
  q.segment <4> (3).normalize();
  Eigen::VectorXd v = Eigen::VectorXd::Ones(model.nv);
  
  crba(model,data_ref,q);
  data_ref.M.triangularView<Eigen::StrictlyLower>() = data_ref.M.transpose().triangularView<Eigen::StrictlyLower>();
  data_ref.Ycrb[0] = data_ref.liMi[1].act(data_ref.Ycrb[1]);
  
  se3::SE3 cMo (se3::SE3::Matrix3::Identity(), -getComFromCrba(model, data_ref));
  
  ccrba(model, data, q, v);
  BOOST_CHECK(data.com[0].isApprox(-cMo.translation(),1e-12));
  BOOST_CHECK(data.Ycrb[0].matrix().isApprox(data_ref.Ycrb[0].matrix(),1e-12));
  
  se3::Inertia Ig_ref (cMo.act(data.Ycrb[0]));
  BOOST_CHECK(data.Ig.matrix().isApprox(Ig_ref.matrix(),1e-12));
  
  se3::SE3 oM1 (data_ref.liMi[1]);
  se3::SE3 cM1 (cMo * oM1);
  
  se3::Data::Matrix6x Ag_ref (cM1.inverse().toActionMatrix().transpose() * data_ref.M.topRows <6> ());
  BOOST_CHECK(data.Ag.isApprox(Ag_ref,1e-12));
}
130
131
132
133
134
135
136
137
138
139
  
  BOOST_AUTO_TEST_CASE (test_dccrb)
  {
    using namespace se3;
    Model model;
    buildModels::humanoidSimple(model);
    Data data(model), data_ref(model);
    
    Eigen::VectorXd q = Eigen::VectorXd::Ones(model.nq);
    q.segment <4> (3).normalize();
140
141
    Eigen::VectorXd v = Eigen::VectorXd::Random(model.nv);
    Eigen::VectorXd a = Eigen::VectorXd::Random(model.nv);
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
    
    const Eigen::VectorXd g = rnea(model,data_ref,q,0*v,0*a);
    rnea(model,data_ref,q,v,a);
    
    crba(model,data_ref,q);
    data_ref.M.triangularView<Eigen::StrictlyLower>() = data_ref.M.transpose().triangularView<Eigen::StrictlyLower>();
    
    SE3::Vector3 com = data_ref.Ycrb[1].lever();
    SE3 cMo(SE3::Identity());
    cMo.translation() = -getComFromCrba(model, data_ref);
    
    
    SE3 oM1 (data_ref.liMi[1]);
    SE3 cM1 (cMo * oM1);
    Data::Matrix6x Ag_ref (cM1.toDualActionMatrix() * data_ref.M.topRows <6> ());

    Force hdot_ref(cM1.act(Force(data_ref.tau.head<6>() - g.head<6>())));
    
    ccrba(model,data_ref,q,v);
    dccrba(model,data,q,0*v);
    BOOST_CHECK(data.Ag.isApprox(Ag_ref));
    BOOST_CHECK(data.Ag.isApprox(data_ref.Ag));
    BOOST_CHECK(data.dAg.isZero());
    
    
    centerOfMass(model,data_ref,q,v,a);
    BOOST_CHECK(data_ref.vcom[0].isApprox(data_ref.hg.linear()/data_ref.M(0,0)));
    BOOST_CHECK(data_ref.acom[0].isApprox(hdot_ref.linear()/data_ref.M(0,0)));
    dccrba(model,data,q,v);
    
    Force::Vector6 test1(data.Ag * a);
    Force::Vector6 test2(data.dAg * v);
    
    
    Force hdot(data.Ag * a + data.dAg * v);
    BOOST_CHECK(hdot.isApprox(hdot_ref));
    
  }
180
181
182

BOOST_AUTO_TEST_SUITE_END ()