10 #include <boost/property_tree/xml_parser.hpp> 
   11 #include <boost/property_tree/ptree.hpp> 
   13 #include <urdf_model/model.h> 
   14 #include <urdf_parser/urdf_parser.h> 
   16 #ifdef PINOCCHIO_WITH_HPP_FCL 
   21 #endif // PINOCCHIO_WITH_HPP_FCL 
   33         typedef std::map<std::string, const ptree &> 
LinkMap_t;
 
   35         void parse(
const std::string & xmlStr)
 
   37           urdf_ = ::urdf::parseURDF(xmlStr);
 
   40             throw std::invalid_argument(
"Unable to parse URDF");
 
   43           std::istringstream iss(xmlStr);
 
   44           using namespace boost::property_tree;
 
   45           read_xml(iss, 
tree_, xml_parser::no_comments);
 
   49             if (link.first == 
"link")
 
   51               std::string 
name = link.second.get<std::string>(
"<xmlattr>.name");
 
   52               links_.insert(std::pair<std::string, const ptree &>(
name, link.second));
 
   57         bool isCapsule(
const std::string & linkName, 
const std::string & geomName)
 const 
   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)
 
   64           BOOST_FOREACH (
const ptree::value_type & cc, link.get_child(
"collision_checking"))
 
   66             if (cc.first == 
"capsule")
 
   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" 
   73               std::string 
name = cc.second.get<std::string>(
"<xmlattr>.name");
 
   83         bool isMeshConvex(
const std::string & linkName, 
const std::string & geomName)
 const 
   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)
 
   90           BOOST_FOREACH (
const ptree::value_type & cc, link.get_child(
"collision_checking"))
 
   92             if (cc.first == 
"convex")
 
   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" 
   99               std::string 
name = cc.second.get<std::string>(
"<xmlattr>.name");
 
  100               if (geomName == 
name)
 
  110         ::urdf::ModelInterfaceSharedPtr 
urdf_;
 
  117       template<
typename Vector3>
 
  119         const ::urdf::MeshSharedPtr & 
mesh, 
const Eigen::MatrixBase<Vector3> & scale)
 
  125 #ifdef PINOCCHIO_WITH_HPP_FCL 
  139         const UrdfTree & tree,
 
  141         const std::string & linkName,
 
  142         const std::string & geomName,
 
  143         const ::urdf::GeometrySharedPtr urdf_geometry,
 
  145         std::string & meshPath,
 
  146         Eigen::Vector3d & meshScale)
 
  148         std::shared_ptr<fcl::CollisionGeometry> 
geometry;
 
  151         if (urdf_geometry->type == ::urdf::Geometry::MESH)
 
  153           const ::urdf::MeshSharedPtr urdf_mesh =
 
  154             ::urdf::static_pointer_cast<::urdf::Mesh>(urdf_geometry);
 
  155           std::string collisionFilename = urdf_mesh->filename;
 
  160             std::stringstream ss;
 
  161             ss << 
"Mesh " << collisionFilename << 
" could not be found.";
 
  162             throw std::invalid_argument(ss.str());
 
  165           fcl::Vec3f scale = fcl::Vec3f(urdf_mesh->scale.x, urdf_mesh->scale.y, urdf_mesh->scale.z);
 
  171           bool convex = tree.isMeshConvex(linkName, geomName);
 
  174             bvh->buildConvexRepresentation(
false);
 
  175             geometry = std::shared_ptr<fcl::CollisionGeometry>(
 
  176               bvh->convex.get(), [bvh](...) 
mutable { bvh->convex.reset(); });
 
  180             geometry = std::shared_ptr<fcl::CollisionGeometry>(
 
  181               bvh.get(), [bvh](...) 
mutable { bvh.reset(); });
 
  187         else if (urdf_geometry->type == ::urdf::Geometry::CYLINDER)
 
  189           const bool is_capsule = tree.isCapsule(linkName, geomName);
 
  190           meshScale << 1, 1, 1;
 
  192             ::urdf::static_pointer_cast<::urdf::Cylinder>(urdf_geometry);
 
  200             meshPath = 
"CAPSULE";
 
  205             meshPath = 
"CYLINDER";
 
  210         else if (urdf_geometry->type == ::urdf::Geometry::BOX)
 
  213           meshScale << 1, 1, 1;
 
  215             ::urdf::static_pointer_cast<::urdf::Box>(urdf_geometry);
 
  224         else if (urdf_geometry->type == ::urdf::Geometry::SPHERE)
 
  227           meshScale << 1, 1, 1;
 
  229             ::urdf::static_pointer_cast<::urdf::Sphere>(urdf_geometry);
 
  236           throw std::invalid_argument(
"Unknown geometry type :");
 
  240           throw std::invalid_argument(
"The polyhedron retrieved is empty");
 
  245 #endif // PINOCCHIO_WITH_HPP_FCL 
  256         getLinkGeometry(const ::urdf::LinkConstSharedPtr link);
 
  259       inline ::urdf::CollisionConstSharedPtr
 
  260       getLinkGeometry<::urdf::Collision>(const ::urdf::LinkConstSharedPtr link)
 
  262         return link->collision;
 
  266       inline ::urdf::VisualConstSharedPtr
 
  267       getLinkGeometry<::urdf::Visual>(const ::urdf::LinkConstSharedPtr link)
 
  282       template<
typename urdfObject>
 
  285         std::string & meshTexturePath,
 
  290       inline bool getVisualMaterial<::urdf::Collision>(
 
  291         const ::urdf::CollisionSharedPtr,
 
  292         std::string & meshTexturePath,
 
  294         const std::vector<std::string> &)
 
  297         meshTexturePath = 
"";
 
  302       inline bool getVisualMaterial<::urdf::Visual>(
 
  303         const ::urdf::VisualSharedPtr urdf_visual,
 
  304         std::string & meshTexturePath,
 
  309         meshTexturePath = 
"";
 
  311         if (urdf_visual->material)
 
  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 != 
"")
 
  335       inline const std::vector<::urdf::CollisionSharedPtr> &
 
  336       getLinkGeometryArray<::urdf::Collision>(const ::urdf::LinkConstSharedPtr link)
 
  338         return link->collision_array;
 
  342       inline const std::vector<::urdf::VisualSharedPtr> &
 
  343       getLinkGeometryArray<::urdf::Visual>(const ::urdf::LinkConstSharedPtr link)
 
  345         return link->visual_array;
 
  362       template<
typename GeometryType>
 
  366         ::urdf::LinkConstSharedPtr link,
 
  367         UrdfGeomVisitorBase & visitor,
 
  371 #ifndef PINOCCHIO_WITH_HPP_FCL 
  374 #endif // PINOCCHIO_WITH_HPP_FCL 
  379         if (getLinkGeometry<GeometryType>(link))
 
  381           std::string meshPath = 
"";
 
  383           Eigen::Vector3d meshScale(Eigen::Vector3d::Ones());
 
  385           const std::string & link_name = link->name;
 
  387           VectorSharedT geometries_array = getLinkGeometryArray<GeometryType>(link);
 
  393           std::size_t objectId = 0;
 
  394           for (
typename VectorSharedT::const_iterator 
i = geometries_array.begin();
 
  395                i != geometries_array.end(); ++
i)
 
  398 #ifdef PINOCCHIO_WITH_HPP_FCL 
  400   #ifdef PINOCCHIO_URDFDOM_COLLISION_WITH_GROUP_NAME 
  401             const std::string & geom_name = (*i)->group_name;
 
  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,
 
  409             ::urdf::MeshSharedPtr urdf_mesh =
 
  410               ::urdf::dynamic_pointer_cast<::urdf::Mesh>((*i)->geometry);
 
  418 #endif // PINOCCHIO_WITH_HPP_FCL 
  421             std::string meshTexturePath;
 
  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());
 
  459         ::urdf::LinkConstSharedPtr link,
 
  460         UrdfGeomVisitorBase & visitor,
 
  469           addLinkGeometryToGeomModel<::urdf::Collision>(
 
  470             tree, meshLoader, link, visitor, geomModel, 
package_dirs);
 
  473           addLinkGeometryToGeomModel<::urdf::Visual>(
 
  474             tree, meshLoader, link, visitor, geomModel, 
package_dirs);
 
  480         BOOST_FOREACH (::urdf::LinkConstSharedPtr child, link->child_links)
 
  488         UrdfGeomVisitorBase & visitor,
 
  489         const std::istream & xmlStream,
 
  497           std::ostringstream os;
 
  498           os << xmlStream.rdbuf();
 
  505         std::vector<std::string> hint_directories(
package_dirs);
 
  508         std::vector<std::string> ros_pkg_paths = 
rosPaths();
 
  509         hint_directories.insert(hint_directories.end(), ros_pkg_paths.begin(), ros_pkg_paths.end());
 
  511 #ifdef PINOCCHIO_WITH_HPP_FCL 
  514 #endif // ifdef PINOCCHIO_WITH_HPP_FCL 
  517           tree, meshLoader, tree.
urdf_->getRoot(), visitor, geomModel, hint_directories, 
type);