joint-jacobian.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2015-2020 CNRS INRIA
3 //
4 
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 
36 
37  VectorXd q = VectorXd::Zero(model.nq);
39 
40  Model::Index idx =
41  model.existJointName("rarm2") ? model.getJointId("rarm2") : (Model::Index)(model.njoints - 1);
42  Data::Matrix6x Jrh(6, model.nv);
43  Jrh.fill(0);
44  getJointJacobian(model, data, idx, WORLD, Jrh);
45 
46  /* Test J*q == v */
47  VectorXd qdot = VectorXd::Random(model.nv);
48  VectorXd qddot = VectorXd::Zero(model.nv);
49  rnea(model, data, q, qdot, qddot);
50  Motion v = data.oMi[idx].act(data.v[idx]);
51  BOOST_CHECK(v.toVector().isApprox(Jrh * qdot, 1e-12));
52 
53  /* Test local jacobian: rhJrh == rhXo oJrh */
54  Data::Matrix6x rhJrh(6, model.nv);
55  rhJrh.fill(0);
56  getJointJacobian(model, data, idx, LOCAL, rhJrh);
57  Data::Matrix6x XJrh(6, model.nv);
58  motionSet::se3Action(data.oMi[idx].inverse(), Jrh, XJrh);
59  BOOST_CHECK(XJrh.isApprox(rhJrh, 1e-12));
60 
61  XJrh.setZero();
62  Data data_jointJacobian(model);
63  computeJointJacobian(model, data_jointJacobian, q, idx, XJrh);
64  BOOST_CHECK(XJrh.isApprox(rhJrh, 1e-12));
65 
66  /* Test computeJointJacobians with pre-computation of the forward kinematics */
67  Data data_fk(model);
68  forwardKinematics(model, data_fk, q);
69  computeJointJacobians(model, data_fk);
70 
71  BOOST_CHECK(data_fk.J.isApprox(data.J));
72 }
73 
74 BOOST_AUTO_TEST_CASE(test_jacobian_time_variation)
75 {
76  using namespace Eigen;
77  using namespace pinocchio;
78 
82  pinocchio::Data data_ref(model);
83 
84  VectorXd q = randomConfiguration(
85  model, -1 * Eigen::VectorXd::Ones(model.nq), Eigen::VectorXd::Ones(model.nq));
86  VectorXd v = VectorXd::Random(model.nv);
87  VectorXd a = VectorXd::Random(model.nv);
88 
90 
91  BOOST_CHECK(isFinite(data.dJ));
92 
93  forwardKinematics(model, data_ref, q, v, a);
94  Model::Index idx =
95  model.existJointName("rarm2") ? model.getJointId("rarm2") : (Model::Index)(model.njoints - 1);
96 
97  Data::Matrix6x J(6, model.nv);
98  J.fill(0.);
99  Data::Matrix6x dJ(6, model.nv);
100  dJ.fill(0.);
101 
102  // Regarding to the WORLD origin
103  getJointJacobian(model, data, idx, WORLD, J);
104  BOOST_CHECK(J.isApprox(getJointJacobian(model, data, idx, WORLD)));
106 
107  Motion v_idx(J * v);
108  BOOST_CHECK(v_idx.isApprox(data_ref.oMi[idx].act(data_ref.v[idx])));
109 
110  Motion a_idx(J * a + dJ * v);
111  const Motion & a_ref = data_ref.oMi[idx].act(data_ref.a[idx]);
112  BOOST_CHECK(a_idx.isApprox(a_ref));
113 
114  // Regarding to the LOCAL frame
115  getJointJacobian(model, data, idx, LOCAL, J);
116  BOOST_CHECK(J.isApprox(getJointJacobian(model, data, idx, LOCAL)));
118 
119  v_idx = (Motion::Vector6)(J * v);
120  BOOST_CHECK(v_idx.isApprox(data_ref.v[idx]));
121 
122  a_idx = (Motion::Vector6)(J * a + dJ * v);
123  BOOST_CHECK(a_idx.isApprox(data_ref.a[idx]));
124 
125  // Regarding to the LOCAL_WORLD_ALIGNED frame
127  BOOST_CHECK(J.isApprox(getJointJacobian(model, data, idx, LOCAL_WORLD_ALIGNED)));
129 
130  Data::SE3 worldMlocal = data.oMi[idx];
131  worldMlocal.translation().setZero();
132  Data::Motion world_v_local = data.ov[idx];
133  world_v_local.linear().setZero();
134 
135  v_idx = (Motion::Vector6)(J * v);
136  BOOST_CHECK(v_idx.isApprox(worldMlocal.act(data_ref.v[idx])));
137 
138  a_idx = (Motion::Vector6)(J * a + dJ * v);
139  BOOST_CHECK(a_idx.isApprox(
140  world_v_local.cross(worldMlocal.act(data_ref.v[idx])) + worldMlocal.act(data_ref.a[idx])));
141 
142  // compare to finite differencies : WORLD
143  {
144  Data data_ref(model), data_ref_plus(model);
145 
146  const double alpha = 1e-8;
147  Eigen::VectorXd q_plus(model.nq);
148  q_plus = integrate(model, q, alpha * v);
149 
150  Data::Matrix6x J_ref(6, model.nv);
151  J_ref.fill(0.);
152  computeJointJacobians(model, data_ref, q);
153  getJointJacobian(model, data_ref, idx, WORLD, J_ref);
154 
155  Data::Matrix6x J_ref_plus(6, model.nv);
156  J_ref_plus.fill(0.);
157  computeJointJacobians(model, data_ref_plus, q_plus);
158  getJointJacobian(model, data_ref_plus, idx, WORLD, J_ref_plus);
159 
160  Data::Matrix6x dJ_ref(6, model.nv);
161  dJ_ref.fill(0.);
162  dJ_ref = (J_ref_plus - J_ref) / alpha;
163 
165  Data::Matrix6x dJ(6, model.nv);
166  dJ.fill(0.);
168 
169  BOOST_CHECK(dJ.isApprox(dJ_ref, sqrt(alpha)));
170  }
171 
172  // compare to finite differencies : LOCAL
173  {
174  Data data_ref(model), data_ref_plus(model);
175 
176  const double alpha = 1e-8;
177  Eigen::VectorXd q_plus(model.nq);
178  q_plus = integrate(model, q, alpha * v);
179 
180  Data::Matrix6x J_ref(6, model.nv);
181  J_ref.fill(0.);
182  computeJointJacobians(model, data_ref, q);
183  getJointJacobian(model, data_ref, idx, LOCAL, J_ref);
184 
185  Data::Matrix6x J_ref_plus(6, model.nv);
186  J_ref_plus.fill(0.);
187  computeJointJacobians(model, data_ref_plus, q_plus);
188  getJointJacobian(model, data_ref_plus, idx, LOCAL, J_ref_plus);
189 
190  Data::Matrix6x dJ_ref(6, model.nv);
191  dJ_ref = (J_ref_plus - J_ref) / alpha;
192 
194  Data::Matrix6x dJ(6, model.nv);
195  dJ.fill(0.);
197 
198  BOOST_CHECK(dJ.isApprox(dJ_ref, sqrt(alpha)));
199  }
200 
201  // compare to finite differencies : LOCAL_WORLD_ALIGNED
202  {
203  Data data_ref(model), data_ref_plus(model);
204 
205  const double alpha = 1e-8;
206  Eigen::VectorXd q_plus(model.nq);
207  q_plus = integrate(model, q, alpha * v);
208 
209  Data::Matrix6x J_ref(6, model.nv);
210  J_ref.fill(0.);
211  computeJointJacobians(model, data_ref, q);
212  getJointJacobian(model, data_ref, idx, LOCAL_WORLD_ALIGNED, J_ref);
213 
214  Data::Matrix6x J_ref_plus(6, model.nv);
215  J_ref_plus.fill(0.);
216  computeJointJacobians(model, data_ref_plus, q_plus);
217  getJointJacobian(model, data_ref_plus, idx, LOCAL_WORLD_ALIGNED, J_ref_plus);
218 
219  Data::Matrix6x dJ_ref(6, model.nv);
220  dJ_ref = (J_ref_plus - J_ref) / alpha;
221 
223  Data::Matrix6x dJ(6, model.nv);
224  dJ.fill(0.);
226 
227  BOOST_CHECK(dJ.isApprox(dJ_ref, sqrt(alpha)));
228  }
229 }
230 
231 BOOST_AUTO_TEST_CASE(test_timings)
232 {
233  using namespace Eigen;
234  using namespace pinocchio;
235 
239 
240  long flag = BOOST_BINARY(1111);
242 #ifdef NDEBUG
243  #ifdef _INTENSE_TESTING_
244  const size_t NBT = 1000 * 1000;
245  #else
246  const size_t NBT = 10;
247  #endif
248 #else
249  const size_t NBT = 1;
250  std::cout << "(the time score in debug mode is not relevant) ";
251 #endif
252 
253  bool verbose = flag & (flag - 1); // True is two or more binaries of the flag are 1.
254  if (verbose)
255  std::cout << "--" << std::endl;
256  Eigen::VectorXd q = Eigen::VectorXd::Zero(model.nq);
257 
258  if (flag >> 0 & 1)
259  {
260  timer.tic();
261  SMOOTH(NBT)
262  {
264  }
265  if (verbose)
266  std::cout << "Compute =\t";
267  timer.toc(std::cout, NBT);
268  }
269 
270  if (flag >> 1 & 1)
271  {
273  Model::Index idx =
274  model.existJointName("rarm6") ? model.getJointId("rarm6") : (Model::Index)(model.njoints - 1);
275  Data::Matrix6x Jrh(6, model.nv);
276  Jrh.fill(0);
277 
278  timer.tic();
279  SMOOTH(NBT)
280  {
281  getJointJacobian(model, data, idx, WORLD, Jrh);
282  }
283  if (verbose)
284  std::cout << "Copy =\t";
285  timer.toc(std::cout, NBT);
286  }
287 
288  if (flag >> 2 & 1)
289  {
291  Model::Index idx =
292  model.existJointName("rarm6") ? model.getJointId("rarm6") : (Model::Index)(model.njoints - 1);
293  Data::Matrix6x Jrh(6, model.nv);
294  Jrh.fill(0);
295 
296  timer.tic();
297  SMOOTH(NBT)
298  {
299  getJointJacobian(model, data, idx, LOCAL, Jrh);
300  }
301  if (verbose)
302  std::cout << "Change frame =\t";
303  timer.toc(std::cout, NBT);
304  }
305 
306  if (flag >> 3 & 1)
307  {
309  Model::Index idx =
310  model.existJointName("rarm6") ? model.getJointId("rarm6") : (Model::Index)(model.njoints - 1);
311  Data::Matrix6x Jrh(6, model.nv);
312  Jrh.fill(0);
313 
314  timer.tic();
315  SMOOTH(NBT)
316  {
317  computeJointJacobian(model, data, q, idx, Jrh);
318  }
319  if (verbose)
320  std::cout << "Single jacobian =\t";
321  timer.toc(std::cout, NBT);
322  }
323 }
324 
325 BOOST_AUTO_TEST_SUITE_END()
pinocchio::WORLD
@ WORLD
Definition: multibody/fwd.hpp:48
act-on-set.hpp
PinocchioTicToc::toc
double toc()
Definition: timer.hpp:88
Eigen
pinocchio::getJointJacobianTimeVariation
void getJointJacobianTimeVariation(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex joint_id, const ReferenceFrame reference_frame, const Eigen::MatrixBase< Matrix6Like > &dJ)
Computes the Jacobian time variation of a specific joint frame expressed either in the world frame (r...
pinocchio::DataTpl
Definition: context/generic.hpp:25
pinocchio::forwardKinematics
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.
pinocchio::SE3Tpl< Scalar, Options >
kinematics.hpp
model.hpp
setup.data
data
Definition: cmake/cython/setup.in.py:48
inverse-kinematics-3d.J
J
Definition: inverse-kinematics-3d.py:28
pinocchio::buildModels::humanoidRandom
void humanoidRandom(ModelTpl< Scalar, Options, JointCollectionTpl > &model, bool usingFF=true)
Create a humanoid kinematic tree with 6-DOF limbs and random joint placements.
pinocchio::computeJointJacobiansTimeVariation
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...
pinocchio::computeJointJacobians
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....
pinocchio::randomConfiguration
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.
Definition: joint-configuration.hpp:315
rnea.hpp
timer.hpp
pinocchio::Index
PINOCCHIO_COMPILER_DIAGNOSTIC_POP typedef std::size_t Index
Definition: multibody/fwd.hpp:22
anymal-simulation.model
model
Definition: anymal-simulation.py:8
pinocchio::SE3Tpl::translation
ConstLinearRef translation() const
Definition: se3-base.hpp:52
pinocchio::LOCAL_WORLD_ALIGNED
@ LOCAL_WORLD_ALIGNED
Definition: multibody/fwd.hpp:52
SMOOTH
#define SMOOTH(s)
Definition: timer.hpp:38
joint-configuration.hpp
reachable-workspace-with-collisions.alpha
float alpha
Definition: reachable-workspace-with-collisions.py:162
pinocchio::integrate
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.
Definition: joint-configuration.hpp:70
isFinite
bool isFinite(const Eigen::MatrixBase< Derived > &x)
Definition: joint-jacobian.cpp:21
pinocchio::getJointJacobian
void getJointJacobian(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex joint_id, const ReferenceFrame reference_frame, const Eigen::MatrixBase< Matrix6Like > &J)
Computes the Jacobian of a specific joint frame expressed in one of the pinocchio::ReferenceFrame opt...
cartpole.v
v
Definition: cartpole.py:153
data.hpp
x
x
pinocchio::forceSet::se3Action
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...
q
q
BOOST_AUTO_TEST_CASE
BOOST_AUTO_TEST_CASE(test_jacobian)
Definition: joint-jacobian.cpp:28
a
Vec3f a
PinocchioTicToc::US
@ US
Definition: timer.hpp:53
pinocchio::DataTpl::J
Matrix6x J
Jacobian of joint placements.
Definition: multibody/data.hpp:360
pinocchio::ModelTpl::Index
pinocchio::Index Index
Definition: multibody/model.hpp:66
pinocchio::rnea
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & rnea(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType1 > &v, const Eigen::MatrixBase< TangentVectorType2 > &a)
The Recursive Newton-Euler algorithm. It computes the inverse dynamics, aka the joint torques accordi...
pinocchio::computeJointJacobian
void computeJointJacobian(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const JointIndex joint_id, const Eigen::MatrixBase< Matrix6Like > &J)
Computes the Jacobian of a specific joint frame expressed in the local frame of the joint and store t...
pinocchio::DataTpl::Matrix6x
Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > Matrix6x
The 6d jacobian type (temporary)
Definition: multibody/data.hpp:92
sample-models.hpp
pinocchio::MotionTpl
Definition: context/casadi.hpp:27
jacobian.hpp
pinocchio::ModelTpl
Definition: context/generic.hpp:20
verbose
bool verbose
PinocchioTicToc
Definition: timer.hpp:47
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27
PinocchioTicToc::tic
void tic()
Definition: timer.hpp:82
pinocchio::LOCAL
@ LOCAL
Definition: multibody/fwd.hpp:50


pinocchio
Author(s):
autogenerated on Thu Dec 19 2024 03:41:30