5 #include "pinocchio/multibody/model.hpp" 6 #include "pinocchio/multibody/data.hpp" 7 #include "pinocchio/algorithm/kinematics.hpp" 8 #include "pinocchio/algorithm/crba.hpp" 9 #include "pinocchio/algorithm/joint-configuration.hpp" 10 #include "pinocchio/parsers/sample-models.hpp" 14 #include <boost/test/unit_test.hpp> 15 #include <boost/utility/binary.hpp> 17 BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE)
21 using namespace Eigen;
38 using namespace Eigen;
56 BOOST_CHECK(
data.oMi[
i] == data_ref.oMi[
i]);
57 BOOST_CHECK(
data.liMi[
i] == data_ref.liMi[
i]);
63 using namespace Eigen;
80 BOOST_CHECK(data.v[
i] == Motion::Zero());
86 using namespace Eigen;
104 BOOST_CHECK(data.v[
i] == Motion::Zero());
105 BOOST_CHECK(data.a[
i] == Motion::Zero());
111 using namespace Eigen;
137 using namespace Eigen;
164 using namespace Eigen;
187 Motion acc_classical_local = acc;
189 acc_classical_local.
linear() = linear;
196 linear = acc_classical_world.
linear() + vel_world.angular().cross(vel_world.linear());
197 acc_classical_world.
linear() = linear;
201 Motion vel_aligned =
SE3(data.oMi[
i].rotation(), Eigen::Vector3d::Zero()).
act(vel);
202 Motion acc_classical_aligned =
SE3(data.oMi[
i].rotation(), Eigen::Vector3d::Zero()).
act(acc);
203 linear = acc_classical_aligned.
linear() + vel_aligned.angular().cross(vel_aligned.linear());
204 acc_classical_aligned.
linear() = linear;
212 using namespace Eigen;
219 jointId = model.
addJoint(jointId,
JointModelRZ(),
SE3(Matrix3d::Identity(), Vector3d(1.0, 0.0, 0.0)),
"Joint2");
235 v_local.
linear() = Vector3d(0.0, 1.0, 0.0);
236 v_local.
angular() = Vector3d(0.0, 0.0, 1.0);
239 v_world.
linear() = Vector3d::Zero();
240 v_world.
angular() = Vector3d(0.0, 0.0, 1.0);
243 v_align.
linear() = Vector3d(-1.0, 0.0, 0.0);
244 v_align.
angular() = Vector3d(0.0, 0.0, 1.0);
248 ac_local.
linear() = Vector3d(-1.0, 0.0, 0.0);
249 ac_local.
angular() = Vector3d::Zero();
251 Motion ac_world = Motion::Zero();
254 ac_align.
linear() = Vector3d(0.0, -1.0, 0.0);
255 ac_align.
angular() = Vector3d::Zero();
279 BOOST_AUTO_TEST_SUITE_END()
The WORLD frame convention corresponds to the frame concident with the Universe/Inertial frame but mo...
const DataTpl< Scalar, Options, JointCollectionTpl >::MatrixXs & crba(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q)
Computes the upper triangular part of the joint space inertia matrix M by using the Composite Rigid B...
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.
static void act(const Eigen::MatrixBase< Mat > &iV, const ForceDense< ForceDerived > &f, Eigen::MatrixBase< MatRet > const &jF)
Action of a motion set on a force object. The input motion set is represented by a 6xN matrix whose e...
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.
MotionTpl< Scalar, Options > getClassicalAcceleration(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex jointId, const ReferenceFrame rf=LOCAL)
Returns the "classical" acceleration of the joint expressed in the desired reference frame...
void updateGlobalPlacements(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data)
Update the global placement of the joints oMi according to the relative placements of the joints...
bool isApprox(const MotionDense< M2 > &m2, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
ConstLinearType linear() const
JointIndex addJoint(const JointIndex parent, const JointModel &joint_model, const SE3 &joint_placement, const std::string &joint_name)
Add a joint to the kinematic tree with infinite bounds.
The LOCAL frame convention corresponds to the frame directly attached to the moving part (Joint...
JointModelRevoluteTpl< double, 0, 2 > JointModelRZ
pinocchio::JointIndex JointIndex
SE3GroupAction< D >::ReturnType act(const D &d) const
ay = aXb.act(by)
Main pinocchio namespace.
The LOCAL_WORLD_ALIGNED frame convention corresponds to the frame centered on the moving part (Joint...
int nv
Dimension of the velocity vector space.
MotionTpl< Scalar, Options > getAcceleration(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex jointId, const ReferenceFrame rf=LOCAL)
Returns the spatial acceleration of the joint expressed in the desired reference frame. You must first call pinocchio::forwardKinematics to update placement, velocity and acceleration values in data structure.
ConfigVectorType upperPositionLimit
Upper joint configuration limit.
BOOST_AUTO_TEST_CASE(test_kinematics_constant_vector_input)
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
int nq
Dimension of the configuration vector representation.
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. You must first call pinocchio::forwardKinematics to update placement and velocity values in data structure.
void fill(Eigen::Ref< MatType > mat, const typename MatType::Scalar &value)