joint-jacobian.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2015-2019 CNRS INRIA
3 //
4 
5 #include "pinocchio/multibody/model.hpp"
6 #include "pinocchio/multibody/data.hpp"
7 #include "pinocchio/algorithm/jacobian.hpp"
8 #include "pinocchio/algorithm/kinematics.hpp"
9 #include "pinocchio/algorithm/rnea.hpp"
10 #include "pinocchio/spatial/act-on-set.hpp"
11 #include "pinocchio/parsers/sample-models.hpp"
12 #include "pinocchio/utils/timer.hpp"
13 #include "pinocchio/algorithm/joint-configuration.hpp"
14 
15 #include <iostream>
16 
17 #include <boost/test/unit_test.hpp>
18 #include <boost/utility/binary.hpp>
19 
20 template<typename Derived>
21 inline bool isFinite(const Eigen::MatrixBase<Derived> & x)
22 {
23  return ((x - x).array() == (x - x).array()).all();
24 }
25 
26 BOOST_AUTO_TEST_SUITE ( BOOST_TEST_MODULE )
27 
28 BOOST_AUTO_TEST_CASE ( test_jacobian )
29 {
30  using namespace Eigen;
31  using namespace pinocchio;
32 
35  pinocchio::Data data(model);
36 
37  VectorXd q = VectorXd::Zero(model.nq);
38  computeJointJacobians(model,data,q);
39 
40  Model::Index idx = model.existJointName("rarm2")?model.getJointId("rarm2"):(Model::Index)(model.njoints-1);
41  Data::Matrix6x Jrh(6,model.nv); Jrh.fill(0);
42  getJointJacobian(model,data,idx,WORLD,Jrh);
43 
44  /* Test J*q == v */
45  VectorXd qdot = VectorXd::Random(model.nv);
46  VectorXd qddot = VectorXd::Zero(model.nv);
47  rnea( model,data,q,qdot,qddot );
48  Motion v = data.oMi[idx].act( data.v[idx] );
49  BOOST_CHECK(v.toVector().isApprox(Jrh*qdot,1e-12));
50 
51 
52  /* Test local jacobian: rhJrh == rhXo oJrh */
53  Data::Matrix6x rhJrh(6,model.nv); rhJrh.fill(0);
54  getJointJacobian(model,data,idx,LOCAL,rhJrh);
55  Data::Matrix6x XJrh(6,model.nv);
56  motionSet::se3Action( data.oMi[idx].inverse(), Jrh,XJrh );
57  BOOST_CHECK(XJrh.isApprox(rhJrh,1e-12));
58 
59  XJrh.setZero();
60  Data data_jointJacobian(model);
61  computeJointJacobian(model,data_jointJacobian,q,idx,XJrh);
62  BOOST_CHECK(XJrh.isApprox(rhJrh,1e-12));
63 
64  /* Test computeJointJacobians with pre-computation of the forward kinematics */
65  Data data_fk(model);
66  forwardKinematics(model, data_fk, q);
67  computeJointJacobians(model, data_fk);
68 
69  BOOST_CHECK(data_fk.J.isApprox(data.J));
70 
71 }
72 
73 BOOST_AUTO_TEST_CASE ( test_jacobian_time_variation )
74 {
75  using namespace Eigen;
76  using namespace pinocchio;
77 
80  pinocchio::Data data(model);
81  pinocchio::Data data_ref(model);
82 
83  VectorXd q = randomConfiguration(model, -1 * Eigen::VectorXd::Ones(model.nq), Eigen::VectorXd::Ones(model.nq) );
84  VectorXd v = VectorXd::Random(model.nv);
85  VectorXd a = VectorXd::Random(model.nv);
86 
87  computeJointJacobiansTimeVariation(model,data,q,v);
88 
89  BOOST_CHECK(isFinite(data.dJ));
90 
91  forwardKinematics(model,data_ref,q,v,a);
92  Model::Index idx = model.existJointName("rarm2")?model.getJointId("rarm2"):(Model::Index)(model.njoints-1);
93 
94  Data::Matrix6x J(6,model.nv); J.fill(0.);
95  Data::Matrix6x dJ(6,model.nv); dJ.fill(0.);
96 
97  // Regarding to the WORLD origin
98  getJointJacobian(model,data,idx,WORLD,J);
99  getJointJacobianTimeVariation(model,data,idx,WORLD,dJ);
100 
101  Motion v_idx(J*v);
102  BOOST_CHECK(v_idx.isApprox(data_ref.oMi[idx].act(data_ref.v[idx])));
103 
104  Motion a_idx(J*a + dJ*v);
105  const Motion & a_ref = data_ref.oMi[idx].act(data_ref.a[idx]);
106  BOOST_CHECK(a_idx.isApprox(a_ref));
107 
108  // Regarding to the LOCAL frame
109  getJointJacobian(model,data,idx,LOCAL,J);
110  getJointJacobianTimeVariation(model,data,idx,LOCAL,dJ);
111 
112  v_idx = (Motion::Vector6)(J*v);
113  BOOST_CHECK(v_idx.isApprox(data_ref.v[idx]));
114 
115  a_idx = (Motion::Vector6)(J*a + dJ*v);
116  BOOST_CHECK(a_idx.isApprox(data_ref.a[idx]));
117 
118  // Regarding to the LOCAL_WORLD_ALIGNED frame
119  getJointJacobian(model,data,idx,LOCAL_WORLD_ALIGNED,J);
121 
122  Data::SE3 worldMlocal = data.oMi[idx];
123  worldMlocal.translation().setZero();
124 
125  v_idx = (Motion::Vector6)(J*v);
126  BOOST_CHECK(v_idx.isApprox(worldMlocal.act(data_ref.v[idx])));
127 
128  a_idx = (Motion::Vector6)(J*a + dJ*v);
129  BOOST_CHECK(a_idx.isApprox(worldMlocal.act(data_ref.a[idx])));
130 
131  // compare to finite differencies : WORLD
132  {
133  Data data_ref(model), data_ref_plus(model);
134 
135  const double alpha = 1e-8;
136  Eigen::VectorXd q_plus(model.nq);
137  q_plus = integrate(model,q,alpha*v);
138 
139  Data::Matrix6x J_ref(6,model.nv); J_ref.fill(0.);
140  computeJointJacobians(model,data_ref,q);
141  getJointJacobian(model,data_ref,idx,WORLD,J_ref);
142 
143  Data::Matrix6x J_ref_plus(6,model.nv); J_ref_plus.fill(0.);
144  computeJointJacobians(model,data_ref_plus,q_plus);
145  getJointJacobian(model,data_ref_plus,idx,WORLD,J_ref_plus);
146 
147  Data::Matrix6x dJ_ref(6,model.nv); dJ_ref.fill(0.);
148  dJ_ref = (J_ref_plus - J_ref)/alpha;
149 
150  computeJointJacobiansTimeVariation(model,data,q,v);
151  Data::Matrix6x dJ(6,model.nv); dJ.fill(0.);
152  getJointJacobianTimeVariation(model,data,idx,WORLD,dJ);
153 
154  BOOST_CHECK(dJ.isApprox(dJ_ref,sqrt(alpha)));
155  }
156 
157  // compare to finite differencies : LOCAL
158  {
159  Data data_ref(model), data_ref_plus(model);
160 
161  const double alpha = 1e-8;
162  Eigen::VectorXd q_plus(model.nq);
163  q_plus = integrate(model,q,alpha*v);
164 
165  Data::Matrix6x J_ref(6,model.nv); J_ref.fill(0.);
166  computeJointJacobians(model,data_ref,q);
167  getJointJacobian(model,data_ref,idx,LOCAL,J_ref);
168 
169  Data::Matrix6x J_ref_plus(6,model.nv); J_ref_plus.fill(0.);
170  computeJointJacobians(model,data_ref_plus,q_plus);
171  getJointJacobian(model,data_ref_plus,idx,LOCAL,J_ref_plus);
172 
173  const Data::SE3 M_plus = data_ref.oMi[idx].inverse()*data_ref_plus.oMi[idx];
174 
175  Data::Matrix6x dJ_ref(6,model.nv); dJ_ref.fill(0.);
176  dJ_ref = (M_plus.toActionMatrix()*J_ref_plus - J_ref)/alpha;
177 
178  computeJointJacobiansTimeVariation(model,data,q,v);
179  Data::Matrix6x dJ(6,model.nv); dJ.fill(0.);
180  getJointJacobianTimeVariation(model,data,idx,LOCAL,dJ);
181 
182  BOOST_CHECK(dJ.isApprox(dJ_ref,sqrt(alpha)));
183  }
184 }
185 
186 BOOST_AUTO_TEST_CASE ( test_timings )
187 {
188  using namespace Eigen;
189  using namespace pinocchio;
190 
193  pinocchio::Data data(model);
194 
195  long flag = BOOST_BINARY(1111);
197  #ifdef NDEBUG
198  #ifdef _INTENSE_TESTING_
199  const size_t NBT = 1000*1000;
200  #else
201  const size_t NBT = 10;
202  #endif
203  #else
204  const size_t NBT = 1;
205  std::cout << "(the time score in debug mode is not relevant) " ;
206  #endif
207 
208  bool verbose = flag & (flag-1) ; // True is two or more binaries of the flag are 1.
209  if(verbose) std::cout <<"--" << std::endl;
210  Eigen::VectorXd q = Eigen::VectorXd::Zero(model.nq);
211 
212  if( flag >> 0 & 1 )
213  {
214  timer.tic();
215  SMOOTH(NBT)
216  {
217  computeJointJacobians(model,data,q);
218  }
219  if(verbose) std::cout << "Compute =\t";
220  timer.toc(std::cout,NBT);
221  }
222 
223  if( flag >> 1 & 1 )
224  {
225  computeJointJacobians(model,data,q);
226  Model::Index idx = model.existJointName("rarm6")?model.getJointId("rarm6"):(Model::Index)(model.njoints-1);
227  Data::Matrix6x Jrh(6,model.nv); Jrh.fill(0);
228 
229  timer.tic();
230  SMOOTH(NBT)
231  {
232  getJointJacobian(model,data,idx,WORLD,Jrh);
233  }
234  if(verbose) std::cout << "Copy =\t";
235  timer.toc(std::cout,NBT);
236  }
237 
238  if( flag >> 2 & 1 )
239  {
240  computeJointJacobians(model,data,q);
241  Model::Index idx = model.existJointName("rarm6")?model.getJointId("rarm6"):(Model::Index)(model.njoints-1);
242  Data::Matrix6x Jrh(6,model.nv); Jrh.fill(0);
243 
244  timer.tic();
245  SMOOTH(NBT)
246  {
247  getJointJacobian(model,data,idx,LOCAL,Jrh);
248  }
249  if(verbose) std::cout << "Change frame =\t";
250  timer.toc(std::cout,NBT);
251  }
252 
253  if( flag >> 3 & 1 )
254  {
255  computeJointJacobians(model,data,q);
256  Model::Index idx = model.existJointName("rarm6")?model.getJointId("rarm6"):(Model::Index)(model.njoints-1);
257  Data::Matrix6x Jrh(6,model.nv); Jrh.fill(0);
258 
259  timer.tic();
260  SMOOTH(NBT)
261  {
262  computeJointJacobian(model,data,q,idx,Jrh);
263  }
264  if(verbose) std::cout << "Single jacobian =\t";
265  timer.toc(std::cout,NBT);
266  }
267 }
268 
269 BOOST_AUTO_TEST_SUITE_END ()
bool verbose
Matrix6x dJ
Derivative of the Jacobian with respect to the time.
The WORLD frame convention corresponds to the frame concident with the Universe/Inertial frame but mo...
double toc()
Definition: timer.hpp:68
q
BOOST_AUTO_TEST_CASE(test_jacobian)
Matrix6x J
Jacobian of joint placements.
void rnea(const int num_threads, ModelPoolTpl< Scalar, Options, JointCollectionTpl > &pool, const Eigen::MatrixBase< ConfigVectorPool > &q, const Eigen::MatrixBase< TangentVectorPool1 > &v, const Eigen::MatrixBase< TangentVectorPool2 > &a, const Eigen::MatrixBase< TangentVectorPool3 > &tau)
The Recursive Newton-Euler algorithm. It computes the inverse dynamics, aka the joint torques accordi...
void integrate(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v, const Eigen::MatrixBase< ReturnType > &qout)
Integrate a configuration vector for the specified model for a tangent vector during one unit time...
int njoints
Number of joints.
v
bn::ndarray array()
void randomConfiguration(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVectorIn1 > &lowerLimits, const Eigen::MatrixBase< ConfigVectorIn2 > &upperLimits, const Eigen::MatrixBase< ReturnType > &qout)
Generate a configuration vector uniformly sampled among provided limits.
void getJointJacobian(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const typename ModelTpl< Scalar, Options, JointCollectionTpl >::JointIndex jointId, const ReferenceFrame rf, const Eigen::MatrixBase< Matrix6Like > &J)
Computes the Jacobian of a specific joint frame expressed either in the world (rf = WORLD) frame or i...
data
void tic()
Definition: timer.hpp:63
bool existJointName(const std::string &name) const
Check if a joint given by its name exists.
void forwardKinematics(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q)
Update the joint placements according to the current joint configuration.
ActionMatrixType toActionMatrix() const
The action matrix of .
Definition: se3-base.hpp:60
static void se3Action(const SE3Tpl< Scalar, Options > &m, const Eigen::MatrixBase< Mat > &iF, Eigen::MatrixBase< MatRet > const &jF)
SE3 action on a set of forces, represented by a 6xN matrix whose each column represent a spatial forc...
bool isApprox(const MotionDense< M2 > &m2, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
The LOCAL frame convention corresponds to the frame directly attached to the moving part (Joint...
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix6x & computeJointJacobiansTimeVariation(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v)
Computes the full model Jacobian variations with respect to time. It corresponds to dJ/dt which depen...
#define SMOOTH(s)
Definition: timer.hpp:38
ConstLinearRef translation() const
Definition: se3-base.hpp:38
SE3GroupAction< D >::ReturnType act(const D &d) const
ay = aXb.act(by)
Definition: se3-base.hpp:90
void getJointJacobianTimeVariation(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex jointId, const ReferenceFrame rf, const Eigen::MatrixBase< Matrix6Like > &dJ)
Computes the Jacobian time variation of a specific joint frame expressed either in the world frame (r...
Main pinocchio namespace.
Definition: timings.cpp:30
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix6x & computeJointJacobians(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q)
Computes the full model Jacobian, i.e. the stack of all motion subspace expressed in the world frame...
ToVectorConstReturnType toVector() const
Definition: motion-base.hpp:37
The LOCAL_WORLD_ALIGNED frame convention corresponds to the frame centered on the moving part (Joint...
int nv
Dimension of the velocity vector space.
JointIndex getJointId(const std::string &name) const
Return the index of a joint given by its name.
bool isFinite(const Eigen::MatrixBase< Derived > &x)
std::size_t Index
list a
x
— Training
Definition: continuous.py:157
void computeJointJacobian(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const JointIndex jointId, const Eigen::MatrixBase< Matrix6Like > &J)
Computes the Jacobian of a specific joint frame expressed in the local frame of the joint and store t...
void humanoidRandom(ModelTpl< Scalar, Options, JointCollectionTpl > &model, bool usingFF=true)
Create a humanoid kinematic tree with 6-DOF limbs and random joint placements.
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > VectorXd
Definition: conversions.cpp:14
Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > Matrix6x
The 6d jacobian type (temporary)
int nq
Dimension of the configuration vector representation.


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