src/parsers/sdf/geometry.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2021-2022 INRIA
3 //
4 
7 
8 #include <sstream>
9 #include <iomanip>
10 #include <boost/shared_ptr.hpp>
11 
12 #ifdef PINOCCHIO_WITH_HPP_FCL
15 #endif // PINOCCHIO_WITH_HPP_FCL
16 
17 namespace pinocchio
18 {
19  namespace sdf
20  {
21  namespace details
22  {
30  template<GeometryType type>
31  static bool hasLinkElement(const ::sdf::ElementPtr link);
32 
33  template<>
34  bool hasLinkElement<::pinocchio::COLLISION>(const ::sdf::ElementPtr link)
35  {
36  return link->HasElement("collision");
37  }
38 
39  template<>
40  bool hasLinkElement<::pinocchio::VISUAL>(const ::sdf::ElementPtr link)
41  {
42  return link->HasElement("visual");
43  }
44 
52  template<GeometryType type>
53  static const std::vector<::sdf::ElementPtr>
54  getLinkGeometryArray(const ::sdf::ElementPtr link);
55 
56  template<>
57  const std::vector<::sdf::ElementPtr>
58  getLinkGeometryArray<::pinocchio::COLLISION>(const ::sdf::ElementPtr link)
59  {
60  std::vector<::sdf::ElementPtr> geometry_array;
61  ::sdf::ElementPtr geomElement = link->GetElement("collision");
62  while (geomElement)
63  {
64  // Inserting data in std::map
65  if (geomElement->Get<std::string>("name") != "__default__")
66  {
67  geometry_array.push_back(geomElement);
68  }
69  geomElement = geomElement->GetNextElement("collision");
70  }
71  return geometry_array;
72  }
73 
74  template<>
75  const std::vector<::sdf::ElementPtr>
76  getLinkGeometryArray<::pinocchio::VISUAL>(const ::sdf::ElementPtr link)
77  {
78  std::vector<::sdf::ElementPtr> geometry_array;
79  ::sdf::ElementPtr geomElement = link->GetElement("visual");
80  while (geomElement)
81  {
82  // Inserting data in std::map
83  if (geomElement->Get<std::string>("name") != "__default__")
84  {
85  geometry_array.push_back(geomElement);
86  }
87  geomElement = geomElement->GetNextElement("visual");
88  }
89  return geometry_array;
90  }
91 
92  static Eigen::Vector3d retrieveMeshScale(const ::sdf::ElementPtr sdf_mesh)
93  {
94  const ignition::math::Vector3d ign_scale = sdf_mesh->Get<ignition::math::Vector3d>("scale");
95  return Eigen::Vector3d(ign_scale.X(), ign_scale.Y(), ign_scale.Z());
96  }
97 
98 #ifdef PINOCCHIO_WITH_HPP_FCL
99 
111  std::shared_ptr<fcl::CollisionGeometry> static retrieveCollisionGeometry(
112  ::hpp::fcl::MeshLoaderPtr & meshLoader,
113  const ::sdf::ElementPtr sdf_geometry,
114  const std::vector<std::string> & package_dirs,
115  std::string & meshPath,
116  Eigen::Vector3d & meshScale)
117  {
118  std::shared_ptr<fcl::CollisionGeometry> geometry;
119 
120  // Handle the case where collision geometry is a mesh
121  if (sdf_geometry->HasElement("mesh"))
122  {
123  const ::sdf::ElementPtr sdf_mesh = sdf_geometry->GetElement("mesh");
124  std::string collisionFilename = sdf_mesh->Get<std::string>("uri");
125 
126  meshPath = retrieveResourcePath(collisionFilename, package_dirs);
127  if (meshPath == "")
128  {
129  std::stringstream ss;
130  ss << "Mesh " << collisionFilename << " could not be found.";
131  throw std::invalid_argument(ss.str());
132  }
133 
134  Eigen::Vector3d scale(retrieveMeshScale(sdf_mesh));
135 
136  // Create FCL mesh by parsing Collada file.
137  hpp::fcl::BVHModelPtr_t bvh = meshLoader->load(meshPath, scale);
138  geometry = bvh;
139  }
140 
141  // Handle the case where collision geometry is a cylinder
142  // Use FCL capsules for cylinders
143  else if (sdf_geometry->HasElement("cylinder"))
144  {
145  meshScale << 1, 1, 1;
146  const ::sdf::ElementPtr collisionGeometry = sdf_geometry->GetElement("cylinder");
147 
148  double radius = collisionGeometry->Get<double>("radius");
149  double length = collisionGeometry->Get<double>("length");
150 
151  // Create fcl capsule geometry.
152  meshPath = "CYLINDER";
153  geometry = std::shared_ptr<fcl::CollisionGeometry>(new fcl::Cylinder(radius, length));
154  }
155  // Handle the case where collision geometry is a box.
156  else if (sdf_geometry->HasElement("box"))
157  {
158  meshPath = "BOX";
159  meshScale << 1, 1, 1;
160 
161  const ::sdf::ElementPtr collisionGeometry = sdf_geometry->GetElement("box");
162  double x = collisionGeometry->Get<double>("x");
163  double y = collisionGeometry->Get<double>("y");
164  double z = collisionGeometry->Get<double>("z");
165  geometry = std::shared_ptr<fcl::CollisionGeometry>(new fcl::Box(x, y, z));
166  }
167  // Handle the case where collision geometry is a sphere.
168  else if (sdf_geometry->HasElement("sphere"))
169  {
170  meshPath = "SPHERE";
171  meshScale << 1, 1, 1;
172  const ::sdf::ElementPtr collisionGeometry = sdf_geometry->GetElement("sphere");
173 
174  double radius = collisionGeometry->Get<double>("radius");
175  geometry = std::shared_ptr<fcl::CollisionGeometry>(new fcl::Sphere(radius));
176  }
177  else
178  throw std::invalid_argument("Unknown geometry type :");
179 
180  if (!geometry)
181  {
182  throw std::invalid_argument("The polyhedron retrived is empty");
183  }
184  return geometry;
185  }
186 #endif
187 
188  template<GeometryType type>
190  const SdfGraph & graph,
191  ::hpp::fcl::MeshLoaderPtr & meshLoader,
192  ::sdf::ElementPtr link,
193  GeometryModel & geomModel,
194  const std::vector<std::string> & package_dirs)
195  {
196 
197  typedef std::vector<::sdf::ElementPtr> GeometryArray;
198  typedef GeometryModel::SE3 SE3;
199 
200  if (hasLinkElement<type>(link))
201  {
202  std::string meshPath = "";
203 
204  Eigen::Vector3d meshScale(Eigen::Vector3d::Ones());
205  const std::string link_name = link->Get<std::string>("name");
206 
207  const GeometryArray geometries_array = getLinkGeometryArray<type>(link);
208 
209  FrameIndex frame_id = graph.urdfVisitor.getBodyId(link_name);
210  Frame frame = graph.urdfVisitor.getBodyFrame(link_name);
211 
212  SE3 body_placement = frame.placement;
213 
214  std::size_t objectId = 0;
215  for (typename GeometryArray::const_iterator i = geometries_array.begin();
216  i != geometries_array.end(); ++i)
217  {
218  meshPath.clear();
219  const ::sdf::ElementPtr sdf_geometry = (*i)->GetElement("geometry");
220 #ifdef PINOCCHIO_WITH_HPP_FCL
222  meshLoader, sdf_geometry, package_dirs, meshPath, meshScale);
223 #else
224  const ::sdf::ElementPtr sdf_mesh = sdf_geometry->GetElement("mesh");
225 
226  if (sdf_mesh)
227  {
228  std::string collisionFilename = sdf_mesh->Get<std::string>("url");
229  meshPath = retrieveResourcePath(collisionFilename, package_dirs);
230 
231  meshScale = retrieveMeshScale(sdf_mesh);
232  }
233 
234  const auto geometry = std::make_shared<fcl::CollisionGeometry>();
235 #endif // PINOCCHIO_WITH_HPP_FCL
236 
237  const ignition::math::Pose3d & pose =
238  (*i)->template Get<ignition::math::Pose3d>("pose");
239 
240  Eigen::Vector4d meshColor(Eigen::Vector4d::Zero());
241  std::string meshTexturePath;
242  bool overrideMaterial = false;
243  const ::sdf::ElementPtr sdf_material = (*i)->GetElement("material");
244  if (sdf_material)
245  {
246  const ignition::math::Color ign_meshColor =
247  sdf_material->Get<ignition::math::Color>("ambient");
248 
249  meshColor << ign_meshColor.R(), ign_meshColor.G(), ign_meshColor.B(),
250  ign_meshColor.A();
251  overrideMaterial = true;
252  }
253 
254  const SE3 lMg = convertFromPose3d(pose);
255  const SE3 geomPlacement = body_placement * lMg;
256  std::ostringstream geometry_object_suffix;
257  geometry_object_suffix << "_" << objectId;
258  const std::string & geometry_object_name =
259  std::string(link_name + geometry_object_suffix.str());
260  GeometryObject geometry_object(
261  geometry_object_name, frame.parentJoint, frame_id, geomPlacement, geometry, meshPath,
262  meshScale, overrideMaterial, meshColor, meshTexturePath);
263  geomModel.addGeometryObject(geometry_object);
264  ++objectId;
265  }
266  }
267  }
268 
270  const SdfGraph & graph,
271  ::hpp::fcl::MeshLoaderPtr & meshLoader,
272  const ::sdf::ElementPtr link,
273  GeometryModel & geomModel,
274  const std::vector<std::string> & package_dirs,
275  const GeometryType type)
276  {
277  switch (type)
278  {
279  case COLLISION:
280  addLinkGeometryToGeomModel<::pinocchio::COLLISION>(
281  graph, meshLoader, link, geomModel, package_dirs);
282  break;
283  case VISUAL:
284  addLinkGeometryToGeomModel<::pinocchio::VISUAL>(
285  graph, meshLoader, link, geomModel, package_dirs);
286  break;
287  default:
288  break;
289  }
290  }
291 
293  const Model & model,
294  const SdfGraph & graph,
295  GeometryModel & geomModel,
296  const std::string & rootLinkName,
297  const GeometryType type,
298  const std::vector<std::string> & package_dirs,
299  ::hpp::fcl::MeshLoaderPtr meshLoader)
300  {
301  std::vector<std::string> hint_directories(package_dirs);
302  std::vector<std::string> ros_pkg_paths = rosPaths();
303  hint_directories.insert(hint_directories.end(), ros_pkg_paths.begin(), ros_pkg_paths.end());
304 
305 #ifdef PINOCCHIO_WITH_HPP_FCL
306  if (!meshLoader)
307  meshLoader = fcl::MeshLoaderPtr(new fcl::MeshLoader);
308 #endif // ifdef PINOCCHIO_WITH_HPP_FCL
309 
310  const ::sdf::ElementPtr rootElement = graph.mapOfLinks.find(rootLinkName)->second;
311 
313  graph, meshLoader, rootElement, geomModel, hint_directories, type);
314 
315  for (pinocchio::Model::FrameVector::const_iterator fm = std::begin(model.frames);
316  fm != std::end(model.frames); ++fm)
317  {
318  if (
319  (fm->type != FIXED_JOINT && fm->type != JOINT)
320  || (graph.mapOfJoints.find(fm->name) == graph.mapOfJoints.end()))
321  {
322  continue;
323  }
324  const ::sdf::ElementPtr childJointElement = graph.mapOfJoints.find(fm->name)->second;
325  const std::string childLinkName =
326  childJointElement->GetElement("child")->template Get<std::string>();
327  const ::sdf::ElementPtr childLinkElement = graph.mapOfLinks.find(childLinkName)->second;
328 
330  graph, meshLoader, childLinkElement, geomModel, hint_directories, type);
331  }
332  }
333  } // namespace details
334  } // namespace sdf
335 } // namespace pinocchio
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
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
y
y
pinocchio::SE3Tpl< Scalar, Options >
inverse-kinematics.i
int i
Definition: inverse-kinematics.py:17
collisionGeometry
const shared_ptr< CollisionGeometry > & collisionGeometry()
pinocchio::GeometryObject
Definition: multibody/geometry-object.hpp:87
pinocchio::sdf::details::hasLinkElement
static bool hasLinkElement(const ::sdf::ElementPtr link)
Get the first geometry attached to a link.
Sphere
Sphere()
pinocchio::FrameTpl
A Plucker coordinate frame attached to a parent joint inside a kinematic tree.
Definition: multibody/frame.hpp:55
pinocchio::VISUAL
@ VISUAL
Definition: multibody/geometry-object.hpp:26
hpp::fcl::MeshLoaderPtr
std::shared_ptr< MeshLoader > MeshLoaderPtr
Definition: meshloader-fwd.hpp:25
details
sdf.hpp
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
x
x
pinocchio::sdf::details::addLinkGeometryToGeomModel
static void addLinkGeometryToGeomModel(const SdfGraph &graph, ::hpp::fcl::MeshLoaderPtr &meshLoader, ::sdf::ElementPtr link, GeometryModel &geomModel, const std::vector< std::string > &package_dirs)
Definition: src/parsers/sdf/geometry.cpp:189
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
pinocchio::JOINT
@ JOINT
joint frame: attached to the child body of a joint (a.k.a. child frame)
Definition: multibody/frame.hpp:34
contact-cholesky.frame_id
frame_id
Definition: contact-cholesky.py:19
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.
Cylinder
Cylinder()
pinocchio::FIXED_JOINT
@ FIXED_JOINT
fixed joint frame: joint frame but for a fixed joint
Definition: multibody/frame.hpp:35
graph
Definition: graph.py:1
pinocchio::GeometryType
GeometryType
Definition: multibody/geometry-object.hpp:24
pinocchio::GeometryModel
Definition: multibody/geometry.hpp:50
Box
Box()
pinocchio::sdf::details::getLinkGeometryArray
static const std::vector<::sdf::ElementPtr > getLinkGeometryArray(const ::sdf::ElementPtr link)
Get the array of geometries attached to a link.
pinocchio::COLLISION
@ COLLISION
Definition: multibody/geometry-object.hpp:27
pinocchio::sdf::details::retrieveMeshScale
static Eigen::Vector3d retrieveMeshScale(const ::sdf::ElementPtr sdf_mesh)
Definition: src/parsers/sdf/geometry.cpp:92
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::ModelTpl
Definition: context/generic.hpp:20
length
FCL_REAL length[2]
meshcat-viewer.overrideMaterial
overrideMaterial
Definition: meshcat-viewer.py:65
hpp::fcl::BVHModelPtr_t
shared_ptr< BVHModelBase > BVHModelPtr_t
pinocchio::sdf::details::parseTreeForGeom
void parseTreeForGeom(const Model &model, const SdfGraph &graph, GeometryModel &geomModel, const std::string &rootLinkName, const GeometryType type, const std::vector< std::string > &package_dirs, ::hpp::fcl::MeshLoaderPtr meshLoader)
Definition: src/parsers/sdf/geometry.cpp:292
radius
FCL_REAL radius
pinocchio::model
JointCollectionTpl & model
Definition: joint-configuration.hpp:1082
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27


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