9 #include "pinocchio/multibody/model.hpp" 10 #include "pinocchio/parsers/urdf.hpp" 12 #ifdef PINOCCHIO_WITH_HPP_FCL 14 #endif // PINOCCHIO_WITH_HPP_FCL 16 #include <boost/test/unit_test.hpp> 18 #include <urdf_parser/urdf_parser.h> 21 BOOST_AUTO_TEST_SUITE ( BOOST_TEST_MODULE )
25 const std::string
filename =
PINOCCHIO_MODEL_DIR + std::string(
"/example-robot-data/robots/romeo_description/urdf/romeo_small.urdf");
33 BOOST_CHECK(model.
nq == 31);
44 BOOST_CHECK_EQUAL(model.
nq, 29);
49 BOOST_CHECK_EQUAL(geomModel.
ngeoms, 2);
51 #ifdef PINOCCHIO_WITH_HPP_FCL 53 #ifdef PINOCCHIO_URDFDOM_COLLISION_WITH_GROUP_NAME 55 #else // PINOCCHIO_URDFDOM_COLLISION_WITH_GROUP_NAME 59 #if ( HPP_FCL_MAJOR_VERSION>1 || ( HPP_FCL_MAJOR_VERSION==1 && \ 60 ( HPP_FCL_MINOR_VERSION>1 || ( HPP_FCL_MINOR_VERSION==1 && \ 61 HPP_FCL_PATCH_VERSION>3)))) 62 # define PINOCCHIO_HPP_FCL_SUPERIOR_TO_1_1_3 65 #if defined(PINOCCHIO_HPP_FCL_SUPERIOR_TO_1_1_3) && !defined(PINOCCHIO_URDFDOM_COLLISION_WITH_GROUP_NAME) 67 #undef PINOCCHIO_HPP_FCL_SUPERIOR_TO_1_1_3 68 #else // PINOCCHIO_HPP_FCL_SUPERIOR_TO_1_1_3 && !PINOCCHIO_URDFDOM_COLLISION_WITH_GROUP_NAME 70 #endif // PINOCCHIO_HPP_FCL_SUPERIOR_TO_1_1_3 && !PINOCCHIO_URDFDOM_COLLISION_WITH_GROUP_NAME 71 #endif // PINOCCHIO_WITH_HPP_FCL 76 BOOST_CHECK(model_ff.nq == 36);
88 BOOST_CHECK_EQUAL(geomModel0.
ngeoms, 2);
96 BOOST_CHECK_EQUAL(geomModel1.
ngeoms, 2);
103 const std::string
filename =
PINOCCHIO_MODEL_DIR + std::string(
"/example-robot-data/robots/romeo_description/urdf/romeo_small.urdf");
107 file.open(filename.c_str());
108 std::string filestr((std::istreambuf_iterator<char>(file)),
109 std::istreambuf_iterator<char>());
114 BOOST_CHECK(model.
nq == 31);
121 "<?xml version=\"1.0\" encoding=\"utf-8\"?>" 122 "<robot name=\"test\">" 123 " <link name=\"base_link\"/>" 124 " <link name=\"link_1\"/>" 125 " <link name=\"link_2\"/>" 126 " <joint name=\"joint_1\" type=\"fixed\">" 127 " <origin xyz=\"1 0 0\"/>" 128 " <axis xyz=\"0 0 1\"/>" 129 " <parent link=\"base_link\"/>" 130 " <child link=\"link_1\"/>" 132 " <joint name=\"joint_2\" type=\"fixed\">" 133 " <origin xyz=\"0 1 0\"/>" 134 " <axis xyz=\"0 0 1\"/>" 135 " <parent link=\"link_1\"/>" 136 " <child link=\"link_2\"/>" 151 BOOST_CHECK_EQUAL(base_link_id, model.
frames[joint1_id].previousFrame);
152 BOOST_CHECK_EQUAL(joint1_id , model.
frames[link1_id ].previousFrame);
153 BOOST_CHECK_EQUAL(link1_id , model.
frames[joint2_id].previousFrame);
154 BOOST_CHECK_EQUAL(joint2_id , model.
frames[link2_id ].previousFrame);
159 const std::string
filename =
PINOCCHIO_MODEL_DIR + std::string(
"/example-robot-data/robots/romeo_description/urdf/romeo_small.urdf");
161 ::urdf::ModelInterfaceSharedPtr urdfTree = ::urdf::parseURDFFile(filename);
166 BOOST_CHECK(model.
nq == 31);
171 const std::string
filename =
PINOCCHIO_MODEL_DIR + std::string(
"/example-robot-data/robots/romeo_description/urdf/romeo_small.urdf");
180 BOOST_CHECK(model.
nq == 38);
185 const std::string
filename =
PINOCCHIO_MODEL_DIR + std::string(
"/example-robot-data/robots/romeo_description/urdf/romeo_small.urdf");
189 file.open(filename.c_str());
190 std::string filestr((std::istreambuf_iterator<char>(file)),
191 std::istreambuf_iterator<char>());
196 BOOST_CHECK(model.
nq == 38);
201 const std::string
filename =
PINOCCHIO_MODEL_DIR + std::string(
"/example-robot-data/robots/romeo_description/urdf/romeo_small.urdf");
203 ::urdf::ModelInterfaceSharedPtr urdfTree = ::urdf::parseURDFFile(filename);
208 BOOST_CHECK(model.
nq == 38);
218 BOOST_CHECK(model.
njoints == 30);
219 const int nframes = model.
nframes;
220 const std::string filestr(
221 "<?xml version=\"1.0\" encoding=\"utf-8\"?>" 222 "<robot name=\"test\">" 223 " <link name=\"box\"/>" 228 BOOST_CHECK(model.
njoints == 30);
229 BOOST_CHECK(nframes + 1 == model.
nframes);
239 BOOST_CHECK(model.
njoints == 31);
240 const std::string filestr(
241 "<?xml version=\"1.0\" encoding=\"utf-8\"?>" 242 "<robot name=\"test\">" 243 " <link name=\"box\"/>" 249 std::invalid_argument);
270 BOOST_CHECK_THROW(model.
getFrameId(
"base"), std::invalid_argument);
275 BOOST_AUTO_TEST_SUITE_END()
int njoints
Number of joints.
FrameVector frames
Vector of operational frames registered on the model.
fixed joint frame: joint frame but for a fixed joint
#define PINOCCHIO_MODEL_DIR
int nframes
Number of operational frames.
body frame: attached to the collision, inertial or visual properties of a link
GeometryModel & buildGeom(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const std::string &filename, const GeometryType type, GeometryModel &geom_model, const std::vector< std::string > &package_paths=std::vector< std::string >(), ::hpp::fcl::MeshLoaderPtr mesh_loader=::hpp::fcl::MeshLoaderPtr())
Build The GeometryModel from a URDF file. Search for meshes in the directories specified by the user ...
GeometryObjectVector geometryObjects
Vector of GeometryObjects used for collision computations.
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.
ModelTpl< Scalar, Options, JointCollectionTpl > & buildModel(const std::string &filename, const typename ModelTpl< Scalar, Options, JointCollectionTpl >::JointModel &rootJoint, 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...
Index ngeoms
The number of GeometryObjects.
ModelTpl< Scalar, Options, JointCollectionTpl > & buildModelFromXML(const std::string &xml_stream, const typename ModelTpl< Scalar, Options, JointCollectionTpl >::JointModel &rootJoint, ModelTpl< Scalar, Options, JointCollectionTpl > &model, const bool verbose=false)
Build the model from an XML stream with a particular joint as root of the model tree inside the model...
BOOST_AUTO_TEST_CASE(build_model)
int nq
Dimension of the configuration vector representation.