5 #include "pinocchio/algorithm/jacobian.hpp" 6 #include "pinocchio/algorithm/joint-configuration.hpp" 7 #include "pinocchio/algorithm/kinematics.hpp" 8 #include "pinocchio/algorithm/kinematics-derivatives.hpp" 9 #include "pinocchio/algorithm/frames.hpp" 10 #include "pinocchio/algorithm/frames-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;
32 BOOST_CHECK(model.
getFrameId(
"rand") == frameId);
33 BOOST_CHECK(model.
frames[frameId].parent == jointId);
46 Data::Matrix6x partial_dq_local_world_aligned(6,model.
nv); partial_dq_local_world_aligned.setZero();
49 Data::Matrix6x partial_dv_local_world_aligned(6,model.
nv); partial_dv_local_world_aligned.setZero();
53 partial_dq,partial_dv);
56 partial_dq_local_world_aligned,partial_dv_local_world_aligned);
59 partial_dq_local,partial_dv_local);
62 Data::Matrix6x J_ref_local_world_aligned(6,model.
nv); J_ref_local_world_aligned.setZero();
69 BOOST_CHECK(data_ref.oMf[frameId].isApprox(
data.oMf[frameId]));
70 BOOST_CHECK(partial_dv.isApprox(J_ref));
71 BOOST_CHECK(partial_dv_local_world_aligned.isApprox(J_ref_local_world_aligned));
72 BOOST_CHECK(partial_dv_local.isApprox(J_ref_local));
76 Data::Matrix6x partial_dq_fd_local_world_aligned(6,model.
nv); partial_dq_fd_local_world_aligned.setZero();
77 Data::Matrix6x partial_dq_fd_local(6,model.
nv); partial_dq_fd_local.setZero();
79 Data::Matrix6x partial_dv_fd_local_world_aligned(6,model.
nv); partial_dv_fd_local_world_aligned.setZero();
80 Data::Matrix6x partial_dv_fd_local(6,model.
nv); partial_dv_fd_local.setZero();
81 const double alpha = 1e-8;
85 Data data_plus(model);
90 for(
int k = 0; k < model.
nv; ++k)
97 partial_dv_fd_local.col(k) = (
getFrameVelocity(model,data_plus,frameId,
LOCAL) - v0_local).toVector()/alpha;
101 BOOST_CHECK(partial_dv.isApprox(partial_dv_fd,sqrt(alpha)));
102 BOOST_CHECK(partial_dv_local_world_aligned.isApprox(partial_dv_fd_local_world_aligned,sqrt(alpha)));
103 BOOST_CHECK(partial_dv_local.isApprox(partial_dv_fd_local,sqrt(alpha)));
110 for(
int k = 0; k < model.
nv; ++k)
118 SE3::Vector3 trans = data_plus.oMf[frameId].translation() - data_ref.oMf[frameId].translation();
119 v_plus_local_world_aligned.
linear() -= v_plus_local_world_aligned.
angular().cross(trans);
121 partial_dq_fd_local_world_aligned.col(k) = (v_plus_local_world_aligned - v0_local_world_aligned).toVector()/alpha;
122 partial_dq_fd_local.col(k) = (
getFrameVelocity(model,data_plus,frameId,
LOCAL) - v0_local).toVector()/alpha;
126 BOOST_CHECK(partial_dq.isApprox(partial_dq_fd,sqrt(alpha)));
127 BOOST_CHECK(partial_dq_local_world_aligned.isApprox(partial_dq_fd_local_world_aligned,sqrt(alpha)));
128 BOOST_CHECK(partial_dq_local.isApprox(partial_dq_fd_local,sqrt(alpha)));
134 using namespace Eigen;
144 BOOST_CHECK(model.
getFrameId(
"rand") == frameId);
145 BOOST_CHECK(model.
frames[frameId].parent == jointId);
158 Data::Matrix6x v_partial_dq_local(6,model.
nv); v_partial_dq_local.setZero();
159 Data::Matrix6x v_partial_dq_local_world_aligned(6,model.
nv); v_partial_dq_local_world_aligned.setZero();
161 Data::Matrix6x a_partial_dq_local_world_aligned(6,model.
nv); a_partial_dq_local_world_aligned.setZero();
162 Data::Matrix6x a_partial_dq_local(6,model.
nv); a_partial_dq_local.setZero();
164 Data::Matrix6x a_partial_dv_local_world_aligned(6,model.
nv); a_partial_dv_local_world_aligned.setZero();
165 Data::Matrix6x a_partial_dv_local(6,model.
nv); a_partial_dv_local.setZero();
167 Data::Matrix6x a_partial_da_local_world_aligned(6,model.
nv); a_partial_da_local_world_aligned.setZero();
168 Data::Matrix6x a_partial_da_local(6,model.
nv); a_partial_da_local.setZero();
172 a_partial_dq,a_partial_dv,a_partial_da);
175 v_partial_dq_local_world_aligned,
176 a_partial_dq_local_world_aligned,
177 a_partial_dv_local_world_aligned,
178 a_partial_da_local_world_aligned);
182 a_partial_dq_local,a_partial_dv_local,a_partial_da_local);
190 Data::Matrix6x v_partial_dq_ref_local_world_aligned(6,model.
nv); v_partial_dq_ref_local_world_aligned.setZero();
191 Data::Matrix6x v_partial_dq_ref_local(6,model.
nv); v_partial_dq_ref_local.setZero();
193 Data::Matrix6x v_partial_dv_ref_local_world_aligned(6,model.
nv); v_partial_dv_ref_local_world_aligned.setZero();
194 Data::Matrix6x v_partial_dv_ref_local(6,model.
nv); v_partial_dv_ref_local.setZero();
197 v_partial_dq_ref,v_partial_dv_ref);
199 BOOST_CHECK(v_partial_dq.isApprox(v_partial_dq_ref));
200 BOOST_CHECK(a_partial_da.isApprox(v_partial_dv_ref));
203 v_partial_dq_ref_local_world_aligned,v_partial_dv_ref_local_world_aligned);
205 BOOST_CHECK(v_partial_dq_local_world_aligned.isApprox(v_partial_dq_ref_local_world_aligned));
206 BOOST_CHECK(a_partial_da_local_world_aligned.isApprox(v_partial_dv_ref_local_world_aligned));
209 v_partial_dq_ref_local,v_partial_dv_ref_local);
211 BOOST_CHECK(v_partial_dq_local.isApprox(v_partial_dq_ref_local));
212 BOOST_CHECK(a_partial_da_local.isApprox(v_partial_dv_ref_local));
217 Data::Matrix6x J_ref_local_world_aligned(6,model.
nv); J_ref_local_world_aligned.setZero();
223 BOOST_CHECK(a_partial_da.isApprox(J_ref));
224 BOOST_CHECK(a_partial_da_local_world_aligned.isApprox(J_ref_local_world_aligned));
225 BOOST_CHECK(a_partial_da_local.isApprox(J_ref_local));
229 Data::Matrix6x a_partial_da_fd_local_world_aligned(6,model.
nv); a_partial_da_fd_local_world_aligned.setZero();
230 Data::Matrix6x a_partial_da_fd_local(6,model.
nv); a_partial_da_fd_local.setZero();
231 const double alpha = 1e-8;
234 Data data_plus(model);
241 for(
int k = 0; k < model.
nv; ++k)
251 BOOST_CHECK(a_partial_da.isApprox(a_partial_da_fd,sqrt(alpha)));
252 BOOST_CHECK(a_partial_da_local_world_aligned.isApprox(a_partial_da_fd_local_world_aligned,sqrt(alpha)));
253 BOOST_CHECK(a_partial_da_local.isApprox(a_partial_da_fd_local,sqrt(alpha)));
257 Data::Matrix6x a_partial_dv_fd_local_world_aligned(6,model.
nv); a_partial_dv_fd_local_world_aligned.setZero();
258 Data::Matrix6x a_partial_dv_fd_local(6,model.
nv); a_partial_dv_fd_local.setZero();
259 for(
int k = 0; k < model.
nv; ++k)
269 BOOST_CHECK(a_partial_dv.isApprox(a_partial_dv_fd,sqrt(alpha)));
270 BOOST_CHECK(a_partial_dv_local_world_aligned.isApprox(a_partial_dv_fd_local_world_aligned,sqrt(alpha)));
271 BOOST_CHECK(a_partial_dv_local.isApprox(a_partial_dv_fd_local,sqrt(alpha)));
274 a_partial_dq.setZero();
275 a_partial_dv.setZero();
276 a_partial_da.setZero();
278 a_partial_dq_local_world_aligned.setZero();
279 a_partial_dv_local_world_aligned.setZero();
280 a_partial_da_local_world_aligned.setZero();
282 a_partial_dq_local.setZero();
283 a_partial_dv_local.setZero();
284 a_partial_da_local.setZero();
287 Data::Matrix6x a_partial_dq_fd_local_world_aligned(6,model.
nv); a_partial_dq_fd_local_world_aligned.setZero();
288 Data::Matrix6x a_partial_dq_fd_local(6,model.
nv); a_partial_dq_fd_local.setZero();
293 a_partial_dq,a_partial_dv,a_partial_da);
296 v_partial_dq_local_world_aligned,
297 a_partial_dq_local_world_aligned,
298 a_partial_dv_local_world_aligned,
299 a_partial_da_local_world_aligned);
303 a_partial_dq_local,a_partial_dv_local,a_partial_da_local);
312 for(
int k = 0; k < model.
nv; ++k)
321 const SE3::Vector3 trans = data_plus.oMf[frameId].translation() - data_ref.oMf[frameId].translation();
322 a_plus_local_world_aligned.
linear() -= a_plus_local_world_aligned.
angular().cross(trans);
323 a_partial_dq_fd_local_world_aligned.col(k) = (a_plus_local_world_aligned - a0_local_world_aligned).toVector()/alpha;
328 BOOST_CHECK(a_partial_dq.isApprox(a_partial_dq_fd,sqrt(alpha)));
329 BOOST_CHECK(a_partial_dq_local_world_aligned.isApprox(a_partial_dq_fd_local_world_aligned,sqrt(alpha)));
330 BOOST_CHECK(a_partial_dq_local.isApprox(a_partial_dq_fd_local,sqrt(alpha)));
333 Data::Matrix6x v_partial_dq_other(6,model.
nv); v_partial_dq_other.setZero();
334 Data::Matrix6x v_partial_dq_local_other(6,model.
nv); v_partial_dq_local_other.setZero();
335 Data::Matrix6x v_partial_dq_local_world_aligned_other(6,model.
nv); v_partial_dq_local_world_aligned_other.setZero();
336 Data::Matrix6x v_partial_dv_other(6,model.
nv); v_partial_dv_other.setZero();
337 Data::Matrix6x v_partial_dv_local_other(6,model.
nv); v_partial_dv_local_other.setZero();
338 Data::Matrix6x v_partial_dv_local_world_aligned_other(6,model.
nv); v_partial_dv_local_world_aligned_other.setZero();
339 Data::Matrix6x a_partial_dq_other(6,model.
nv); a_partial_dq_other.setZero();
340 Data::Matrix6x a_partial_dq_local_world_aligned_other(6,model.
nv); a_partial_dq_local_world_aligned_other.setZero();
341 Data::Matrix6x a_partial_dq_local_other(6,model.
nv); a_partial_dq_local_other.setZero();
342 Data::Matrix6x a_partial_dv_other(6,model.
nv); a_partial_dv_other.setZero();
343 Data::Matrix6x a_partial_dv_local_world_aligned_other(6,model.
nv); a_partial_dv_local_world_aligned_other.setZero();
344 Data::Matrix6x a_partial_dv_local_other(6,model.
nv); a_partial_dv_local_other.setZero();
345 Data::Matrix6x a_partial_da_other(6,model.
nv); a_partial_da_other.setZero();
346 Data::Matrix6x a_partial_da_local_world_aligned_other(6,model.
nv); a_partial_da_local_world_aligned_other.setZero();
347 Data::Matrix6x a_partial_da_local_other(6,model.
nv); a_partial_da_local_other.setZero();
356 BOOST_CHECK(v_partial_dq_other.isApprox(v_partial_dq));
357 BOOST_CHECK(v_partial_dv_other.isApprox(a_partial_da));
358 BOOST_CHECK(a_partial_dq_other.isApprox(a_partial_dq));
359 BOOST_CHECK(a_partial_dv_other.isApprox(a_partial_dv));
360 BOOST_CHECK(a_partial_da_other.isApprox(a_partial_da));
363 v_partial_dq_local_world_aligned_other,
364 v_partial_dv_local_world_aligned_other,
365 a_partial_dq_local_world_aligned_other,
366 a_partial_dv_local_world_aligned_other,
367 a_partial_da_local_world_aligned_other);
369 BOOST_CHECK(v_partial_dq_local_world_aligned_other.isApprox(v_partial_dq_local_world_aligned));
370 BOOST_CHECK(v_partial_dv_local_world_aligned_other.isApprox(a_partial_da_local_world_aligned));
371 BOOST_CHECK(a_partial_dq_local_world_aligned_other.isApprox(a_partial_dq_local_world_aligned));
372 BOOST_CHECK(a_partial_dv_local_world_aligned_other.isApprox(a_partial_dv_local_world_aligned));
373 BOOST_CHECK(a_partial_da_local_world_aligned_other.isApprox(a_partial_da_local_world_aligned));
376 v_partial_dq_local_other,
377 v_partial_dv_local_other,
378 a_partial_dq_local_other,
379 a_partial_dv_local_other,
380 a_partial_da_local_other);
382 BOOST_CHECK(v_partial_dq_local_other.isApprox(v_partial_dq_local));
383 BOOST_CHECK(v_partial_dv_local_other.isApprox(a_partial_da_local));
384 BOOST_CHECK(a_partial_dq_local_other.isApprox(a_partial_dq_local));
385 BOOST_CHECK(a_partial_dv_local_other.isApprox(a_partial_dv_local));
386 BOOST_CHECK(a_partial_da_local_other.isApprox(a_partial_da_local));
389 BOOST_AUTO_TEST_SUITE_END()
The WORLD frame convention corresponds to the frame concident with the Universe/Inertial frame but mo...
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...
A Plucker coordinate frame attached to a parent joint inside a kinematic tree.
int njoints
Number of joints.
MotionTpl< Scalar, Options > getFrameVelocity(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id, const ReferenceFrame rf=LOCAL)
Returns the spatial velocity of the Frame expressed in the desired reference frame. You must first call pinocchio::forwardKinematics to update placement and velocity values in data structure.
ConfigVectorType lowerPositionLimit
Lower joint configuration limit.
FrameVector frames
Vector of operational frames registered on the model.
BOOST_AUTO_TEST_CASE(test_frames_derivatives_velocity)
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.
MotionTpl< Scalar, Options > getFrameAcceleration(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id, const ReferenceFrame rf=LOCAL)
Returns the spatial acceleration of the Frame expressed in the desired reference frame. You must first call pinocchio::forwardKinematics to update placement, velocity and acceleration values in data structure.
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.
ConstLinearType linear() const
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...
FrameIndex getFrameId(const std::string &name, const FrameType &type=(FrameType)(JOINT|FIXED_JOINT|BODY|OP_FRAME|SENSOR)) const
Returns the index of a frame given by its name.
void getFrameAccelerationDerivatives(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id, 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 derivatives of the frame acceleration quantity with respect to q...
traits< SE3Tpl >::Vector3 Vector3
FrameIndex addFrame(const Frame &frame, const bool append_inertia=true)
Adds a frame to the kinematic tree. The inertia stored within the frame will be happened to the inert...
Main pinocchio namespace.
void getFrameVelocityDerivatives(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id, const ReferenceFrame rf, const Eigen::MatrixBase< Matrix6xOut1 > &v_partial_dq, const Eigen::MatrixBase< Matrix6xOut2 > &v_partial_dv)
Computes the partial derivatives of the frame velocity quantity with respect to q and v...
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.
JointIndex getJointId(const std::string &name) const
Return the index of a joint given by its name.
void updateFramePlacements(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data)
Updates the position of each frame contained in the model.
ConfigVectorType upperPositionLimit
Upper joint configuration limit.
ConstAngularType angular() const
void getFrameJacobian(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id, const ReferenceFrame rf, const Eigen::MatrixBase< Matrix6xLike > &J)
Returns the jacobian of the frame expressed either expressed in the LOCAL frame coordinate system or ...
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)
void fill(Eigen::Ref< MatType > mat, const typename MatType::Scalar &value)