10 #include <boost/shared_ptr.hpp> 
   12 #ifdef PINOCCHIO_WITH_HPP_FCL 
   15 #endif // PINOCCHIO_WITH_HPP_FCL 
   30       template<GeometryType type>
 
   34       bool hasLinkElement<::pinocchio::COLLISION>(const ::sdf::ElementPtr link)
 
   36         return link->HasElement(
"collision");
 
   40       bool hasLinkElement<::pinocchio::VISUAL>(const ::sdf::ElementPtr link)
 
   42         return link->HasElement(
"visual");
 
   52       template<GeometryType type>
 
   53       static const std::vector<::sdf::ElementPtr>
 
   57       const std::vector<::sdf::ElementPtr>
 
   58       getLinkGeometryArray<::pinocchio::COLLISION>(const ::sdf::ElementPtr link)
 
   60         std::vector<::sdf::ElementPtr> geometry_array;
 
   61         ::sdf::ElementPtr geomElement = link->GetElement(
"collision");
 
   65           if (geomElement->Get<std::string>(
"name") != 
"__default__")
 
   67             geometry_array.push_back(geomElement);
 
   69           geomElement = geomElement->GetNextElement(
"collision");
 
   71         return geometry_array;
 
   75       const std::vector<::sdf::ElementPtr>
 
   76       getLinkGeometryArray<::pinocchio::VISUAL>(const ::sdf::ElementPtr link)
 
   78         std::vector<::sdf::ElementPtr> geometry_array;
 
   79         ::sdf::ElementPtr geomElement = link->GetElement(
"visual");
 
   83           if (geomElement->Get<std::string>(
"name") != 
"__default__")
 
   85             geometry_array.push_back(geomElement);
 
   87           geomElement = geomElement->GetNextElement(
"visual");
 
   89         return geometry_array;
 
   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());
 
   98 #ifdef PINOCCHIO_WITH_HPP_FCL 
  113         const ::sdf::ElementPtr sdf_geometry,
 
  115         std::string & meshPath,
 
  116         Eigen::Vector3d & meshScale)
 
  118         std::shared_ptr<fcl::CollisionGeometry> 
geometry;
 
  121         if (sdf_geometry->HasElement(
"mesh"))
 
  123           const ::sdf::ElementPtr sdf_mesh = sdf_geometry->GetElement(
"mesh");
 
  124           std::string collisionFilename = sdf_mesh->Get<std::string>(
"uri");
 
  129             std::stringstream ss;
 
  130             ss << 
"Mesh " << collisionFilename << 
" could not be found.";
 
  131             throw std::invalid_argument(ss.str());
 
  143         else if (sdf_geometry->HasElement(
"cylinder"))
 
  145           meshScale << 1, 1, 1;
 
  146           const ::sdf::ElementPtr 
collisionGeometry = sdf_geometry->GetElement(
"cylinder");
 
  152           meshPath = 
"CYLINDER";
 
  156         else if (sdf_geometry->HasElement(
"box"))
 
  159           meshScale << 1, 1, 1;
 
  168         else if (sdf_geometry->HasElement(
"sphere"))
 
  171           meshScale << 1, 1, 1;
 
  178           throw std::invalid_argument(
"Unknown geometry type :");
 
  182           throw std::invalid_argument(
"The polyhedron retrived is empty");
 
  188       template<GeometryType type>
 
  190         const SdfGraph & 
graph,
 
  192         ::sdf::ElementPtr link,
 
  197         typedef std::vector<::sdf::ElementPtr> GeometryArray;
 
  200         if (hasLinkElement<type>(link))
 
  202           std::string meshPath = 
"";
 
  204           Eigen::Vector3d meshScale(Eigen::Vector3d::Ones());
 
  205           const std::string link_name = link->Get<std::string>(
"name");
 
  207           const GeometryArray geometries_array = getLinkGeometryArray<type>(link);
 
  214           std::size_t objectId = 0;
 
  215           for (
typename GeometryArray::const_iterator 
i = geometries_array.begin();
 
  216                i != geometries_array.end(); ++
i)
 
  219             const ::sdf::ElementPtr sdf_geometry = (*i)->GetElement(
"geometry");
 
  220 #ifdef PINOCCHIO_WITH_HPP_FCL 
  222               meshLoader, sdf_geometry, 
package_dirs, meshPath, meshScale);
 
  224             const ::sdf::ElementPtr sdf_mesh = sdf_geometry->GetElement(
"mesh");
 
  228               std::string collisionFilename = sdf_mesh->Get<std::string>(
"url");
 
  234             const auto geometry = std::make_shared<fcl::CollisionGeometry>();
 
  235 #endif // PINOCCHIO_WITH_HPP_FCL 
  237             const ignition::math::Pose3d & pose =
 
  238               (*i)->template Get<ignition::math::Pose3d>(
"pose");
 
  240             Eigen::Vector4d 
meshColor(Eigen::Vector4d::Zero());
 
  241             std::string meshTexturePath;
 
  243             const ::sdf::ElementPtr sdf_material = (*i)->GetElement(
"material");
 
  246               const ignition::math::Color ign_meshColor =
 
  247                 sdf_material->Get<ignition::math::Color>(
"ambient");
 
  249               meshColor << ign_meshColor.R(), ign_meshColor.G(), ign_meshColor.B(),
 
  254             const SE3 lMg = convertFromPose3d(pose);
 
  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());
 
  270         const SdfGraph & 
graph,
 
  272         const ::sdf::ElementPtr link,
 
  280           addLinkGeometryToGeomModel<::pinocchio::COLLISION>(
 
  284           addLinkGeometryToGeomModel<::pinocchio::VISUAL>(
 
  294         const SdfGraph & 
graph,
 
  296         const std::string & rootLinkName,
 
  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());
 
  305 #ifdef PINOCCHIO_WITH_HPP_FCL 
  308 #endif // ifdef PINOCCHIO_WITH_HPP_FCL 
  310         const ::sdf::ElementPtr rootElement = 
graph.mapOfLinks.find(rootLinkName)->second;
 
  313           graph, meshLoader, rootElement, geomModel, hint_directories, 
type);
 
  315         for (pinocchio::Model::FrameVector::const_iterator fm = std::begin(
model.frames);
 
  316              fm != std::end(
model.frames); ++fm)
 
  320             || (
graph.mapOfJoints.find(fm->name) == 
graph.mapOfJoints.end()))
 
  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;
 
  330             graph, meshLoader, childLinkElement, geomModel, hint_directories, 
type);