#include <urdf_model/model.h>
#include <urdf_parser/urdf_parser.h>
#include <iostream>
#include <boost/foreach.hpp>
#include "pinocchio/multibody/model.hpp"
#include <hpp/fcl/collision_object.h>
#include <hpp/fcl/collision.h>
#include <hpp/fcl/shape/geometric_shapes.h>
#include "pinocchio/multibody/parser/from-collada-to-fcl.hpp"
#include <exception>
Namespaces |
namespace | se3 |
namespace | se3::urdf |
Functions |
fcl::CollisionObject | se3::urdf::retrieveCollisionGeometry (const ::urdf::LinkConstPtr &link, const std::string &meshRootDir) |
| Get a CollisionObject from an urdf link, reading the corresponding mesh.
|
void | se3::urdf::parseTreeForGeom (::urdf::LinkConstPtr link, Model &model, GeometryModel &model_geom, const std::string &meshRootDir, const bool rootJointAdded) throw (std::invalid_argument) |
| Recursive procedure for reading the URDF tree, looking for geometries This function fill the geometric model whith geometry objects retrieved from the URDF tree.
|
template<typename D > |
std::pair< Model, GeometryModel > | se3::urdf::buildModelAndGeom (const std::string &filename, const std::string &meshRootDir, const JointModelBase< D > &root_joint) |
| Build The Model and GeometryModel from a URDF file with a particular joint as root of the model tree.
|
std::pair< Model, GeometryModel > | se3::urdf::buildModelAndGeom (const std::string &filename, const std::string &meshRootDir) |
| Build The Model and GeometryModel from a URDF file with no root joint added to the model tree.
|