5 #include "pinocchio/multibody/data.hpp" 6 #include "pinocchio/multibody/model.hpp" 8 #include "pinocchio/algorithm/check.hpp" 9 #include "pinocchio/algorithm/model.hpp" 10 #include "pinocchio/algorithm/kinematics.hpp" 11 #include "pinocchio/algorithm/frames.hpp" 12 #include "pinocchio/algorithm/joint-configuration.hpp" 13 #include "pinocchio/algorithm/geometry.hpp" 15 #include "pinocchio/parsers/sample-models.hpp" 17 #include <boost/test/unit_test.hpp> 18 #include <boost/utility/binary.hpp> 22 BOOST_AUTO_TEST_SUITE ( BOOST_TEST_MODULE )
32 BOOST_CHECK(subtree.size()==6);
34 for(
size_t i=1;
i<subtree.size();++
i)
36 BOOST_CHECK(model.
parents[subtree[
i]]==subtree[
i-1]);
69 BOOST_CHECK(model.
supports[0] == support0_ref);
77 size_t current_id = support.size()-2;
83 BOOST_CHECK(
parent_id == support[current_id]);
111 BOOST_CHECK(model == model);
119 BOOST_CHECK(model.
cast<
double>() == model.
cast<
double>());
120 BOOST_CHECK(model.
cast<
double>().cast<
long double>() == model.
cast<
long double>());
129 for(
size_t k = 0; k < 20; ++k)
131 models.push_back(
Model());
134 BOOST_CHECK(model == models.back());
138 #ifdef PINOCCHIO_WITH_HPP_FCL 141 std::string operator() (
const std::string& n) {
return p + n; }
143 AddPrefix (
const char* _p) :
p(_p) {}
152 buildModels::manipulatorGeometries(manipulator, geomManipulator);
155 AddPrefix addManipulatorPrefix (
"manipulator/");
156 std::transform (++manipulator.
names.begin(), manipulator.
names.end(),
157 ++manipulator.
names.begin(), addManipulatorPrefix);
158 std::transform (++manipulator.
frames.begin(), manipulator.
frames.end(),
159 ++manipulator.
frames.begin(), addManipulatorPrefix);
161 BOOST_TEST_MESSAGE(manipulator);
164 buildModels::humanoidGeometries(humanoid, geomHumanoid);
167 AddPrefix addHumanoidPrefix (
"humanoid/");
168 std::transform (++humanoid.
names.begin(), humanoid.
names.end(),
169 ++humanoid.
names.begin(), addHumanoidPrefix);
170 std::transform (++humanoid.
frames.begin(), humanoid.
frames.end(),
171 ++humanoid.
frames.begin(), addHumanoidPrefix);
173 BOOST_TEST_MESSAGE(humanoid);
176 manipulator.inertias[0].setRandom();
183 appendModel (humanoid, manipulator, geomHumanoid, geomManipulator, fid,
190 BOOST_CHECK(model1 == model2);
191 BOOST_CHECK(model1 == model3);
192 BOOST_CHECK(model2 == model3);
196 BOOST_CHECK(model1.
check(data1));
198 BOOST_TEST_MESSAGE(model1);
206 humanoid.
getFrameId(
"humanoid/chest2_joint"), aMb,
209 appendModel (humanoid, manipulator, geomHumanoid, geomManipulator, fid,
216 BOOST_CHECK(model == model2);
217 BOOST_CHECK(model == model3);
218 BOOST_CHECK(model2 == model3);
221 BOOST_TEST_MESSAGE(model);
224 BOOST_CHECK(model.
check(data));
227 BOOST_CHECK_EQUAL(model.
getJointId(
"humanoid/chest2_joint"),
232 for (
JointIndex jid = 1; jid < chest2; ++jid) {
233 BOOST_TEST_MESSAGE(
"Checking joint " << jid <<
" " << model.
names[jid]);
234 BOOST_CHECK_EQUAL(model.
names[jid], humanoid.
names[jid]);
235 BOOST_CHECK_EQUAL(model.inertias[jid], humanoid.inertias[jid]);
236 BOOST_CHECK_EQUAL(model.jointPlacements[jid], humanoid.jointPlacements[jid]);
238 BOOST_TEST_MESSAGE(
"Checking joint " << chest2 <<
" " << model.
names[chest2]);
239 BOOST_CHECK_EQUAL(model.
names[chest2], humanoid.
names[chest2]);
240 BOOST_CHECK_MESSAGE(model.inertias[chest2].isApprox(manipulator.inertias[0].se3Action(aMb) + humanoid.inertias[chest2]),
241 model.inertias[chest2] <<
" != " << manipulator.inertias[0].se3Action(aMb) + humanoid.inertias[chest2]);
242 BOOST_CHECK_EQUAL(model.jointPlacements[chest2], humanoid.jointPlacements[chest2]);
245 BOOST_TEST_MESSAGE(
"Checking joint " << chest2+jid <<
" " << model.
names[chest2+jid]);
246 BOOST_CHECK_EQUAL(model.
names[chest2+jid], manipulator.
names[jid]);
247 BOOST_CHECK_EQUAL(model.inertias[chest2+jid], manipulator.inertias[jid]);
249 BOOST_CHECK_EQUAL(model.jointPlacements[chest2+jid], aMb*manipulator.jointPlacements[jid]);
251 BOOST_CHECK_EQUAL(model.jointPlacements[chest2+jid], manipulator.jointPlacements[jid]);
254 BOOST_TEST_MESSAGE(
"Checking joint " << jid+manipulator.
joints.size()-1 <<
" " << model.
names[jid+manipulator.
joints.size()-1]);
255 BOOST_CHECK_EQUAL(model.
names[jid+manipulator.
joints.size()-1], humanoid.
names[jid]);
256 BOOST_CHECK_EQUAL(model.inertias[jid+manipulator.
joints.size()-1], humanoid.inertias[jid]);
257 BOOST_CHECK_EQUAL(model.jointPlacements[jid+manipulator.
joints.size()-1], humanoid.jointPlacements[jid]);
266 nparent = model.
frames[nframe.previousFrame];
267 BOOST_CHECK_EQUAL(
parent.name, nparent.name);
268 BOOST_CHECK_EQUAL(frame.
placement, nframe.placement);
275 nparent = model.
frames[nframe.previousFrame];
277 BOOST_CHECK_EQUAL(
parent.name, nparent.name);
278 BOOST_CHECK_EQUAL(frame.
placement, nframe.placement);
286 Model humanoid_model;
289 static const std::vector<JointIndex> empty_index_vector;
296 Model humanoid_copy_model =
buildReducedModel(humanoid_model,empty_index_vector,reference_config_humanoid);
298 BOOST_CHECK(humanoid_copy_model.
names == humanoid_model.
names);
299 BOOST_CHECK(humanoid_copy_model.
joints == humanoid_model.
joints);
300 BOOST_CHECK(humanoid_copy_model == humanoid_model);
303 const std::vector<JointIndex> empty_joints_to_lock;
305 const Model reduced_humanoid_model =
buildReducedModel(humanoid_model,empty_joints_to_lock,reference_config_humanoid);
306 BOOST_CHECK(reduced_humanoid_model.
njoints == humanoid_model.
njoints);
307 BOOST_CHECK(reduced_humanoid_model.
frames == humanoid_model.
frames);
308 BOOST_CHECK(reduced_humanoid_model.jointPlacements == humanoid_model.jointPlacements);
309 BOOST_CHECK(reduced_humanoid_model.
joints == humanoid_model.
joints);
313 BOOST_CHECK(reduced_humanoid_model.inertias[
joint_id].isApprox(humanoid_model.inertias[
joint_id]));
319 Model humanoid_model;
322 static const std::vector<JointIndex> empty_index_vector;
329 Model humanoid_copy_model =
buildReducedModel(humanoid_model,empty_index_vector,reference_config_humanoid);
331 BOOST_CHECK(humanoid_copy_model.
names == humanoid_model.
names);
332 BOOST_CHECK(humanoid_copy_model.
joints == humanoid_model.
joints);
333 BOOST_CHECK(humanoid_copy_model == humanoid_model);
336 std::vector<JointIndex> joints_to_lock;
337 const std::string joint1_to_lock =
"rarm_shoulder2_joint";
338 joints_to_lock.push_back(humanoid_model.
getJointId(joint1_to_lock));
339 const std::string joint2_to_lock =
"larm_shoulder2_joint";
340 joints_to_lock.push_back(humanoid_model.
getJointId(joint2_to_lock));
342 Model reduced_humanoid_model =
buildReducedModel(humanoid_model,joints_to_lock,reference_config_humanoid);
343 BOOST_CHECK(reduced_humanoid_model.
njoints == humanoid_model.
njoints-(
int)joints_to_lock.size());
345 BOOST_CHECK(reduced_humanoid_model != humanoid_model);
347 Model reduced_humanoid_model_other_signature;
348 buildReducedModel(humanoid_model,joints_to_lock,reference_config_humanoid,reduced_humanoid_model_other_signature);
349 BOOST_CHECK(reduced_humanoid_model == reduced_humanoid_model_other_signature);
352 Data data(humanoid_model), reduced_data(reduced_humanoid_model);
360 reduced_humanoid_model.
joints[
joint_id].jointConfigSelector(reduced_q) =
361 humanoid_model.
joints[reference_joint_id].jointConfigSelector(q);
369 for(
size_t frame_id = 0; frame_id < reduced_humanoid_model.
frames.size(); ++frame_id)
371 const Frame & reduced_frame = reduced_humanoid_model.
frames[frame_id];
372 switch(reduced_frame.
type)
381 BOOST_CHECK(
data.oMi[joint_id].isApprox(reduced_data.oMf[frame_id]));
386 BOOST_CHECK(
data.oMf[humanoid_frame_id].isApprox(reduced_data.oMf[frame_id]));
390 BOOST_CHECK_MESSAGE(
false,
"The frame " << reduced_frame.
name <<
" is not presend in the humanoid_model");
398 BOOST_CHECK(
data.oMf[humanoid_frame_id].isApprox(reduced_data.oMf[frame_id]));
410 VectorOfModels models;
411 for(
size_t k = 0; k < 100; ++k)
413 models.push_back(
Model());
418 #ifdef PINOCCHIO_WITH_HPP_FCL 421 Model humanoid_model;
429 buildModels::humanoidGeometries(humanoid_model, humanoid_geometry);
431 static const std::vector<JointIndex> empty_index_vector;
435 reference_config_humanoid,humanoid_copy_model,humanoid_copy_geometry);
437 BOOST_CHECK(humanoid_copy_model == humanoid_model);
438 BOOST_CHECK(humanoid_copy_geometry == humanoid_geometry);
440 std::vector<JointIndex> joints_to_lock;
441 const std::string joint1_to_lock =
"rarm_shoulder2_joint";
442 joints_to_lock.push_back(humanoid_model.
getJointId(joint1_to_lock));
443 const std::string joint2_to_lock =
"larm_shoulder2_joint";
444 joints_to_lock.push_back(humanoid_model.
getJointId(joint2_to_lock));
448 reference_config_humanoid,reduced_humanoid_model,reduced_humanoid_geometry);
450 BOOST_CHECK(reduced_humanoid_geometry.
ngeoms == humanoid_geometry.
ngeoms);
458 BOOST_CHECK_EQUAL(go1.name, go2.name);
459 BOOST_CHECK_EQUAL(go1.geometry, go2.geometry);
460 BOOST_CHECK_EQUAL(go1.meshPath, go2.meshPath);
461 BOOST_CHECK_EQUAL(go1.meshScale, go2.meshScale);
462 BOOST_CHECK_EQUAL(go1.overrideMaterial, go2.overrideMaterial);
463 BOOST_CHECK_EQUAL(go1.meshColor, go2.meshColor);
464 BOOST_CHECK_EQUAL(go1.meshTexturePath, go2.meshTexturePath);
465 BOOST_CHECK_EQUAL(humanoid_model.
frames[go1.parentFrame].name,
466 reduced_humanoid_model.
frames[go2.parentFrame].name);
469 Data data(humanoid_model), reduced_data(reduced_humanoid_model);
477 reduced_humanoid_model.
joints[
joint_id].jointConfigSelector(reduced_q) =
478 humanoid_model.
joints[reference_joint_id].jointConfigSelector(q);
484 for(
size_t frame_id = 0; frame_id < reduced_humanoid_model.
frames.size(); ++frame_id)
486 const Frame & reduced_frame = reduced_humanoid_model.
frames[frame_id];
487 switch(reduced_frame.
type)
496 BOOST_CHECK(
data.oMi[joint_id].isApprox(reduced_data.oMf[frame_id]));
501 BOOST_CHECK(
data.oMf[humanoid_frame_id].isApprox(reduced_data.oMf[frame_id]));
505 BOOST_CHECK_MESSAGE(
false,
"The frame " << reduced_frame.
name <<
" is not presend in the humanoid_model");
513 BOOST_CHECK(
data.oMf[humanoid_frame_id].isApprox(reduced_data.oMf[frame_id]));
525 BOOST_CHECK(
geom_data.oMg.size() == reduded_geom_data.oMg.size());
528 BOOST_CHECK(
geom_data.oMg[
i].isApprox(reduded_geom_data.oMg[
i]));
532 std::vector<GeometryModel> full_geometry_models;
533 full_geometry_models.push_back(humanoid_geometry);
534 full_geometry_models.push_back(humanoid_geometry);
535 full_geometry_models.push_back(humanoid_geometry);
537 std::vector<GeometryModel> reduced_geometry_models;
539 Model reduced_humanoid_model_other_sig;
541 reference_config_humanoid,reduced_humanoid_model_other_sig,reduced_geometry_models);
543 BOOST_CHECK(reduced_geometry_models[0] == reduced_humanoid_geometry);
544 BOOST_CHECK(reduced_geometry_models[1] == reduced_humanoid_geometry);
545 BOOST_CHECK(reduced_geometry_models[2] == reduced_humanoid_geometry);
547 #endif // PINOCCHIO_WITH_HPP_FCL 549 BOOST_AUTO_TEST_SUITE_END()
result_of::push_front< V const, T >::type append(T const &t, V const &v)
Append the element T at the front of boost fusion vector V.
typedef PINOCCHIO_ALIGNED_STD_VECTOR(JointData) JointDataVector
JointModelVector joints
Model of joint i, encapsulated in a JointModelAccessor.
void appendModel(const ModelTpl< Scalar, Options, JointCollectionTpl > &modelA, const ModelTpl< Scalar, Options, JointCollectionTpl > &modelB, const FrameIndex frameInModelA, const SE3Tpl< Scalar, Options > &aMb, ModelTpl< Scalar, Options, JointCollectionTpl > &model)
Append a child model into a parent model, after a specific frame given by its index.
A Plucker coordinate frame attached to a parent joint inside a kinematic tree.
int njoints
Number of joints.
CollisionPairVector collisionPairs
Vector of collision pairs.
bool check(const AlgorithmCheckerBase< D > &checker=AlgorithmCheckerBase< D >()) const
Check the validity of the attributes of Model with respect to the specification of some algorithms...
std::vector< std::string > names
Name of joint i
NewScalar cast(const Scalar &value)
ConfigVectorType lowerPositionLimit
Lower joint configuration limit.
BOOST_AUTO_TEST_CASE(test_model_subtree)
FrameVector frames
Vector of operational frames registered on the model.
std::vector< int > nvs
Dimension of the joint i tangent subspace.
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.
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
void humanoid(ModelTpl< Scalar, Options, JointCollectionTpl > &model, bool usingFF=true)
Create a 28-DOF kinematic chain of a floating humanoid robot.
std::vector< IndexVector > subtrees
Vector of joint subtrees. subtree[j] corresponds to the subtree supported by the joint j...
ConfigVectorMap referenceConfigurations
Map of reference configurations, indexed by user given names.
FrameType type
Type of the frame.
int nframes
Number of operational frames.
bool existJointName(const std::string &name) const
Check if a joint given by its name exists.
std::vector< int > nqs
Dimension of the joint i configuration subspace.
GeometryObjectVector geometryObjects
Vector of GeometryObjects used for collision computations.
std::vector< int > idx_qs
Starting index of the joint i in the configuration space.
std::vector< Index > IndexVector
pinocchio::JointIndex JointIndex
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.
bool existFrame(const std::string &name, const FrameType &type=(FrameType)(JOINT|FIXED_JOINT|BODY|OP_FRAME|SENSOR)) const
Checks if a frame given by its name exists.
Index ngeoms
The number of GeometryObjects.
void addAllCollisionPairs()
Add all possible collision pairs.
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...
SE3 placement
Placement of the frame wrt the parent joint.
Main pinocchio namespace.
std::vector< int > idx_vs
Starting index of the joint i in the tangent configuration space.
void neutral(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ReturnType > &qout)
Return the neutral configuration element related to the model configuration space.
std::vector< JointIndex > parents
Joint parent of joint i, denoted li (li==parents[i]).
JointIndex getJointId(const std::string &name) const
Return the index of a joint given by its name.
std::string name
Name of the frame.
ConfigVectorType upperPositionLimit
Upper joint configuration limit.
void updateGeometryPlacements(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const GeometryModel &geom_model, GeometryData &geom_data, const Eigen::MatrixBase< ConfigVectorType > &q)
Apply a forward kinematics and update the placement of the geometry objects.
std::vector< IndexVector > supports
Vector of joint supports. supports[j] corresponds to the collection of all joints located on the path...
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
JointCollectionTpl & model
FrameIndex previousFrame
Index of the previous frame.
int nq
Dimension of the configuration vector representation.
void framesForwardKinematics(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q)
First calls the forwardKinematics on the model, then computes the placement of each frame...
void manipulator(ModelTpl< Scalar, Options, JointCollectionTpl > &model)
Create a 6-DOF kinematic chain shoulder-elbow-wrist.
void buildReducedModel(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, std::vector< JointIndex > list_of_joints_to_lock, const Eigen::MatrixBase< ConfigVectorType > &reference_configuration, ModelTpl< Scalar, Options, JointCollectionTpl > &reduced_model)
Build a reduced model from a given input model and a list of joint to lock.
ModelTpl< NewScalar, Options, JointCollectionTpl > cast() const
void fill(Eigen::Ref< MatType > mat, const typename MatType::Scalar &value)