src/parsers/urdf/geometry.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2015-2020 CNRS INRIA
3 //
4 
9 
10 #include <boost/property_tree/xml_parser.hpp>
11 #include <boost/property_tree/ptree.hpp>
12 
13 #include <urdf_model/model.h>
14 #include <urdf_parser/urdf_parser.h>
15 
16 #ifdef PINOCCHIO_WITH_HPP_FCL
17 
20 
21 #endif // PINOCCHIO_WITH_HPP_FCL
22 
23 namespace pinocchio
24 {
25  namespace urdf
26  {
28  namespace details
29  {
30  struct UrdfTree
31  {
33  typedef std::map<std::string, const ptree &> LinkMap_t;
34 
35  void parse(const std::string & xmlStr)
36  {
37  urdf_ = ::urdf::parseURDF(xmlStr);
38  if (!urdf_)
39  {
40  throw std::invalid_argument("Unable to parse URDF");
41  }
42 
43  std::istringstream iss(xmlStr);
44  using namespace boost::property_tree;
45  read_xml(iss, tree_, xml_parser::no_comments);
46 
47  BOOST_FOREACH (const ptree::value_type & link, tree_.get_child("robot"))
48  {
49  if (link.first == "link")
50  {
51  std::string name = link.second.get<std::string>("<xmlattr>.name");
52  links_.insert(std::pair<std::string, const ptree &>(name, link.second));
53  }
54  } // BOOST_FOREACH
55  }
56 
57  bool isCapsule(const std::string & linkName, const std::string & geomName) const
58  {
59  LinkMap_t::const_iterator _link = links_.find(linkName);
60  assert(_link != links_.end());
61  const ptree & link = _link->second;
62  if (link.count("collision_checking") == 0)
63  return false;
64  BOOST_FOREACH (const ptree::value_type & cc, link.get_child("collision_checking"))
65  {
66  if (cc.first == "capsule")
67  {
68 #ifdef PINOCCHIO_URDFDOM_COLLISION_WITH_GROUP_NAME
69  std::cerr << "Warning: support for tag link/collision_checking/capsule"
70  " is not available for URDFDOM < 0.3.0"
71  << std::endl;
72 #else
73  std::string name = cc.second.get<std::string>("<xmlattr>.name");
74  if (geomName == name)
75  return true;
76 #endif
77  }
78  } // BOOST_FOREACH
79 
80  return false;
81  }
82 
83  bool isMeshConvex(const std::string & linkName, const std::string & geomName) const
84  {
85  LinkMap_t::const_iterator _link = links_.find(linkName);
86  assert(_link != links_.end());
87  const ptree & link = _link->second;
88  if (link.count("collision_checking") == 0)
89  return false;
90  BOOST_FOREACH (const ptree::value_type & cc, link.get_child("collision_checking"))
91  {
92  if (cc.first == "convex")
93  {
94 #ifdef PINOCCHIO_URDFDOM_COLLISION_WITH_GROUP_NAME
95  std::cerr << "Warning: support for tag link/collision_checking/convex"
96  " is not available for URDFDOM < 0.3.0"
97  << std::endl;
98 #else
99  std::string name = cc.second.get<std::string>("<xmlattr>.name");
100  if (geomName == name)
101  return true;
102 #endif
103  }
104  } // BOOST_FOREACH
105 
106  return false;
107  }
108 
109  // For standard URDF tags
110  ::urdf::ModelInterfaceSharedPtr urdf_;
111  // For other tags
113  // A mapping from link name to corresponding child of tree_
115  };
116 
117  template<typename Vector3>
118  static void retrieveMeshScale(
119  const ::urdf::MeshSharedPtr & mesh, const Eigen::MatrixBase<Vector3> & scale)
120  {
121  Vector3 & scale_ = PINOCCHIO_EIGEN_CONST_CAST(Vector3, scale);
122  scale_ << mesh->scale.x, mesh->scale.y, mesh->scale.z;
123  }
124 
125 #ifdef PINOCCHIO_WITH_HPP_FCL
126 
138  std::shared_ptr<fcl::CollisionGeometry> inline retrieveCollisionGeometry(
139  const UrdfTree & tree,
140  fcl::MeshLoaderPtr & meshLoader,
141  const std::string & linkName,
142  const std::string & geomName,
143  const ::urdf::GeometrySharedPtr urdf_geometry,
144  const std::vector<std::string> & package_dirs,
145  std::string & meshPath,
146  Eigen::Vector3d & meshScale)
147  {
148  std::shared_ptr<fcl::CollisionGeometry> geometry;
149 
150  // Handle the case where collision geometry is a mesh
151  if (urdf_geometry->type == ::urdf::Geometry::MESH)
152  {
153  const ::urdf::MeshSharedPtr urdf_mesh =
154  ::urdf::static_pointer_cast<::urdf::Mesh>(urdf_geometry);
155  std::string collisionFilename = urdf_mesh->filename;
156 
157  meshPath = retrieveResourcePath(collisionFilename, package_dirs);
158  if (meshPath == "")
159  {
160  std::stringstream ss;
161  ss << "Mesh " << collisionFilename << " could not be found.";
162  throw std::invalid_argument(ss.str());
163  }
164 
165  fcl::Vec3f scale = fcl::Vec3f(urdf_mesh->scale.x, urdf_mesh->scale.y, urdf_mesh->scale.z);
166 
167  retrieveMeshScale(urdf_mesh, meshScale);
168 
169  // Create FCL mesh by parsing Collada file.
170  hpp::fcl::BVHModelPtr_t bvh = meshLoader->load(meshPath, scale);
171  bool convex = tree.isMeshConvex(linkName, geomName);
172  if (convex)
173  {
174  bvh->buildConvexRepresentation(false);
175  geometry = std::shared_ptr<fcl::CollisionGeometry>(
176  bvh->convex.get(), [bvh](...) mutable { bvh->convex.reset(); });
177  }
178  else
179  {
180  geometry = std::shared_ptr<fcl::CollisionGeometry>(
181  bvh.get(), [bvh](...) mutable { bvh.reset(); });
182  }
183  }
184 
185  // Handle the case where collision geometry is a cylinder
186  // Use FCL capsules for cylinders
187  else if (urdf_geometry->type == ::urdf::Geometry::CYLINDER)
188  {
189  const bool is_capsule = tree.isCapsule(linkName, geomName);
190  meshScale << 1, 1, 1;
191  const ::urdf::CylinderSharedPtr collisionGeometry =
192  ::urdf::static_pointer_cast<::urdf::Cylinder>(urdf_geometry);
193 
194  double radius = collisionGeometry->radius;
195  double length = collisionGeometry->length;
196 
197  // Create fcl capsule geometry.
198  if (is_capsule)
199  {
200  meshPath = "CAPSULE";
201  geometry = std::shared_ptr<fcl::CollisionGeometry>(new fcl::Capsule(radius, length));
202  }
203  else
204  {
205  meshPath = "CYLINDER";
206  geometry = std::shared_ptr<fcl::CollisionGeometry>(new fcl::Cylinder(radius, length));
207  }
208  }
209  // Handle the case where collision geometry is a box.
210  else if (urdf_geometry->type == ::urdf::Geometry::BOX)
211  {
212  meshPath = "BOX";
213  meshScale << 1, 1, 1;
214  const ::urdf::BoxSharedPtr collisionGeometry =
215  ::urdf::static_pointer_cast<::urdf::Box>(urdf_geometry);
216 
217  double x = collisionGeometry->dim.x;
218  double y = collisionGeometry->dim.y;
219  double z = collisionGeometry->dim.z;
220 
221  geometry = std::shared_ptr<fcl::CollisionGeometry>(new fcl::Box(x, y, z));
222  }
223  // Handle the case where collision geometry is a sphere.
224  else if (urdf_geometry->type == ::urdf::Geometry::SPHERE)
225  {
226  meshPath = "SPHERE";
227  meshScale << 1, 1, 1;
228  const ::urdf::SphereSharedPtr collisionGeometry =
229  ::urdf::static_pointer_cast<::urdf::Sphere>(urdf_geometry);
230 
231  double radius = collisionGeometry->radius;
232 
233  geometry = std::shared_ptr<fcl::CollisionGeometry>(new fcl::Sphere(radius));
234  }
235  else
236  throw std::invalid_argument("Unknown geometry type :");
237 
238  if (!geometry)
239  {
240  throw std::invalid_argument("The polyhedron retrieved is empty");
241  }
242 
243  return geometry;
244  }
245 #endif // PINOCCHIO_WITH_HPP_FCL
246 
254  template<typename T>
255  inline PINOCCHIO_URDF_SHARED_PTR(const T)
256  getLinkGeometry(const ::urdf::LinkConstSharedPtr link);
257 
258  template<>
259  inline ::urdf::CollisionConstSharedPtr
260  getLinkGeometry<::urdf::Collision>(const ::urdf::LinkConstSharedPtr link)
261  {
262  return link->collision;
263  }
264 
265  template<>
266  inline ::urdf::VisualConstSharedPtr
267  getLinkGeometry<::urdf::Visual>(const ::urdf::LinkConstSharedPtr link)
268  {
269  return link->visual;
270  }
271 
282  template<typename urdfObject>
283  inline bool getVisualMaterial(
284  const PINOCCHIO_URDF_SHARED_PTR(urdfObject) urdf_object,
285  std::string & meshTexturePath,
286  Eigen::Vector4d & meshColor,
287  const std::vector<std::string> & package_dirs);
288 
289  template<>
290  inline bool getVisualMaterial<::urdf::Collision>(
291  const ::urdf::CollisionSharedPtr,
292  std::string & meshTexturePath,
293  Eigen::Vector4d & meshColor,
294  const std::vector<std::string> &)
295  {
296  meshColor << 0.9, 0.9, 0.9, 1.;
297  meshTexturePath = "";
298  return false;
299  }
300 
301  template<>
302  inline bool getVisualMaterial<::urdf::Visual>(
303  const ::urdf::VisualSharedPtr urdf_visual,
304  std::string & meshTexturePath,
305  Eigen::Vector4d & meshColor,
306  const std::vector<std::string> & package_dirs)
307  {
308  meshColor << 0.9, 0.9, 0.9, 1.;
309  meshTexturePath = "";
310  bool overrideMaterial = false;
311  if (urdf_visual->material)
312  {
313  overrideMaterial = true;
314  meshColor << urdf_visual->material->color.r, urdf_visual->material->color.g,
315  urdf_visual->material->color.b, urdf_visual->material->color.a;
316  if (urdf_visual->material->texture_filename != "")
317  meshTexturePath =
318  retrieveResourcePath((urdf_visual)->material->texture_filename, package_dirs);
319  }
320  return overrideMaterial;
321  }
322 
330  template<typename T>
331  inline const std::vector<PINOCCHIO_URDF_SHARED_PTR(T)> &
332  getLinkGeometryArray(const ::urdf::LinkConstSharedPtr link);
333 
334  template<>
335  inline const std::vector<::urdf::CollisionSharedPtr> &
336  getLinkGeometryArray<::urdf::Collision>(const ::urdf::LinkConstSharedPtr link)
337  {
338  return link->collision_array;
339  }
340 
341  template<>
342  inline const std::vector<::urdf::VisualSharedPtr> &
343  getLinkGeometryArray<::urdf::Visual>(const ::urdf::LinkConstSharedPtr link)
344  {
345  return link->visual_array;
346  }
347 
362  template<typename GeometryType>
364  const UrdfTree & tree,
365  ::hpp::fcl::MeshLoaderPtr & meshLoader,
366  ::urdf::LinkConstSharedPtr link,
367  UrdfGeomVisitorBase & visitor,
368  GeometryModel & geomModel,
369  const std::vector<std::string> & package_dirs)
370  {
371 #ifndef PINOCCHIO_WITH_HPP_FCL
373  PINOCCHIO_UNUSED_VARIABLE(meshLoader);
374 #endif // PINOCCHIO_WITH_HPP_FCL
375 
376  typedef std::vector<PINOCCHIO_URDF_SHARED_PTR(GeometryType)> VectorSharedT;
377  typedef GeometryModel::SE3 SE3;
378 
379  if (getLinkGeometry<GeometryType>(link))
380  {
381  std::string meshPath = "";
382 
383  Eigen::Vector3d meshScale(Eigen::Vector3d::Ones());
384 
385  const std::string & link_name = link->name;
386 
387  VectorSharedT geometries_array = getLinkGeometryArray<GeometryType>(link);
388 
390  UrdfGeomVisitorBase::Frame frame = visitor.getBodyFrame(link_name, frame_id);
391  const SE3 & body_placement = frame.placement.cast<SE3::Scalar>();
392 
393  std::size_t objectId = 0;
394  for (typename VectorSharedT::const_iterator i = geometries_array.begin();
395  i != geometries_array.end(); ++i)
396  {
397  meshPath.clear();
398 #ifdef PINOCCHIO_WITH_HPP_FCL
399 
400  #ifdef PINOCCHIO_URDFDOM_COLLISION_WITH_GROUP_NAME
401  const std::string & geom_name = (*i)->group_name;
402  #else
403  const std::string & geom_name = (*i)->name;
404  #endif // PINOCCHIO_URDFDOM_COLLISION_WITH_GROUP_NAME
406  tree, meshLoader, link_name, geom_name, (*i)->geometry, package_dirs, meshPath,
407  meshScale);
408 #else
409  ::urdf::MeshSharedPtr urdf_mesh =
410  ::urdf::dynamic_pointer_cast<::urdf::Mesh>((*i)->geometry);
411  if (urdf_mesh)
412  {
413  meshPath = retrieveResourcePath(urdf_mesh->filename, package_dirs);
414  retrieveMeshScale(urdf_mesh, meshScale);
415  }
416 
417  const std::shared_ptr<fcl::CollisionGeometry> geometry(new fcl::CollisionGeometry());
418 #endif // PINOCCHIO_WITH_HPP_FCL
419 
420  Eigen::Vector4d meshColor;
421  std::string meshTexturePath;
422  bool overrideMaterial =
423  getVisualMaterial<GeometryType>((*i), meshTexturePath, meshColor, package_dirs);
424 
425  const SE3 geomPlacement = body_placement * convertFromUrdf((*i)->origin);
426  std::ostringstream geometry_object_suffix;
427  geometry_object_suffix << "_" << objectId;
428  const std::string & geometry_object_name =
429  std::string(link_name + geometry_object_suffix.str());
430  GeometryObject geometry_object(
431  geometry_object_name, frame.parentJoint, frame_id, geomPlacement, geometry, meshPath,
432  meshScale, overrideMaterial, meshColor, meshTexturePath);
433  geomModel.addGeometryObject(geometry_object);
434  ++objectId;
435  }
436  }
437  }
438 
457  const UrdfTree & tree,
458  ::hpp::fcl::MeshLoaderPtr & meshLoader,
459  ::urdf::LinkConstSharedPtr link,
460  UrdfGeomVisitorBase & visitor,
461  GeometryModel & geomModel,
462  const std::vector<std::string> & package_dirs,
463  const GeometryType type)
464  {
465 
466  switch (type)
467  {
468  case COLLISION:
469  addLinkGeometryToGeomModel<::urdf::Collision>(
470  tree, meshLoader, link, visitor, geomModel, package_dirs);
471  break;
472  case VISUAL:
473  addLinkGeometryToGeomModel<::urdf::Visual>(
474  tree, meshLoader, link, visitor, geomModel, package_dirs);
475  break;
476  default:
477  break;
478  }
479 
480  BOOST_FOREACH (::urdf::LinkConstSharedPtr child, link->child_links)
481  {
483  tree, meshLoader, child, visitor, geomModel, package_dirs, type);
484  }
485  }
486 
488  UrdfGeomVisitorBase & visitor,
489  const std::istream & xmlStream,
490  const GeometryType type,
491  GeometryModel & geomModel,
492  const std::vector<std::string> & package_dirs,
493  ::hpp::fcl::MeshLoaderPtr meshLoader)
494  {
495  std::string xmlStr;
496  {
497  std::ostringstream os;
498  os << xmlStream.rdbuf();
499  xmlStr = os.str();
500  }
501 
502  details::UrdfTree tree;
503  tree.parse(xmlStr);
504 
505  std::vector<std::string> hint_directories(package_dirs);
506 
507  // Append the ROS_PACKAGE_PATH
508  std::vector<std::string> ros_pkg_paths = rosPaths();
509  hint_directories.insert(hint_directories.end(), ros_pkg_paths.begin(), ros_pkg_paths.end());
510 
511 #ifdef PINOCCHIO_WITH_HPP_FCL
512  if (!meshLoader)
513  meshLoader = fcl::MeshLoaderPtr(new fcl::MeshLoader);
514 #endif // ifdef PINOCCHIO_WITH_HPP_FCL
515 
517  tree, meshLoader, tree.urdf_->getRoot(), visitor, geomModel, hint_directories, type);
518  }
519  } // namespace details
521  } // namespace urdf
522 } // namespace pinocchio
meshcat-viewer.mesh
mesh
Definition: meshcat-viewer.py:54
pinocchio::urdf::details::getLinkGeometryArray
const std::vector< PINOCCHIO_URDF_SHARED_PTR(T)> & getLinkGeometryArray(const ::urdf::LinkConstSharedPtr link)
Get the array of geometries attached to a link.
simulation-contact-dynamics.T
int T
Definition: simulation-contact-dynamics.py:89
pinocchio::mjcf::details::retrieveCollisionGeometry
static std::shared_ptr< fcl::CollisionGeometry > retrieveCollisionGeometry(::hpp::fcl::MeshLoaderPtr &, const MjcfGeom &, const MjcfGraph &, std::string &, Eigen::Vector3d &)
Get a fcl::CollisionObject from an mjcf geometry, searching for it in specified package directories.
Definition: mjcf-graph-geom.cpp:128
pinocchio::FrameIndex
Index FrameIndex
Definition: multibody/fwd.hpp:28
common_symbols.type
type
Definition: common_symbols.py:35
pinocchio::urdf::details::UrdfTree::isCapsule
bool isCapsule(const std::string &linkName, const std::string &geomName) const
Definition: src/parsers/urdf/geometry.cpp:57
append-urdf-model-with-another-model.meshColor
meshColor
Definition: append-urdf-model-with-another-model.py:46
assimp.h
utils.hpp
pinocchio::rosPaths
PINOCCHIO_PARSERS_DLLAPI std::vector< std::string > rosPaths()
Parse the environment variables ROS_PACKAGE_PATH / AMENT_PREFIX_PATH and extract paths.
Definition: file-explorer.cpp:60
loader.h
meshcat-viewer.convex
convex
Definition: meshcat-viewer.py:56
y
y
types.hpp
PINOCCHIO_EIGEN_CONST_CAST
#define PINOCCHIO_EIGEN_CONST_CAST(TYPE, OBJ)
Macro for an automatic const_cast.
Definition: eigen-macros.hpp:51
pinocchio::python::context::Frame
FrameTpl< Scalar, Options > Frame
Definition: bindings/python/context/generic.hpp:62
pinocchio::urdf::details::addLinkGeometryToGeomModel
static void addLinkGeometryToGeomModel(const UrdfTree &tree, ::hpp::fcl::MeshLoaderPtr &meshLoader, ::urdf::LinkConstSharedPtr link, UrdfGeomVisitorBase &visitor, GeometryModel &geomModel, const std::vector< std::string > &package_dirs)
Add the geometries attached to a URDF link to a GeometryModel, looking either for collisions or visua...
Definition: src/parsers/urdf/geometry.cpp:363
pinocchio::SE3Tpl< Scalar, Options >
pinocchio::urdf::details::getVisualMaterial
bool getVisualMaterial(const PINOCCHIO_URDF_SHARED_PTR(urdfObject) urdf_object, std::string &meshTexturePath, Eigen::Vector4d &meshColor, const std::vector< std::string > &package_dirs)
Get the material values from the link visual object.
inverse-kinematics.i
int i
Definition: inverse-kinematics.py:17
pinocchio::name
std::string name(const LieGroupGenericTpl< LieGroupCollection > &lg)
Visit a LieGroupVariant to get the name of it.
collisionGeometry
const shared_ptr< CollisionGeometry > & collisionGeometry()
PINOCCHIO_URDF_SHARED_PTR
#define PINOCCHIO_URDF_SHARED_PTR(type)
Definition: types.hpp:18
pinocchio::urdf::details::UrdfTree::LinkMap_t
std::map< std::string, const ptree & > LinkMap_t
Definition: src/parsers/urdf/geometry.cpp:33
pinocchio::python::Scalar
context::Scalar Scalar
Definition: admm-solver.cpp:29
pinocchio::urdf::details::convertFromUrdf
SE3 convertFromUrdf(const ::urdf::Pose &M)
Convert URDF Pose quantity to SE3.
Definition: utils.cpp:10
pinocchio::GeometryObject
Definition: multibody/geometry-object.hpp:87
pinocchio::urdf::details::UrdfTree::parse
void parse(const std::string &xmlStr)
Definition: src/parsers/urdf/geometry.cpp:35
Sphere
Sphere()
pinocchio::urdf::details::retrieveMeshScale
static void retrieveMeshScale(const ::urdf::MeshSharedPtr &mesh, const Eigen::MatrixBase< Vector3 > &scale)
Definition: src/parsers/urdf/geometry.cpp:118
pinocchio::VISUAL
@ VISUAL
Definition: multibody/geometry-object.hpp:26
pinocchio::urdf::details::UrdfTree::tree_
ptree tree_
Definition: src/parsers/urdf/geometry.cpp:112
hpp::fcl::MeshLoaderPtr
std::shared_ptr< MeshLoader > MeshLoaderPtr
Definition: meshloader-fwd.hpp:25
details
collision-with-point-clouds.geometry
geometry
Definition: collision-with-point-clouds.py:83
append-urdf-model-with-another-model.package_dirs
package_dirs
Definition: append-urdf-model-with-another-model.py:20
pinocchio::fcl::FakeCollisionGeometry
Definition: multibody/fcl.hpp:63
pinocchio::urdf::details::UrdfTree::ptree
boost::property_tree::ptree ptree
Definition: src/parsers/urdf/geometry.cpp:32
urdf.hpp
x
x
pinocchio::urdf::details::UrdfTree::links_
LinkMap_t links_
Definition: src/parsers/urdf/geometry.cpp:114
pinocchio::context::Vector3
Eigen::Matrix< Scalar, 3, 1, Options > Vector3
Definition: context/generic.hpp:53
pinocchio::mjcf::details::ptree
boost::property_tree::ptree ptree
Definition: mjcf-graph.cpp:15
pinocchio::retrieveResourcePath
std::string retrieveResourcePath(const std::string &string, const std::vector< std::string > &package_dirs)
Retrieve the path of the file whose path is given in URL-format. Currently convert from the following...
Definition: utils.hpp:60
contact-cholesky.frame
frame
Definition: contact-cholesky.py:24
utils.hpp
contact-cholesky.frame_id
frame_id
Definition: contact-cholesky.py:19
value_type
Scalar value_type
Definition: eigen_plugin.hpp:2
Capsule
Capsule()
pinocchio::GeometryModel::addGeometryObject
GeomIndex addGeometryObject(const GeometryObject &object, const ModelTpl< S2, O2, _JointCollectionTpl > &model)
Add a geometry object to a GeometryModel and set its parent joint.
urdf
Definition: types.hpp:29
pinocchio::urdf::details::parseTreeForGeom
void parseTreeForGeom(UrdfGeomVisitorBase &visitor, const std::istream &xmlStream, const GeometryType type, GeometryModel &geomModel, const std::vector< std::string > &package_dirs, ::hpp::fcl::MeshLoaderPtr meshLoader)
Definition: src/parsers/urdf/geometry.cpp:487
Cylinder
Cylinder()
pinocchio::urdf::details::recursiveParseTreeForGeom
void recursiveParseTreeForGeom(const UrdfTree &tree, ::hpp::fcl::MeshLoaderPtr &meshLoader, ::urdf::LinkConstSharedPtr link, UrdfGeomVisitorBase &visitor, GeometryModel &geomModel, const std::vector< std::string > &package_dirs, const GeometryType type)
Recursive procedure for reading the URDF tree, looking for geometries This function fill the geometri...
Definition: src/parsers/urdf/geometry.cpp:456
pinocchio::GeometryType
GeometryType
Definition: multibody/geometry-object.hpp:24
pinocchio::GeometryModel
Definition: multibody/geometry.hpp:50
Box
Box()
pinocchio::COLLISION
@ COLLISION
Definition: multibody/geometry-object.hpp:27
append-urdf-model-with-another-model.body_placement
body_placement
Definition: append-urdf-model-with-another-model.py:39
pinocchio::GeometryObject::CollisionGeometryPtr
std::shared_ptr< fcl::CollisionGeometry > CollisionGeometryPtr
Definition: multibody/geometry-object.hpp:102
pinocchio::SE3
SE3Tpl< context::Scalar, context::Options > SE3
Definition: spatial/fwd.hpp:64
pinocchio::urdf::details::UrdfTree::urdf_
::urdf::ModelInterfaceSharedPtr urdf_
Definition: src/parsers/urdf/geometry.cpp:110
pinocchio::urdf::details::UrdfTree::isMeshConvex
bool isMeshConvex(const std::string &linkName, const std::string &geomName) const
Definition: src/parsers/urdf/geometry.cpp:83
length
FCL_REAL length[2]
meshcat-viewer.overrideMaterial
overrideMaterial
Definition: meshcat-viewer.py:65
hpp::fcl::BVHModelPtr_t
shared_ptr< BVHModelBase > BVHModelPtr_t
pinocchio::urdf::details::UrdfTree
Definition: src/parsers/urdf/geometry.cpp:30
radius
FCL_REAL radius
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27
PINOCCHIO_UNUSED_VARIABLE
#define PINOCCHIO_UNUSED_VARIABLE(var)
Helper to declare that a parameter is unused.
Definition: include/pinocchio/macros.hpp:72


pinocchio
Author(s):
autogenerated on Thu Dec 19 2024 03:41:29