5 #include "pinocchio/spatial/fwd.hpp" 6 #include "pinocchio/spatial/explog.hpp" 7 #include "pinocchio/algorithm/regressor.hpp" 8 #include "pinocchio/algorithm/rnea.hpp" 9 #include "pinocchio/algorithm/frames.hpp" 10 #include "pinocchio/algorithm/joint-configuration.hpp" 11 #include "pinocchio/algorithm/center-of-mass.hpp" 12 #include "pinocchio/parsers/sample-models.hpp" 16 #include <boost/test/unit_test.hpp> 17 #include <boost/utility/binary.hpp> 19 BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE)
23 using namespace Eigen;
41 const double eps = 1e-8;
62 Motion::Vector6
v = Motion::Vector6::Zero();
64 SE3 & M_placement_plus = model_plus.jointPlacements[(
JointIndex)
i];
65 for(Eigen::DenseIndex k = 0; k < 6; ++k)
68 M_placement_plus = M_placement *
exp6(
Motion(v));
73 kinematic_regressor_L_fd.middleCols<6>(6*(
i-1)).col(k) = diff_L.
toVector()/
eps;
74 const Motion diff_LWA = Mi_LWA.
act(diff_L);
75 kinematic_regressor_LWA_fd.middleCols<6>(6*(
i-1)).col(k) = diff_LWA.
toVector()/
eps;
77 kinematic_regressor_W_fd.middleCols<6>(6*(
i-1)).col(k) = diff_W.
toVector()/
eps;
81 M_placement_plus = M_placement;
84 BOOST_CHECK(kinematic_regressor_L.isApprox(kinematic_regressor_L_fd,sqrt(eps)));
85 BOOST_CHECK(kinematic_regressor_LWA.isApprox(kinematic_regressor_LWA_fd,sqrt(eps)));
86 BOOST_CHECK(kinematic_regressor_W.isApprox(kinematic_regressor_W_fd,sqrt(eps)));
92 using namespace Eigen;
126 BOOST_CHECK(kinematic_regressor_L.isApprox(kinematic_regressor_L_ref));
127 BOOST_CHECK(kinematic_regressor_LWA.isApprox(kinematic_regressor_LWA_ref));
128 BOOST_CHECK(kinematic_regressor_W.isApprox(kinematic_regressor_W_ref));
134 using namespace Eigen;
144 model.
addBodyFrame(
"test_body", joint_id, SE3::Random(), -1);
155 const double eps = 1e-8;
176 BOOST_CHECK(kinematic_regressor_L.isApprox(kinematic_regressor_L_ref));
177 BOOST_CHECK(kinematic_regressor_LWA.isApprox(kinematic_regressor_LWA_ref));
178 BOOST_CHECK(kinematic_regressor_W.isApprox(kinematic_regressor_W_ref));
190 Motion::Vector6
v = Motion::Vector6::Zero();
192 SE3 & M_placement_plus = model_plus.jointPlacements[(
JointIndex)
i];
193 for(Eigen::DenseIndex k = 0; k < 6; ++k)
196 M_placement_plus = M_placement *
exp6(
Motion(v));
202 kinematic_regressor_L_fd.middleCols<6>(6*(
i-1)).col(k) = diff_L.
toVector()/
eps;
203 const Motion diff_LWA = Mf_LWA.
act(diff_L);
204 kinematic_regressor_LWA_fd.middleCols<6>(6*(
i-1)).col(k) = diff_LWA.
toVector()/
eps;
206 kinematic_regressor_W_fd.middleCols<6>(6*(
i-1)).col(k) = diff_W.
toVector()/
eps;
210 M_placement_plus = M_placement;
213 BOOST_CHECK(kinematic_regressor_L.isApprox(kinematic_regressor_L_fd,sqrt(eps)));
214 BOOST_CHECK(kinematic_regressor_LWA.isApprox(kinematic_regressor_LWA_fd,sqrt(eps)));
215 BOOST_CHECK(kinematic_regressor_W.isApprox(kinematic_regressor_W_fd,sqrt(eps)));
221 using namespace Eigen;
236 for(
int k = 1; k < model.
njoints; ++k)
238 const Inertia &
Y = model.inertias[(size_t)k];
243 Vector3d static_com_ref;
244 static_com_ref <<
com;
248 BOOST_CHECK(static_com.isApprox(static_com_ref));
253 using namespace Eigen;
264 BOOST_CHECK(f_regressor.isApprox(f.
toVector()));
269 using namespace Eigen;
282 rnea(model,data,q,v,a);
288 BOOST_CHECK(f_regressor.isApprox(f.
toVector()));
293 using namespace Eigen;
301 const SE3 & framePlacement = SE3::Random();
310 rnea(model,data,q,v,a);
317 BOOST_CHECK(f_regressor.isApprox(f.
toVector()));
322 using namespace Eigen;
338 rnea(model,data_ref,q,v,a);
342 params.segment<10>((int)((
i-1)*10)) = model.inertias[
i].toDynamicParameters();
348 BOOST_CHECK(tau_regressor.isApprox(data_ref.
tau));
351 BOOST_AUTO_TEST_SUITE_END()
Force vxiv(const Motion &v) const
Vector10 toDynamicParameters() const
The WORLD frame convention corresponds to the frame concident with the Universe/Inertial frame but mo...
TangentVectorType tau
Vector of joint torques (dim model.nv).
BOOST_AUTO_TEST_CASE(test_kinematic_regressor_joint)
ToVectorConstReturnType toVector() const
Return the force as an Eigen vector.
SE3GroupAction< D >::ReturnType actInv(const D &d) const
by = aXb.actInv(ay)
MatrixXs jointTorqueRegressor
Matrix related to joint torque regressor.
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...
A Plucker coordinate frame attached to a parent joint inside a kinematic tree.
int njoints
Number of joints.
const Vector3 & lever() const
ConfigVectorType lowerPositionLimit
Lower joint configuration limit.
DataTpl< Scalar, Options, JointCollectionTpl >::BodyRegressorType & jointBodyRegressor(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, JointIndex jointId)
Computes the regressor for the dynamic parameters of a rigid body attached to a given joint...
JointIndex parent
Index of the parent joint.
FrameVector frames
Vector of operational frames registered on the model.
MotionTpl< Scalar, Options > log6(const SE3Tpl< Scalar, Options > &M)
Log: SE3 -> se3.
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.
DataTpl< Scalar, Options, JointCollectionTpl >::BodyRegressorType & frameBodyRegressor(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, FrameIndex frameId)
Computes the regressor for the dynamic parameters of a rigid body attached to a given frame...
int nframes
Number of operational frames.
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.
void bodyRegressor(const MotionDense< MotionVelocity > &v, const MotionDense< MotionAcceleration > &a, const Eigen::MatrixBase< OutputType > ®ressor)
Computes the regressor for the dynamic parameters of a single rigid body.
The LOCAL frame convention corresponds to the frame directly attached to the moving part (Joint...
MotionTpl< double, 0 > Motion
DataTpl< Scalar, Options, JointCollectionTpl >::MatrixXs & computeJointTorqueRegressor(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 the joint torque regressor that links the joint torque to the dynamic parameters of each lin...
ConstAngularRef rotation() const
SE3 placement
Placement of the frame wrt the parent joint.
Main pinocchio namespace.
ToVectorConstReturnType toVector() const
JointIndex getJointId(const std::string &name) const
Return the index of a joint given by its name.
The LOCAL_WORLD_ALIGNED frame convention corresponds to the frame centered on the moving part (Joint...
int nv
Dimension of the velocity vector space.
void updateFramePlacements(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data)
Updates the position of each frame contained in the model.
DataTpl< Scalar, Options, JointCollectionTpl >::Matrix3x & computeStaticRegressor(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q)
Computes the static regressor that links the center of mass positions of all the links to the center ...
SE3GroupAction< D >::ReturnType act(const D &d) const
ay = aXb.act(by)
void computeJointKinematicRegressor(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex joint_id, const ReferenceFrame rf, const SE3Tpl< Scalar, Options > &placement, const Eigen::MatrixBase< Matrix6xReturnType > &kinematic_regressor)
Computes the kinematic regressor that links the joint placements variations of the whole kinematic tr...
const DataTpl< Scalar, Options, JointCollectionTpl >::Vector3 & centerOfMass(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const bool computeSubtreeComs=true)
Computes the center of mass position of a given model according to a particular joint configuration...
ConfigVectorType upperPositionLimit
Upper joint configuration limit.
Matrix3x staticRegressor
Matrix related to static regressor.
void computeFrameKinematicRegressor(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id, const ReferenceFrame rf, const Eigen::MatrixBase< Matrix6xReturnType > &kinematic_regressor)
Computes the kinematic regressor that links the joint placement variations of the whole kinematic tre...
SE3Tpl< typename MotionDerived::Scalar, PINOCCHIO_EIGEN_PLAIN_TYPE(typename MotionDerived::Vector3)::Options > exp6(const MotionDense< MotionDerived > &nu)
Exp: se3 -> SE3.
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 manipulator(ModelTpl< Scalar, Options, JointCollectionTpl > &model)
Create a 6-DOF kinematic chain shoulder-elbow-wrist.
FrameIndex addBodyFrame(const std::string &body_name, const JointIndex &parentJoint, const SE3 &body_placement=SE3::Identity(), int previousFrame=-1)
Add a body to the frame tree.