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" 17 #include <boost/test/unit_test.hpp> 18 #include <boost/utility/binary.hpp> 20 template<
typename Derived>
21 inline bool isFinite(
const Eigen::MatrixBase<Derived> &
x)
23 return ((x - x).
array() == (x - x).
array()).all();
26 BOOST_AUTO_TEST_SUITE ( BOOST_TEST_MODULE )
30 using namespace Eigen;
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));
57 BOOST_CHECK(XJrh.isApprox(rhJrh,1e-12));
60 Data data_jointJacobian(model);
62 BOOST_CHECK(XJrh.isApprox(rhJrh,1e-12));
69 BOOST_CHECK(data_fk.J.isApprox(data.
J));
75 using namespace Eigen;
102 BOOST_CHECK(v_idx.
isApprox(data_ref.oMi[idx].act(data_ref.v[idx])));
105 const Motion & a_ref = data_ref.oMi[idx].act(data_ref.a[idx]);
112 v_idx = (Motion::Vector6)(J*v);
113 BOOST_CHECK(v_idx.
isApprox(data_ref.v[idx]));
115 a_idx = (Motion::Vector6)(J*a + dJ*v);
116 BOOST_CHECK(a_idx.isApprox(data_ref.a[idx]));
125 v_idx = (Motion::Vector6)(J*v);
126 BOOST_CHECK(v_idx.
isApprox(worldMlocal.
act(data_ref.v[idx])));
128 a_idx = (Motion::Vector6)(J*a + dJ*v);
129 BOOST_CHECK(a_idx.isApprox(worldMlocal.
act(data_ref.a[idx])));
133 Data data_ref(model), data_ref_plus(model);
135 const double alpha = 1e-8;
148 dJ_ref = (J_ref_plus - J_ref)/alpha;
154 BOOST_CHECK(dJ.isApprox(dJ_ref,sqrt(alpha)));
159 Data data_ref(model), data_ref_plus(model);
161 const double alpha = 1e-8;
173 const Data::SE3 M_plus = data_ref.oMi[idx].inverse()*data_ref_plus.oMi[idx];
182 BOOST_CHECK(dJ.isApprox(dJ_ref,sqrt(alpha)));
188 using namespace Eigen;
195 long flag = BOOST_BINARY(1111);
198 #ifdef _INTENSE_TESTING_ 199 const size_t NBT = 1000*1000;
201 const size_t NBT = 10;
204 const size_t NBT = 1;
205 std::cout <<
"(the time score in debug mode is not relevant) " ;
208 bool verbose = flag & (flag-1) ;
209 if(verbose) std::cout <<
"--" << std::endl;
219 if(verbose) std::cout <<
"Compute =\t";
220 timer.
toc(std::cout,NBT);
234 if(verbose) std::cout <<
"Copy =\t";
235 timer.
toc(std::cout,NBT);
249 if(verbose) std::cout <<
"Change frame =\t";
250 timer.
toc(std::cout,NBT);
264 if(verbose) std::cout <<
"Single jacobian =\t";
265 timer.
toc(std::cout,NBT);
269 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...
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.
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...
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 .
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...
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...
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...
ToVectorConstReturnType toVector() const
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)
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
Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > Matrix6x
The 6d jacobian type (temporary)
int nq
Dimension of the configuration vector representation.