Go to the documentation of this file.
12 #include <boost/test/unit_test.hpp>
14 BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE)
20 + std::string(
"/example-robot-data/robots/cassie_description/robots/cassie.sdf");
24 const std::string rootLinkName =
"pelvis";
30 BOOST_CHECK(
model.nq == 62);
38 + std::string(
"/example-robot-data/robots/cassie_description/robots/cassie.sdf");
40 const std::string rootLinkName =
"pelvis";
48 BOOST_CHECK(
model.nq == 69);
56 + std::string(
"/example-robot-data/robots/cassie_description/robots/cassie.sdf");
58 const std::string rootLinkName =
"";
66 BOOST_CHECK(
model.nq == 69);
73 const std::string rootLinkName =
"WAIST_LINK0";
78 BOOST_CHECK(
model.names[1] ==
"root_joint");
81 const std::string name_ =
"freeFlyer_joint";
86 BOOST_CHECK(model_name.
names[1] == name_);
95 const std::string rootLinkName =
"WAIST_LINK0";
103 const std::string filename_urdf =
PINOCCHIO_MODEL_DIR + std::string(
"/simple_humanoid.urdf");
112 BOOST_CHECK(model_urdf.
nq == model_sdf.
nq);
113 BOOST_CHECK(model_urdf.
nv == model_sdf.
nv);
119 BOOST_CHECK(model_urdf.
names == model_sdf.
names);
122 BOOST_CHECK(model_urdf.
name == model_sdf.
name);
124 BOOST_CHECK(model_urdf.
nqs == model_sdf.
nqs);
126 BOOST_CHECK(model_urdf.
nvs == model_sdf.
nvs);
131 typename ConfigVectorMap::const_iterator it_model_urdf =
136 std::advance(it_model_urdf, k);
137 BOOST_CHECK(
it->second.size() == it_model_urdf->second.size());
138 BOOST_CHECK(
it->second == it_model_urdf->second);
146 BOOST_CHECK(model_urdf.
damping.size() == model_sdf.
damping.size());
170 for (
size_t k = 1; k < model_sdf.
inertias.size(); ++k)
182 BOOST_CHECK(model_urdf.
frames.size() == model_sdf.
frames.size());
183 for (
size_t k = 1; k < model_urdf.
frames.size(); ++k)
185 BOOST_CHECK(model_urdf.
frames[k] == model_sdf.
frames[k]);
192 std::string filestr(
"<sdf version=\"1.6\">"
193 " <model name=\"parallelogram\">"
194 " <link name=\"link_A1\">"
195 " <pose>0 0 0 0 0 0</pose>"
197 " <pose>0 0 0 0 0 0</pose>"
200 " <ixx>0.008416666667</ixx>"
201 " <iyy>0.841666666667</iyy>"
202 " <izz>0.833416666667</izz>"
208 " <visual name=\"link_A1_visual\">"
211 " <length>1.0</length>"
212 " <radius>0.05</radius>"
217 " <link name=\"link_B1\">"
218 " <pose>-0.2 0 0 0 0 0</pose>"
220 " <pose>0 0 0 0 0 0</pose>"
223 " <ixx>0.0042083333333</ixx>"
224 " <iyy>0.1541666666667</iyy>"
225 " <izz>0.1500416666667</izz>"
231 " <visual name=\"link_B1_visual\">"
234 " <length>0.6</length>"
235 " <radius>0.05</radius>"
240 " <link name=\"link_A2\">"
241 " <pose>0.6 0 0 0 0 0</pose>"
243 " <pose>0 0 0 0 0 0</pose>"
246 " <ixx>0.008416666667</ixx>"
247 " <iyy>0.841666666667</iyy>"
248 " <izz>0.833416666667</izz>"
254 " <visual name=\"link_A2_visual\">"
257 " <length>1.0</length>"
258 " <radius>0.05</radius>"
263 " <link name=\"link_B2\">"
264 " <pose>0.8 0 0 0 0 0</pose>"
266 " <pose>0 0 0 0 0 0</pose>"
269 " <ixx>0.0042083333333</ixx>"
270 " <iyy>0.1541666666667</iyy>"
271 " <izz>0.1500416666667</izz>"
277 " <visual name=\"link_B2_visual\">"
280 " <length>0.6</length>"
281 " <radius>0.05</radius>"
286 " <joint name=\"joint_B1\" type=\"revolute\">"
287 " <pose>-0.3 0 0 0 0 0</pose>"
288 " <child>link_B1</child>"
289 " <parent>link_A1</parent>"
292 " <use_parent_model_frame>1</use_parent_model_frame>"
295 " <joint name=\"joint_A2\" type=\"revolute\">"
296 " <pose>-0.5 0 0 0 0 0</pose>"
297 " <child>link_A2</child>"
298 " <parent>link_B1</parent>"
301 " <use_parent_model_frame>1</use_parent_model_frame>"
304 " <joint name=\"joint_B2\" type=\"revolute\">"
305 " <pose>-0.3 0 0 0 0 0</pose>"
306 " <child>link_B2</child>"
307 " <parent>link_A1</parent>"
310 " <use_parent_model_frame>1</use_parent_model_frame>"
313 " <joint name=\"joint_B3\" type=\"revolute\">"
314 " <pose>0.5 0 0 0 0 0</pose>"
315 " <child>link_A2</child>"
316 " <parent>link_B2</parent>"
319 " <use_parent_model_frame>1</use_parent_model_frame>"
345 Eigen::Vector3d::UnitZ(), Eigen::Vector3d::UnitX())
354 Eigen::Quaterniond::FromTwoVectors(Eigen::Vector3d::UnitZ(), Eigen::Vector3d::UnitX()).matrix();
381 model.appendBodyToJoint(joint4_id, inertia_link_A_2, placement_center_link_A_minus);
387 BOOST_CHECK(
model.nq == model_sdf.
nq);
388 BOOST_CHECK(
model.nv == model_sdf.
nv);
400 BOOST_CHECK(
model.nqs == model_sdf.
nqs);
402 BOOST_CHECK(
model.nvs == model_sdf.
nvs);
404 for (std::size_t k = 1; k <
model.jointPlacements.size(); k++)
409 for (std::size_t k = 1; k <
model.inertias.size(); k++)
411 BOOST_CHECK(
model.inertias[k].isApprox(model_sdf.
inertias[k]));
423 BOOST_AUTO_TEST_SUITE_END()
std::vector< std::string > names
Name of the joints.
FrameVector frames
Vector of operational frames registered on the model.
SE3Vector jointPlacements
Vector of joint placements: placement of a joint i wrt its parent joint frame.
ConfigVectorType lowerPositionLimit
Lower joint configuration limit.
ModelTpl< Scalar, Options, JointCollectionTpl > & buildModelFromXML(const std::string &xmlStream, const typename ModelTpl< Scalar, Options, JointCollectionTpl >::JointModel &rootJoint, const std::string &rootJointName, ModelTpl< Scalar, Options, JointCollectionTpl > &model, PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) &contact_models, const std::string &rootLinkName="", const std::vector< std::string > &parentGuidance={}, const bool verbose=false)
Build the model from an XML stream with a particular joint as root of the model tree inside the model...
GeometryModel & buildGeom(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const std::string &filename, const GeometryType type, GeometryModel &geomModel, const std::string &rootLinkName="", const std::vector< std::string > &packageDirs=std::vector< std::string >(), ::hpp::fcl::MeshLoaderPtr meshLoader=::hpp::fcl::MeshLoaderPtr())
Build The GeometryModel from a SDF file. Search for meshes in the directories specified by the user f...
JointModelVector joints
Vector of joint models.
std::string name
Model name.
@ CONTACT_6D
Point contact model.
ModelTpl< Scalar, Options, JointCollectionTpl > & buildModel(const std::string &filename, const typename ModelTpl< Scalar, Options, JointCollectionTpl >::JointModel &rootJoint, const std::string &rootJointName, ModelTpl< Scalar, Options, JointCollectionTpl > &model, PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) &contact_models, const std::string &rootLinkName="", const std::vector< std::string > &parentGuidance={}, const bool verbose=false)
Build the model from a SDF file with a particular joint as root of the model tree inside the model gi...
TangentVectorType rotorInertia
Vector of rotor inertia parameters.
InertiaVector inertias
Vector of spatial inertias supported by each joint.
ConstLinearRef translation() const
ConfigVectorMap referenceConfigurations
Map of reference configurations, indexed by user given names.
std::vector< IndexVector > subtrees
Vector of joint subtrees. subtree[j] corresponds to the subtree supported by the joint j....
std::vector< int > nqs
Vector of dimension of the joint configuration subspace.
std::vector< int > nvs
Dimension of the *i*th joint tangent subspace.
std::vector< IndexVector > children
Vector of children index. Chidren of the i*th joint, denoted *mu(i) corresponds to the set (i==parent...
std::vector< int > idx_qs
Vector of starting index of the *i*th joint in the configuration space.
TangentVectorType rotorGearRatio
Vector of rotor gear ratio parameters.
VectorXs armature
Vector of armature values expressed at the joint level This vector may contain the contribution of ro...
ModelTpl< Scalar, Options, JointCollectionTpl > & buildModel(const std::string &filename, const typename ModelTpl< Scalar, Options, JointCollectionTpl >::JointModel &rootJoint, const std::string &rootJointName, ModelTpl< Scalar, Options, JointCollectionTpl > &model, const bool verbose=false)
Build the model from a URDF file with a particular joint as root of the model tree inside the model g...
int nframes
Number of operational frames.
TangentVectorType velocityLimit
Vector of maximal joint velocities.
int nbodies
Number of bodies.
TangentVectorType friction
Vector of joint friction parameters.
#define PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(T)
Motion gravity
Spatial gravity of the model.
TangentVectorType damping
Vector of joint damping parameters.
int nv
Dimension of the velocity vector space.
std::map< std::string, ConfigVectorType > ConfigVectorMap
Map between a string (key) and a configuration vector.
TangentVectorType effortLimit
Vector of maximal joint torques.
static InertiaTpl FromBox(const Scalar mass, const Scalar x, const Scalar y, const Scalar z)
Computes the Inertia of a box defined by its mass and main dimensions (x,y,z).
std::vector< JointIndex > parents
Vector of parent joint indexes. The parent of joint i, denoted li, corresponds to li==parents[i].
BOOST_AUTO_TEST_CASE(build_model)
std::vector< int > idx_vs
Starting index of the *i*th joint in the tangent configuration space.
ConfigVectorType upperPositionLimit
Upper joint configuration limit.
int nq
Dimension of the configuration vector representation.
int njoints
Number of joints.
#define PINOCCHIO_MODEL_DIR
pinocchio
Author(s):
autogenerated on Thu Dec 19 2024 03:41:32