Namespaces | Functions
pinocchio::urdf Namespace Reference

URDF parsing. More...

Namespaces

 details
 

Functions

template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl>
GeometryModelbuildGeom (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const std::string &filename, const GeometryType type, GeometryModel &geom_model, const std::vector< std::string > &package_paths=std::vector< std::string >(), ::hpp::fcl::MeshLoaderPtr mesh_loader=::hpp::fcl::MeshLoaderPtr())
 Build The GeometryModel from a URDF file. Search for meshes in the directories specified by the user first and then in the environment variable ROS_PACKAGE_PATH. More...
 
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl>
GeometryModelbuildGeom (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const std::string &filename, const GeometryType type, GeometryModel &geom_model, const std::string &package_path, hpp::fcl::MeshLoaderPtr mesh_loader=hpp::fcl::MeshLoaderPtr())
 Build The GeometryModel from a URDF file. Search for meshes in the directories specified by the user first and then in the environment variable ROS_PACKAGE_PATH. More...
 
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl>
GeometryModelbuildGeom (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const std::istream &xml_stream, const GeometryType type, GeometryModel &geom_model, const std::vector< std::string > &package_paths=std::vector< std::string >(), hpp::fcl::MeshLoaderPtr mesh_loader=hpp::fcl::MeshLoaderPtr())
 Build The GeometryModel from a URDF model. Search for meshes in the directories specified by the user first and then in the environment variable ROS_PACKAGE_PATH. More...
 
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl>
GeometryModelbuildGeom (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const std::istream &xml_stream, const GeometryType type, GeometryModel &geom_model, const std::string &package_path, hpp::fcl::MeshLoaderPtr mesh_loader=hpp::fcl::MeshLoaderPtr())
 Build The GeometryModel from a URDF model. Search for meshes in the directories specified by the user first and then in the environment variable ROS_PACKAGE_PATH. More...
 
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl>
ModelTpl< Scalar, Options, JointCollectionTpl > & buildModel (const std::string &filename, const typename ModelTpl< Scalar, Options, JointCollectionTpl >::JointModel &rootJoint, ModelTpl< Scalar, Options, JointCollectionTpl > &model, const bool verbose=false)
 Build the model from a URDF file with a particular joint as root of the model tree inside the model given as reference argument. More...
 
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl>
ModelTpl< Scalar, Options, JointCollectionTpl > & buildModel (const std::string &filename, ModelTpl< Scalar, Options, JointCollectionTpl > &model, const bool verbose=false)
 Build the model from a URDF file with a fixed joint as root of the model tree. More...
 
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl>
ModelTpl< Scalar, Options, JointCollectionTpl > & buildModel (const boost::shared_ptr< ::urdf::ModelInterface > urdfTree, const typename ModelTpl< Scalar, Options, JointCollectionTpl >::JointModel &rootJoint, ModelTpl< Scalar, Options, JointCollectionTpl > &model, const bool verbose=false)
 Build the model from a URDF model with a particular joint as root of the model tree inside the model given as reference argument. More...
 
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl>
ModelTpl< Scalar, Options, JointCollectionTpl > & buildModel (const boost::shared_ptr< ::urdf::ModelInterface > urdfTree, ModelTpl< Scalar, Options, JointCollectionTpl > &model, const bool verbose=false)
 Build the model from a URDF model. More...
 
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl>
ModelTpl< Scalar, Options, JointCollectionTpl > & buildModelFromXML (const std::string &xml_stream, const typename ModelTpl< Scalar, Options, JointCollectionTpl >::JointModel &rootJoint, ModelTpl< Scalar, Options, JointCollectionTpl > &model, const bool verbose=false)
 Build the model from an XML stream with a particular joint as root of the model tree inside the model given as reference argument. More...
 
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl>
ModelTpl< Scalar, Options, JointCollectionTpl > & buildModelFromXML (const std::string &xml_stream, ModelTpl< Scalar, Options, JointCollectionTpl > &model, const bool verbose=false)
 Build the model from an XML stream. More...
 

Detailed Description

URDF parsing.

Function Documentation

◆ buildGeom() [1/4]

template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl>
GeometryModel& pinocchio::urdf::buildGeom ( const ModelTpl< Scalar, Options, JointCollectionTpl > &  model,
const std::string &  filename,
const GeometryType  type,
GeometryModel geom_model,
const std::vector< std::string > &  package_paths = std::vector< std::string >(),
::hpp::fcl::MeshLoaderPtr  mesh_loader = ::hpp::fcl::MeshLoaderPtr() 
)

Build The GeometryModel from a URDF file. Search for meshes in the directories specified by the user first and then in the environment variable ROS_PACKAGE_PATH.

Parameters
[in]modelThe model of the robot, built with urdf::buildModel
[in]filenameThe URDF complete (absolute) file path
[in]package_pathsA vector containing the different directories where to search for models and meshes, typically obtained from calling pinocchio::rosPaths()
[in]typeThe type of objects that must be loaded (must be VISUAL or COLLISION)
[in]mesh_loaderobject used to load meshes: hpp::fcl::MeshLoader [default] or hpp::fcl::CachedMeshLoader.
[out]geom_modelReference where to put the parsed information.
Returns
Returns the reference on geom model for convenience.
Warning
If hpp-fcl has not been found during compilation, COLLISION objects can not be loaded

◆ buildGeom() [2/4]

template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl>
GeometryModel& pinocchio::urdf::buildGeom ( const ModelTpl< Scalar, Options, JointCollectionTpl > &  model,
const std::string &  filename,
const GeometryType  type,
GeometryModel geom_model,
const std::string &  package_path,
hpp::fcl::MeshLoaderPtr  mesh_loader = hpp::fcl::MeshLoaderPtr() 
)

Build The GeometryModel from a URDF file. Search for meshes in the directories specified by the user first and then in the environment variable ROS_PACKAGE_PATH.

Parameters
[in]modelThe model of the robot, built with urdf::buildModel
[in]filenameThe URDF complete (absolute) file path
[in]package_pathA string containing the path to the directories of the meshes, typically obtained from calling pinocchio::rosPaths().
[in]typeThe type of objects that must be loaded (must be VISUAL or COLLISION)
[in]mesh_loaderobject used to load meshes: hpp::fcl::MeshLoader [default] or hpp::fcl::CachedMeshLoader.
[out]geom_modelReference where to put the parsed information.
Returns
Returns the reference on geom model for convenience.
Warning
If hpp-fcl has not been found during compilation, COLLISION objects can not be loaded

Definition at line 211 of file src/parsers/urdf.hpp.

◆ buildGeom() [3/4]

template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl>
GeometryModel& pinocchio::urdf::buildGeom ( const ModelTpl< Scalar, Options, JointCollectionTpl > &  model,
const std::istream &  xml_stream,
const GeometryType  type,
GeometryModel geom_model,
const std::vector< std::string > &  package_paths = std::vector< std::string >(),
hpp::fcl::MeshLoaderPtr  mesh_loader = hpp::fcl::MeshLoaderPtr() 
)

Build The GeometryModel from a URDF model. Search for meshes in the directories specified by the user first and then in the environment variable ROS_PACKAGE_PATH.

Parameters
[in]modelThe model of the robot, built with urdf::buildModel
[in]xml_streamStream containing the URDF model
[in]package_pathsA vector containing the different directories where to search for models and meshes, typically obtained from calling pinocchio::rosPaths()
[in]typeThe type of objects that must be loaded (must be VISUAL or COLLISION)
[in]mesh_loaderobject used to load meshes: hpp::fcl::MeshLoader [default] or hpp::fcl::CachedMeshLoader.
[out]geom_modelReference where to put the parsed information.
Returns
Returns the reference on geom model for convenience.
Warning
If hpp-fcl has not been found during compilation, COLLISION objects cannot be loaded

◆ buildGeom() [4/4]

template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl>
GeometryModel& pinocchio::urdf::buildGeom ( const ModelTpl< Scalar, Options, JointCollectionTpl > &  model,
const std::istream &  xml_stream,
const GeometryType  type,
GeometryModel geom_model,
const std::string &  package_path,
hpp::fcl::MeshLoaderPtr  mesh_loader = hpp::fcl::MeshLoaderPtr() 
)

Build The GeometryModel from a URDF model. Search for meshes in the directories specified by the user first and then in the environment variable ROS_PACKAGE_PATH.

Parameters
[in]modelThe model of the robot, built with urdf::buildModel
[in]xml_streamStream containing the URDF model
[in]package_pathA string containing the path to the directories of the meshes, typically obtained from calling pinocchio::rosPaths().
[in]typeThe type of objects that must be loaded (must be VISUAL or COLLISION)
[in]mesh_loaderobject used to load meshes: hpp::fcl::MeshLoader [default] or hpp::fcl::CachedMeshLoader.
[out]geom_modelReference where to put the parsed information.
Returns
Returns the reference on geom model for convenience.
Warning
If hpp-fcl has not been found during compilation, COLLISION objects cannot be loaded

Definition at line 273 of file src/parsers/urdf.hpp.

◆ buildModel() [1/4]

template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl>
ModelTpl<Scalar,Options,JointCollectionTpl>& pinocchio::urdf::buildModel ( const std::string &  filename,
const typename ModelTpl< Scalar, Options, JointCollectionTpl >::JointModel rootJoint,
ModelTpl< Scalar, Options, JointCollectionTpl > &  model,
const bool  verbose = false 
)

Build the model from a URDF file with a particular joint as root of the model tree inside the model given as reference argument.

Parameters
[in]filenameThe URDF complete file path.
[in]rootJointThe joint at the root of the model tree.
[in]verbosePrint parsing info.
[out]modelReference model where to put the parsed information.
Returns
Return the reference on argument model for convenience.

◆ buildModel() [2/4]

template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl>
ModelTpl<Scalar,Options,JointCollectionTpl>& pinocchio::urdf::buildModel ( const std::string &  filename,
ModelTpl< Scalar, Options, JointCollectionTpl > &  model,
const bool  verbose = false 
)

Build the model from a URDF file with a fixed joint as root of the model tree.

Parameters
[in]filenameThe URDF complete file path.
[in]verbosePrint parsing info.
[out]modelReference model where to put the parsed information.
Returns
Return the reference on argument model for convenience.

◆ buildModel() [3/4]

template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl>
ModelTpl<Scalar,Options,JointCollectionTpl>& pinocchio::urdf::buildModel ( const boost::shared_ptr< ::urdf::ModelInterface >  urdfTree,
const typename ModelTpl< Scalar, Options, JointCollectionTpl >::JointModel rootJoint,
ModelTpl< Scalar, Options, JointCollectionTpl > &  model,
const bool  verbose = false 
)

Build the model from a URDF model with a particular joint as root of the model tree inside the model given as reference argument.

Parameters
[in]urdfTreethe tree build from the URDF
[in]rootJointThe joint at the root of the model tree.
[in]verbosePrint parsing info.
[out]modelReference model where to put the parsed information.
Returns
Return the reference on argument model for convenience.
Note
urdfTree can be build from ::urdf::parseURDF or ::urdf::parseURDFFile

◆ buildModel() [4/4]

template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl>
ModelTpl<Scalar,Options,JointCollectionTpl>& pinocchio::urdf::buildModel ( const boost::shared_ptr< ::urdf::ModelInterface >  urdfTree,
ModelTpl< Scalar, Options, JointCollectionTpl > &  model,
const bool  verbose = false 
)

Build the model from a URDF model.

Parameters
[in]urdfTreethe tree build from the URDF
[in]verbosePrint parsing info.
[out]modelReference model where to put the parsed information.
Returns
Return the reference on argument model for convenience.
Note
urdfTree can be build from ::urdf::parseURDF or ::urdf::parseURDFFile

◆ buildModelFromXML() [1/2]

template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl>
ModelTpl<Scalar,Options,JointCollectionTpl>& pinocchio::urdf::buildModelFromXML ( const std::string &  xml_stream,
const typename ModelTpl< Scalar, Options, JointCollectionTpl >::JointModel rootJoint,
ModelTpl< Scalar, Options, JointCollectionTpl > &  model,
const bool  verbose = false 
)

Build the model from an XML stream with a particular joint as root of the model tree inside the model given as reference argument.

Parameters
[in]xml_streamstream containing the URDF model.
[in]rootJointThe joint at the root of the model tree.
[in]verbosePrint parsing info.
[out]modelReference model where to put the parsed information.
Returns
Return the reference on argument model for convenience.
Note
urdfTree can be build from ::urdf::parseURDF or ::urdf::parseURDFFile

◆ buildModelFromXML() [2/2]

template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl>
ModelTpl<Scalar,Options,JointCollectionTpl>& pinocchio::urdf::buildModelFromXML ( const std::string &  xml_stream,
ModelTpl< Scalar, Options, JointCollectionTpl > &  model,
const bool  verbose = false 
)

Build the model from an XML stream.

Parameters
[in]xml_streamstream containing the URDF model.
[in]verbosePrint parsing info.
[out]modelReference model where to put the parsed information.
Returns
Return the reference on argument model for convenience.
Note
urdfTree can be build from ::urdf::parseURDF or ::urdf::parseURDFFile


pinocchio
Author(s):
autogenerated on Fri Jun 23 2023 02:38:36