5 #include "pinocchio/multibody/model.hpp" 6 #include "pinocchio/multibody/data.hpp" 7 #include "pinocchio/algorithm/jacobian.hpp" 8 #include "pinocchio/algorithm/joint-configuration.hpp" 9 #include "pinocchio/algorithm/kinematics.hpp" 10 #include "pinocchio/algorithm/kinematics-derivatives.hpp" 11 #include "pinocchio/parsers/sample-models.hpp" 15 #include <boost/test/unit_test.hpp> 16 #include <boost/utility/binary.hpp> 18 BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE)
22 using namespace Eigen;
39 for(
size_t i = 1;
i < (size_t)model.
njoints; ++
i)
41 BOOST_CHECK(
data.oMi[
i].isApprox(data_ref.oMi[
i]));
42 BOOST_CHECK(
data.v[
i].isApprox(data_ref.v[
i]));
43 BOOST_CHECK(
data.ov[
i].isApprox(data_ref.oMi[
i].act(data_ref.v[
i])));
44 BOOST_CHECK(
data.a[
i].isApprox(data_ref.a[
i]));
45 BOOST_CHECK(
data.oa[
i].isApprox(data_ref.oMi[
i].act(data_ref.a[
i])));
49 BOOST_CHECK(
data.J.isApprox(data_ref.
J));
52 BOOST_CHECK(
data.dJ.isApprox(data_ref.
dJ));
57 using namespace Eigen;
75 Data::Matrix6x partial_dq_local_world_aligned(6,model.
nv); partial_dq_local_world_aligned.setZero();
78 Data::Matrix6x partial_dv_local_world_aligned(6,model.
nv); partial_dv_local_world_aligned.setZero();
82 partial_dq,partial_dv);
85 partial_dq_local_world_aligned,partial_dv_local_world_aligned);
88 partial_dq_local,partial_dv_local);
91 Data::Matrix6x J_ref_local_world_aligned(6,model.
nv); J_ref_local_world_aligned.setZero();
98 BOOST_CHECK(partial_dv.isApprox(J_ref));
99 BOOST_CHECK(partial_dv_local_world_aligned.isApprox(J_ref_local_world_aligned));
100 BOOST_CHECK(partial_dv_local.isApprox(J_ref_local));
104 Data::Matrix6x partial_dq_fd_local_world_aligned(6,model.
nv); partial_dq_fd_local_world_aligned.setZero();
105 Data::Matrix6x partial_dq_fd_local(6,model.
nv); partial_dq_fd_local.setZero();
107 Data::Matrix6x partial_dv_fd_local_world_aligned(6,model.
nv); partial_dv_fd_local_world_aligned.setZero();
108 Data::Matrix6x partial_dv_fd_local(6,model.
nv); partial_dv_fd_local.setZero();
109 const double alpha = 1e-8;
113 Data data_plus(model);
115 SE3 oMi_rot(SE3::Identity());
116 oMi_rot.
rotation() = data_ref.oMi[jointId].rotation();
117 Motion v0(data_ref.oMi[jointId].act(data_ref.v[jointId]));
118 Motion v0_local_world_aligned(oMi_rot.
act(data_ref.v[jointId]));
119 Motion v0_local(data_ref.v[jointId]);
120 for(
int k = 0; k < model.
nv; ++k)
125 partial_dv_fd.col(k) = (data_plus.oMi[jointId].act(data_plus.v[jointId]) - v0).toVector()/alpha;
126 partial_dv_fd_local_world_aligned.col(k) = (oMi_rot.
act(data_plus.v[jointId]) - v0_local_world_aligned).toVector()/alpha;
127 partial_dv_fd_local.col(k) = (data_plus.v[jointId] - v0_local).toVector()/alpha;
131 BOOST_CHECK(partial_dv.isApprox(partial_dv_fd,sqrt(alpha)));
132 BOOST_CHECK(partial_dv_local_world_aligned.isApprox(partial_dv_fd_local_world_aligned,sqrt(alpha)));
133 BOOST_CHECK(partial_dv_local.isApprox(partial_dv_fd_local,sqrt(alpha)));
138 v0 = data_ref.oMi[jointId].act(data_ref.v[jointId]);
140 for(
int k = 0; k < model.
nv; ++k)
146 SE3 oMi_plus_rot = data_plus.oMi[jointId];
149 Motion v_plus_local_world_aligned = oMi_plus_rot.
act(data_plus.v[jointId]);
150 SE3::Vector3 trans = data_plus.oMi[jointId].translation() - data_ref.oMi[jointId].translation();
151 v_plus_local_world_aligned.
linear() -= v_plus_local_world_aligned.
angular().cross(trans);
152 partial_dq_fd.col(k) = (data_plus.oMi[jointId].act(data_plus.v[jointId]) - v0).toVector()/alpha;
153 partial_dq_fd_local_world_aligned.col(k) = (v_plus_local_world_aligned - v0_local_world_aligned).toVector()/alpha;
154 partial_dq_fd_local.col(k) = (data_plus.v[jointId] - v0_local).toVector()/alpha;
158 BOOST_CHECK(partial_dq.isApprox(partial_dq_fd,sqrt(alpha)));
159 BOOST_CHECK(partial_dq_local_world_aligned.isApprox(partial_dq_fd_local_world_aligned,sqrt(alpha)));
160 BOOST_CHECK(partial_dq_local.isApprox(partial_dq_fd_local,sqrt(alpha)));
166 using namespace Eigen;
185 Data::Matrix6x v_partial_dq_local(6,model.
nv); v_partial_dq_local.setZero();
186 Data::Matrix6x v_partial_dq_local_world_aligned(6,model.
nv); v_partial_dq_local_world_aligned.setZero();
188 Data::Matrix6x a_partial_dq_local_world_aligned(6,model.
nv); a_partial_dq_local_world_aligned.setZero();
189 Data::Matrix6x a_partial_dq_local(6,model.
nv); a_partial_dq_local.setZero();
191 Data::Matrix6x a_partial_dv_local_world_aligned(6,model.
nv); a_partial_dv_local_world_aligned.setZero();
192 Data::Matrix6x a_partial_dv_local(6,model.
nv); a_partial_dv_local.setZero();
194 Data::Matrix6x a_partial_da_local_world_aligned(6,model.
nv); a_partial_da_local_world_aligned.setZero();
195 Data::Matrix6x a_partial_da_local(6,model.
nv); a_partial_da_local.setZero();
199 a_partial_dq,a_partial_dv,a_partial_da);
202 v_partial_dq_local_world_aligned,
203 a_partial_dq_local_world_aligned,
204 a_partial_dv_local_world_aligned,
205 a_partial_da_local_world_aligned);
209 a_partial_dq_local,a_partial_dv_local,a_partial_da_local);
217 Data::Matrix6x v_partial_dq_ref_local_world_aligned(6,model.
nv); v_partial_dq_ref_local_world_aligned.setZero();
218 Data::Matrix6x v_partial_dq_ref_local(6,model.
nv); v_partial_dq_ref_local.setZero();
220 Data::Matrix6x v_partial_dv_ref_local_world_aligned(6,model.
nv); v_partial_dv_ref_local_world_aligned.setZero();
221 Data::Matrix6x v_partial_dv_ref_local(6,model.
nv); v_partial_dv_ref_local.setZero();
224 v_partial_dq_ref,v_partial_dv_ref);
226 BOOST_CHECK(v_partial_dq.isApprox(v_partial_dq_ref));
227 BOOST_CHECK(a_partial_da.isApprox(v_partial_dv_ref));
230 v_partial_dq_ref_local_world_aligned,v_partial_dv_ref_local_world_aligned);
232 BOOST_CHECK(v_partial_dq_local_world_aligned.isApprox(v_partial_dq_ref_local_world_aligned));
233 BOOST_CHECK(a_partial_da_local_world_aligned.isApprox(v_partial_dv_ref_local_world_aligned));
236 v_partial_dq_ref_local,v_partial_dv_ref_local);
238 BOOST_CHECK(v_partial_dq_local.isApprox(v_partial_dq_ref_local));
239 BOOST_CHECK(a_partial_da_local.isApprox(v_partial_dv_ref_local));
244 Data::Matrix6x J_ref_local_world_aligned(6,model.
nv); J_ref_local_world_aligned.setZero();
250 BOOST_CHECK(a_partial_da.isApprox(J_ref));
251 BOOST_CHECK(a_partial_da_local_world_aligned.isApprox(J_ref_local_world_aligned));
252 BOOST_CHECK(a_partial_da_local.isApprox(J_ref_local));
256 Data::Matrix6x a_partial_da_fd_local_world_aligned(6,model.
nv); a_partial_da_fd_local_world_aligned.setZero();
257 Data::Matrix6x a_partial_da_fd_local(6,model.
nv); a_partial_da_fd_local.setZero();
258 const double alpha = 1e-8;
261 Data data_plus(model);
263 SE3 oMi_rot(SE3::Identity());
264 oMi_rot.
rotation() = data_ref.oMi[jointId].rotation();
267 Motion a0(data_ref.oMi[jointId].act(data_ref.a[jointId]));
268 Motion a0_local_world_aligned(oMi_rot.
act(data_ref.a[jointId]));
269 Motion a0_local(data_ref.a[jointId]);
270 for(
int k = 0; k < model.
nv; ++k)
275 a_partial_da_fd.col(k) = (data_plus.oMi[jointId].act(data_plus.a[jointId]) - a0).toVector()/alpha;
276 a_partial_da_fd_local_world_aligned.col(k) = (oMi_rot.
act(data_plus.a[jointId]) - a0_local_world_aligned).toVector()/alpha;
277 a_partial_da_fd_local.col(k) = (data_plus.a[jointId] - a0_local).toVector()/alpha;
280 BOOST_CHECK(a_partial_da.isApprox(a_partial_da_fd,sqrt(alpha)));
281 BOOST_CHECK(a_partial_da_local_world_aligned.isApprox(a_partial_da_fd_local_world_aligned,sqrt(alpha)));
282 BOOST_CHECK(a_partial_da_local.isApprox(a_partial_da_fd_local,sqrt(alpha)));
284 BOOST_CHECK(a_partial_da_local.isApprox(a_partial_da_fd_local,sqrt(alpha)));
288 Data::Matrix6x a_partial_dv_fd_local_world_aligned(6,model.
nv); a_partial_dv_fd_local_world_aligned.setZero();
289 Data::Matrix6x a_partial_dv_fd_local(6,model.
nv); a_partial_dv_fd_local.setZero();
290 for(
int k = 0; k < model.
nv; ++k)
295 a_partial_dv_fd.col(k) = (data_plus.oMi[jointId].act(data_plus.a[jointId]) - a0).toVector()/alpha; a_partial_dv_fd_local_world_aligned.col(k) = (oMi_rot.
act(data_plus.a[jointId]) - a0_local_world_aligned).toVector()/alpha;
296 a_partial_dv_fd_local.col(k) = (data_plus.a[jointId] - a0_local).toVector()/alpha;
300 BOOST_CHECK(a_partial_dv.isApprox(a_partial_dv_fd,sqrt(alpha)));
301 BOOST_CHECK(a_partial_dv_local_world_aligned.isApprox(a_partial_dv_fd_local_world_aligned,sqrt(alpha)));
302 BOOST_CHECK(a_partial_dv_local.isApprox(a_partial_dv_fd_local,sqrt(alpha)));
304 BOOST_CHECK(a_partial_dv_local.isApprox(a_partial_dv_fd_local,sqrt(alpha)));
307 a_partial_dq.setZero();
308 a_partial_dv.setZero();
309 a_partial_da.setZero();
311 a_partial_dq_local_world_aligned.setZero();
312 a_partial_dv_local_world_aligned.setZero();
313 a_partial_da_local_world_aligned.setZero();
315 a_partial_dq_local.setZero();
316 a_partial_dv_local.setZero();
317 a_partial_da_local.setZero();
320 Data::Matrix6x a_partial_dq_fd_local_world_aligned(6,model.
nv); a_partial_dq_fd_local_world_aligned.setZero();
321 Data::Matrix6x a_partial_dq_fd_local(6,model.
nv); a_partial_dq_fd_local.setZero();
326 a_partial_dq,a_partial_dv,a_partial_da);
329 v_partial_dq_local_world_aligned,
330 a_partial_dq_local_world_aligned,
331 a_partial_dv_local_world_aligned,
332 a_partial_da_local_world_aligned);
336 a_partial_dq_local,a_partial_dv_local,a_partial_da_local);
340 a0 = data_ref.oMi[jointId].act(data_ref.a[jointId]);
341 oMi_rot.
rotation() = data_ref.oMi[jointId].rotation();
342 a0_local_world_aligned = oMi_rot.
act(data_ref.a[jointId]);
343 a0_local = data_ref.a[jointId];
345 for(
int k = 0; k < model.
nv; ++k)
351 SE3 oMi_plus_rot = data_plus.oMi[jointId];
354 Motion a_plus_local_world_aligned = oMi_plus_rot.
act(data_plus.a[jointId]);
355 const SE3::Vector3 trans = data_plus.oMi[jointId].translation() - data_ref.oMi[jointId].translation();
356 a_plus_local_world_aligned.
linear() -= a_plus_local_world_aligned.
angular().cross(trans);
357 a_partial_dq_fd.col(k) = (data_plus.oMi[jointId].act(data_plus.a[jointId]) - a0).toVector()/alpha;
358 a_partial_dq_fd_local_world_aligned.col(k) = (a_plus_local_world_aligned - a0_local_world_aligned).toVector()/alpha;
359 a_partial_dq_fd_local.col(k) = (data_plus.a[jointId] - a0_local).toVector()/alpha;
363 BOOST_CHECK(a_partial_dq.isApprox(a_partial_dq_fd,sqrt(alpha)));
364 BOOST_CHECK(a_partial_dq_local_world_aligned.isApprox(a_partial_dq_fd_local_world_aligned,sqrt(alpha)));
365 BOOST_CHECK(a_partial_dq_local.isApprox(a_partial_dq_fd_local,sqrt(alpha)));
371 using namespace Eigen;
425 v_partial_dq.setZero();
426 a_partial_dq.setZero();
427 a_partial_dv.setZero();
428 a_partial_da.setZero();
435 a_partial_dq,a_partial_dv,a_partial_da);
439 v_partial_dq_ref.setZero(); v_partial_dv_ref.setZero();
441 v_partial_dq_ref,v_partial_dv_ref);
442 rhs += v_partial_dq_ref;
443 BOOST_CHECK(a_partial_dv.isApprox(rhs,1e-12));
504 const double alpha = 1e-8;
507 Data data_plus(model);
508 v_plus = v + alpha * a;
517 v_partial_dq_ref.setZero(); v_partial_dv_ref.setZero();
519 v_partial_dq.setZero();
520 a_partial_dq.setZero();
521 a_partial_dv.setZero();
522 a_partial_da.setZero();
525 v_partial_dq_ref,v_partial_dv_ref);
527 v_partial_dq_plus,v_partial_dv_plus);
531 a_partial_dq,a_partial_dv,a_partial_da);
533 Data::Matrix6x rhs = (v_partial_dq_plus - v_partial_dq_ref)/alpha;
534 BOOST_CHECK(a_partial_dq.isApprox(rhs,sqrt(alpha)));
545 using namespace Eigen;
551 Data data(model), data_ref(model), data_plus(model);
564 BOOST_CHECK(data2.
J.isApprox(
data.J));
566 const Eigen::DenseIndex matrix_offset = 6 * model.
nv;
568 for(
int k = 0; k < model.
nv; ++k)
570 Eigen::Map<Data::Matrix6x> dJ(
data.kinematic_hessians.data() + k*matrix_offset,6,model.
nv);
573 BOOST_CHECK(dJ2.isApprox(dJ));
576 for(
int i = 0;
i < model.
nv; ++
i)
578 for(
int j =
i; j < model.
nv; ++j)
580 bool j_is_children_of_i =
false;
585 j_is_children_of_i =
true;
590 if(j_is_children_of_i)
594 Eigen::Map<Data::Motion::Vector6> SixSi(
data.kinematic_hessians.data()
597 BOOST_CHECK(SixSi.isZero());
601 Eigen::Map<Data::Motion::Vector6> SixSj(
data.kinematic_hessians.data()
605 Eigen::Map<Data::Motion::Vector6> SjxSi(
data.kinematic_hessians.data()
609 BOOST_CHECK(SixSj.isApprox(-SjxSi));
614 Eigen::Map<Data::Motion::Vector6> SixSj(
data.kinematic_hessians.data()
618 Eigen::Map<Data::Motion::Vector6> SjxSi(
data.kinematic_hessians.data()
622 BOOST_CHECK(SixSj.isZero());
623 BOOST_CHECK(SjxSi.isZero());
628 const double eps = 1e-8;
630 J_ref.setZero(); J_plus.setZero();
635 const Eigen::DenseIndex outer_offset = model.
nv * 6;
640 for(Eigen::DenseIndex k = 0; k < model.
nv; ++k)
649 Eigen::Map<Data::Matrix6x> dJ_dq(kinematic_hessian_world.
data() + k * outer_offset,6,model.
nv);
654 BOOST_CHECK((dJ_dq_ref-dJ_dq).
isZero(sqrt(eps)));
663 for(Eigen::DenseIndex k = 0; k < model.
nv; ++k)
674 dt_last_fd.col(k) = (data_plus.oMi[
joint_id].translation() - data_ref.oMi[
joint_id].translation())/eps;
677 Eigen::Map<Data::Matrix6x> dJ_dq(kinematic_hessian_local_world_aligned.
data() + k * outer_offset,6,model.
nv);
682 BOOST_CHECK((dJ_dq_ref-dJ_dq).
isZero(sqrt(eps)));
689 BOOST_CHECK(dt_last_fd.isApprox(J_world.topRows<3>(),sqrt(eps)));
695 for(Eigen::DenseIndex k = 0; k < model.
nv; ++k)
706 Eigen::Map<Data::Matrix6x> dJ_dq(kinematic_hessian_local.
data() + k * outer_offset,6,model.
nv);
711 BOOST_CHECK((dJ_dq_ref-dJ_dq).
isZero(sqrt(eps)));
716 BOOST_AUTO_TEST_SUITE_END()
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...
Matrix6x J
Jacobian of joint placements.
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...
void getJointVelocityDerivatives(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const Model::JointIndex jointId, const ReferenceFrame rf, const Eigen::MatrixBase< Matrix6xOut1 > &v_partial_dq, const Eigen::MatrixBase< Matrix6xOut2 > &v_partial_dv)
Computes the partial derivaties of the spatial velocity of a given with respect to the joint configur...
Tensor3x kinematic_hessians
Tensor containing the kinematic Hessian of all the joints.
bool isZero(const Eigen::MatrixBase< MatrixLike > &m, const typename MatrixLike::RealScalar &prec=Eigen::NumTraits< typename MatrixLike::Scalar >::dummy_precision())
int njoints
Number of joints.
ConfigVectorType lowerPositionLimit
Lower joint configuration limit.
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...
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar * data()
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.
BOOST_AUTO_TEST_CASE(test_kinematics_derivatives_all)
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...
ConstLinearType linear() const
SE3Tpl inverse() const
aXb = bXa.inverse()
The LOCAL frame convention corresponds to the frame directly attached to the moving part (Joint...
pinocchio::JointIndex JointIndex
void computeForwardKinematicsDerivatives(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)
Computes all the terms required to compute the derivatives of the placement, spatial velocity and acc...
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...
void getJointAccelerationDerivatives(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const Model::JointIndex jointId, const ReferenceFrame rf, const Eigen::MatrixBase< Matrix6xOut1 > &v_partial_dq, const Eigen::MatrixBase< Matrix6xOut2 > &a_partial_dq, const Eigen::MatrixBase< Matrix6xOut3 > &a_partial_dv, const Eigen::MatrixBase< Matrix6xOut4 > &a_partial_da)
Computes the partial derivaties of the spatial acceleration of a given with respect to the joint conf...
ConstLinearRef translation() const
SE3GroupAction< D >::ReturnType act(const D &d) const
ay = aXb.act(by)
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...
traits< SE3Tpl >::Vector3 Vector3
void computeJointKinematicHessians(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data)
Computes all the terms required to compute the second order derivatives of the placement information...
Main pinocchio namespace.
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...
The LOCAL_WORLD_ALIGNED frame convention corresponds to the frame centered on the moving part (Joint...
int nv
Dimension of the velocity vector space.
Eigen::Matrix< Scalar, 3, Eigen::Dynamic, Options > Matrix3x
The 3d jacobian type (temporary)
JointIndex getJointId(const std::string &name) const
Return the index of a joint given by its name.
void getJointKinematicHessian(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const Model::JointIndex joint_id, const ReferenceFrame rf, Tensor< Scalar, 3, Options > &kinematic_hessian)
Retrieves the kinematic Hessian of a given joint according to the values aleardy computed by computeJ...
ConfigVectorType upperPositionLimit
Upper joint configuration limit.
ConstAngularType angular() const
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
Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > Matrix6x
The 6d jacobian type (temporary)
int nq
Dimension of the configuration vector representation.
ConstAngularRef rotation() const
void fill(Eigen::Ref< MatType > mat, const typename MatType::Scalar &value)