joint-jacobian.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2015-2020 CNRS INRIA
3 //
4 
14 
15 #include <boost/test/unit_test.hpp>
16 #include <boost/utility/binary.hpp>
18 
19 template<typename Derived>
20 inline bool isFinite(const Eigen::MatrixBase<Derived> & x)
21 {
22  return ((x - x).array() == (x - x).array()).all();
23 }
24 
26 {
27  using namespace Eigen;
28  using namespace pinocchio;
29 
31 
32  VectorXd q = pinocchio::neutral(model);
34 
35  Data::Matrix6x Jrh(6, model.nv);
36  Jrh.fill(0);
38 
39  /* Test J*q == v */
40  VectorXd qdot = VectorXd::Random(model.nv);
41  VectorXd qddot = VectorXd::Zero(model.nv);
42  rnea(model, data, q, qdot, qddot);
43  Motion v = data.oMi[joint_id].act(data.v[joint_id]);
44  BOOST_CHECK(v.toVector().isApprox(Jrh * qdot, 1e-12));
45 
46  /* Test local jacobian: rhJrh == rhXo oJrh */
47  Data::Matrix6x rhJrh(6, model.nv);
48  rhJrh.fill(0);
50  Data::Matrix6x XJrh(6, model.nv);
51  motionSet::se3Action(data.oMi[joint_id].inverse(), Jrh, XJrh);
52  BOOST_CHECK(XJrh.isApprox(rhJrh, 1e-12));
53 
54  XJrh.setZero();
55  Data data_jointJacobian(model);
56  computeJointJacobian(model, data_jointJacobian, q, joint_id, XJrh);
57  BOOST_CHECK(XJrh.isApprox(rhJrh, 1e-12));
58 
59  /* Test local world-aligned jacobian */
60  forwardKinematics(model, data, q, qdot);
61  Data::Matrix6x WJrh = Data::Matrix6x::Zero(6, model.nv);
64  BOOST_CHECK(w_v.toVector().isApprox(WJrh * qdot));
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_SUITE(BOOST_TEST_MODULE)
75 
76 BOOST_AUTO_TEST_CASE(test_jacobian)
77 {
80 
81  for (int j = 1; j < model.njoints; j++)
82  {
84  }
85 }
86 
87 BOOST_AUTO_TEST_CASE(test_jacobian_mimic)
88 {
89  for (int i = 0; i < pinocchio::MimicTestCases::N_CASES; i++)
90  {
91  const pinocchio::MimicTestCases mimic_test_case(i);
92  const pinocchio::Model & model_mimic = mimic_test_case.model_mimic;
93  for (int j = 1; j < model_mimic.njoints; j++)
94  {
96  }
97  }
98 }
99 
100 BOOST_AUTO_TEST_CASE(test_jacobian_time_variation)
101 {
102  using namespace Eigen;
103  using namespace pinocchio;
104 
108  pinocchio::Data data_ref(model);
109  VectorXd q = randomConfiguration(
110  model, -1 * Eigen::VectorXd::Ones(model.nq), Eigen::VectorXd::Ones(model.nq));
111  VectorXd v = VectorXd::Random(model.nv);
112  VectorXd a = VectorXd::Random(model.nv);
113 
115 
116  BOOST_CHECK(isFinite(data.dJ));
117 
118  forwardKinematics(model, data_ref, q, v, a);
119  Model::Index idx =
120  model.existJointName("rarm2") ? model.getJointId("rarm2") : (Model::Index)(model.njoints - 1);
121 
122  Data::Matrix6x J(6, model.nv);
123  J.fill(0.);
124  Data::Matrix6x dJ(6, model.nv);
125  dJ.fill(0.);
126 
127  // Regarding to the WORLD origin
128  getJointJacobian(model, data, idx, WORLD, J);
129  BOOST_CHECK(J.isApprox(getJointJacobian(model, data, idx, WORLD)));
131  Motion v_idx(J * v);
132  BOOST_CHECK(v_idx.isApprox(data_ref.oMi[idx].act(data_ref.v[idx])));
133 
134  Motion a_idx(J * a + dJ * v);
135  const Motion & a_ref = data_ref.oMi[idx].act(data_ref.a[idx]);
136  BOOST_CHECK(a_idx.isApprox(a_ref));
137 
138  // Regarding to the LOCAL frame
139  getJointJacobian(model, data, idx, LOCAL, J);
140  BOOST_CHECK(J.isApprox(getJointJacobian(model, data, idx, LOCAL)));
142 
143  v_idx = (Motion::Vector6)(J * v);
144  BOOST_CHECK(v_idx.isApprox(data_ref.v[idx]));
145 
146  a_idx = (Motion::Vector6)(J * a + dJ * v);
147  BOOST_CHECK(a_idx.isApprox(data_ref.a[idx]));
148 
149  // Regarding to the LOCAL_WORLD_ALIGNED frame
151  BOOST_CHECK(J.isApprox(getJointJacobian(model, data, idx, LOCAL_WORLD_ALIGNED)));
153 
154  Data::SE3 worldMlocal = data.oMi[idx];
155  worldMlocal.translation().setZero();
156  Data::Motion world_v_local = data.ov[idx];
157  world_v_local.linear().setZero();
158 
159  v_idx = (Motion::Vector6)(J * v);
160  BOOST_CHECK(v_idx.isApprox(worldMlocal.act(data_ref.v[idx])));
161 
162  a_idx = (Motion::Vector6)(J * a + dJ * v);
163  BOOST_CHECK(a_idx.isApprox(
164  world_v_local.cross(worldMlocal.act(data_ref.v[idx])) + worldMlocal.act(data_ref.a[idx])));
165 
166  // compare to finite differencies : WORLD
167  {
168  Data data_ref(model), data_ref_plus(model);
169 
170  const double alpha = 1e-8;
171  Eigen::VectorXd q_plus(model.nq);
172  q_plus = integrate(model, q, alpha * v);
173 
174  Data::Matrix6x J_ref(6, model.nv);
175  J_ref.fill(0.);
176  computeJointJacobians(model, data_ref, q);
177  getJointJacobian(model, data_ref, idx, WORLD, J_ref);
178 
179  Data::Matrix6x J_ref_plus(6, model.nv);
180  J_ref_plus.fill(0.);
181  computeJointJacobians(model, data_ref_plus, q_plus);
182  getJointJacobian(model, data_ref_plus, idx, WORLD, J_ref_plus);
183 
184  Data::Matrix6x dJ_ref(6, model.nv);
185  dJ_ref.fill(0.);
186  dJ_ref = (J_ref_plus - J_ref) / alpha;
187 
189  Data::Matrix6x dJ(6, model.nv);
190  dJ.fill(0.);
192 
193  BOOST_CHECK(dJ.isApprox(dJ_ref, sqrt(alpha)));
194  }
195  // compare to finite differencies : LOCAL
196  {
197  Data data_ref(model), data_ref_plus(model);
198 
199  const double alpha = 1e-8;
200  Eigen::VectorXd q_plus(model.nq);
201  q_plus = integrate(model, q, alpha * v);
202 
203  Data::Matrix6x J_ref(6, model.nv);
204  J_ref.fill(0.);
205  computeJointJacobians(model, data_ref, q);
206  getJointJacobian(model, data_ref, idx, LOCAL, J_ref);
207 
208  Data::Matrix6x J_ref_plus(6, model.nv);
209  J_ref_plus.fill(0.);
210  computeJointJacobians(model, data_ref_plus, q_plus);
211  getJointJacobian(model, data_ref_plus, idx, LOCAL, J_ref_plus);
212 
213  Data::Matrix6x dJ_ref(6, model.nv);
214  dJ_ref = (J_ref_plus - J_ref) / alpha;
215 
217  Data::Matrix6x dJ(6, model.nv);
218  dJ.fill(0.);
220 
221  BOOST_CHECK(dJ.isApprox(dJ_ref, sqrt(alpha)));
222  }
223 
224  // compare to finite differencies : LOCAL_WORLD_ALIGNED
225  {
226  Data data_ref(model), data_ref_plus(model);
227 
228  const double alpha = 1e-8;
229  Eigen::VectorXd q_plus(model.nq);
230  q_plus = integrate(model, q, alpha * v);
231 
232  Data::Matrix6x J_ref(6, model.nv);
233  J_ref.fill(0.);
234  computeJointJacobians(model, data_ref, q);
235  getJointJacobian(model, data_ref, idx, LOCAL_WORLD_ALIGNED, J_ref);
236 
237  Data::Matrix6x J_ref_plus(6, model.nv);
238  J_ref_plus.fill(0.);
239  computeJointJacobians(model, data_ref_plus, q_plus);
240  getJointJacobian(model, data_ref_plus, idx, LOCAL_WORLD_ALIGNED, J_ref_plus);
241 
242  Data::Matrix6x dJ_ref(6, model.nv);
243  dJ_ref = (J_ref_plus - J_ref) / alpha;
244 
246  Data::Matrix6x dJ(6, model.nv);
247  dJ.fill(0.);
249 
250  BOOST_CHECK(dJ.isApprox(dJ_ref, sqrt(alpha)));
251  }
252 }
253 
254 BOOST_AUTO_TEST_CASE(test_timings)
255 {
256  using namespace Eigen;
257  using namespace pinocchio;
258 
262 
263  long flag = BOOST_BINARY(1111);
265 #ifdef NDEBUG
266  #ifdef _INTENSE_TESTING_
267  const size_t NBT = 1000 * 1000;
268  #else
269  const size_t NBT = 10;
270  #endif
271 #else
272  const size_t NBT = 1;
273  std::cout << "(the time score in debug mode is not relevant) ";
274 #endif
275 
276  bool verbose = flag & (flag - 1); // True is two or more binaries of the flag are 1.
277  if (verbose)
278  std::cout << "--" << std::endl;
279  Eigen::VectorXd q = pinocchio::neutral(model);
280 
281  if (flag >> 0 & 1)
282  {
283  timer.tic();
284  SMOOTH(NBT)
285  {
287  }
288  if (verbose)
289  std::cout << "Compute =\t";
290  timer.toc(std::cout, NBT);
291  }
292 
293  if (flag >> 1 & 1)
294  {
296  Model::Index idx =
297  model.existJointName("rarm6") ? model.getJointId("rarm6") : (Model::Index)(model.njoints - 1);
298  Data::Matrix6x Jrh(6, model.nv);
299  Jrh.fill(0);
300 
301  timer.tic();
302  SMOOTH(NBT)
303  {
304  getJointJacobian(model, data, idx, WORLD, Jrh);
305  }
306  if (verbose)
307  std::cout << "Copy =\t";
308  timer.toc(std::cout, NBT);
309  }
310 
311  if (flag >> 2 & 1)
312  {
314  Model::Index idx =
315  model.existJointName("rarm6") ? model.getJointId("rarm6") : (Model::Index)(model.njoints - 1);
316  Data::Matrix6x Jrh(6, model.nv);
317  Jrh.fill(0);
318 
319  timer.tic();
320  SMOOTH(NBT)
321  {
322  getJointJacobian(model, data, idx, LOCAL, Jrh);
323  }
324  if (verbose)
325  std::cout << "Change frame =\t";
326  timer.toc(std::cout, NBT);
327  }
328 
329  if (flag >> 3 & 1)
330  {
332  Model::Index idx =
333  model.existJointName("rarm6") ? model.getJointId("rarm6") : (Model::Index)(model.njoints - 1);
334  Data::Matrix6x Jrh(6, model.nv);
335  Jrh.fill(0);
336 
337  timer.tic();
338  SMOOTH(NBT)
339  {
340  computeJointJacobian(model, data, q, idx, Jrh);
341  }
342  if (verbose)
343  std::cout << "Single jacobian =\t";
344  timer.toc(std::cout, NBT);
345  }
346 }
347 
348 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 >
inverse-kinematics.i
int i
Definition: inverse-kinematics.py:17
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::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::MimicTestCases::N_CASES
static const int N_CASES
Definition: model-generator.hpp:128
pinocchio::buildModels::humanoidRandom
void humanoidRandom(ModelTpl< Scalar, Options, JointCollectionTpl > &model, bool usingFF=true, bool mimic=false)
Create a humanoid kinematic tree with 6-DOF limbs and random joint placements.
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
model-generator.hpp
rnea.hpp
timer.hpp
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:20
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::MimicTestCases::model_mimic
pinocchio::Model model_mimic
Definition: model-generator.hpp:130
mimic_dynamics.model_mimic
model_mimic
Definition: mimic_dynamics.py:19
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:76
pinocchio::getVelocity
MotionTpl< Scalar, Options > getVelocity(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex jointId, const ReferenceFrame rf=LOCAL)
Returns the spatial velocity of the joint expressed in the desired reference frame....
a
Vec3f a
PinocchioTicToc::US
@ US
Definition: timer.hpp:53
pinocchio::DataTpl::J
Matrix6x J
Jacobian of joint placements.
Definition: multibody/data.hpp:374
pinocchio::ModelTpl< Scalar >::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::MimicTestCases
Definition: model-generator.hpp:125
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::JointIndex
Index JointIndex
Definition: multibody/fwd.hpp:26
pinocchio::DataTpl::Matrix6x
Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > Matrix6x
The 6d jacobian type (temporary)
Definition: multibody/data.hpp:92
test_jacobian_impl
void test_jacobian_impl(const pinocchio::Model &model, pinocchio::JointIndex joint_id)
Definition: joint-jacobian.cpp:25
pinocchio::neutral
void neutral(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ReturnType > &qout)
Return the neutral configuration element related to the model configuration space.
Definition: joint-configuration.hpp:363
sample-models.hpp
pinocchio::MotionTpl
Definition: context/casadi.hpp:28
append-urdf-model-with-another-model.joint_id
joint_id
Definition: append-urdf-model-with-another-model.py:34
jacobian.hpp
pinocchio::ModelTpl< context::Scalar, context::Options >
verbose
bool verbose
PinocchioTicToc
Definition: timer.hpp:47
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:33
PinocchioTicToc::tic
void tic()
Definition: timer.hpp:82
pinocchio::LOCAL
@ LOCAL
Definition: multibody/fwd.hpp:50


pinocchio
Author(s):
autogenerated on Thu Apr 10 2025 02:42:19