URDF parsing. More...
Functions | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
GeometryModel & | 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. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
GeometryModel & | 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. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
GeometryModel & | 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. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
GeometryModel & | 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. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
ModelTpl< Scalar, Options, JointCollectionTpl > & | buildModel (const std::shared_ptr<::urdf::ModelInterface > urdfTree, const typename ModelTpl< Scalar, Options, JointCollectionTpl >::JointModel &rootJoint, const std::string &rootJointName, 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 std::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 std::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 > & | buildModel (const std::string &filename, const typename ModelTpl< Scalar, Options, JointCollectionTpl >::JointModel &rootJoint, const std::string &rootJointName, 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, 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 > & | buildModelFromXML (const std::string &xml_stream, const typename ModelTpl< Scalar, Options, JointCollectionTpl >::JointModel &rootJoint, const std::string &rootJointName, 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, 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... | |
URDF parsing.
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.
[in] | model | The model of the robot, built with urdf::buildModel |
[in] | xml_stream | Stream containing the URDF model |
[in] | package_path | A string containing the path to the directories of the meshes, typically obtained from calling pinocchio::rosPaths(). |
[in] | type | The type of objects that must be loaded (must be VISUAL or COLLISION) |
[in] | mesh_loader | object used to load meshes: hpp::fcl::MeshLoader [default] or hpp::fcl::CachedMeshLoader. |
[out] | geom_model | Reference where to put the parsed information. |
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.
[in] | model | The model of the robot, built with urdf::buildModel |
[in] | xml_stream | Stream containing the URDF model |
[in] | package_paths | A vector containing the different directories where to search for models and meshes, typically obtained from calling pinocchio::rosPaths() |
[in] | type | The type of objects that must be loaded (must be VISUAL or COLLISION) |
[in] | mesh_loader | object used to load meshes: hpp::fcl::MeshLoader [default] or hpp::fcl::CachedMeshLoader. |
[out] | geom_model | Reference where to put the parsed information. |
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.
[in] | model | The model of the robot, built with urdf::buildModel |
[in] | filename | The URDF complete (absolute) file path |
[in] | package_path | A string containing the path to the directories of the meshes, typically obtained from calling pinocchio::rosPaths(). |
[in] | type | The type of objects that must be loaded (must be VISUAL or COLLISION) |
[in] | mesh_loader | object used to load meshes: hpp::fcl::MeshLoader [default] or hpp::fcl::CachedMeshLoader. |
[out] | geom_model | Reference where to put the parsed information. |
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.
[in] | model | The model of the robot, built with urdf::buildModel |
[in] | filename | The URDF complete (absolute) file path |
[in] | package_paths | A vector containing the different directories where to search for models and meshes, typically obtained from calling pinocchio::rosPaths() |
[in] | type | The type of objects that must be loaded (must be VISUAL or COLLISION) |
[in] | mesh_loader | object used to load meshes: hpp::fcl::MeshLoader [default] or hpp::fcl::CachedMeshLoader. |
[out] | geom_model | Reference where to put the parsed information. |
ModelTpl<Scalar, Options, JointCollectionTpl>& pinocchio::urdf::buildModel | ( | const std::shared_ptr<::urdf::ModelInterface > | urdfTree, |
const typename ModelTpl< Scalar, Options, JointCollectionTpl >::JointModel & | rootJoint, | ||
const std::string & | rootJointName, | ||
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.
[in] | urdfTree | the tree build from the URDF |
[in] | rootJoint | The joint at the root of the model tree. |
[in] | rootJointName | Name of the rootJoint. |
[in] | verbose | Print parsing info. |
[out] | model | Reference model where to put the parsed information. |
ModelTpl<Scalar, Options, JointCollectionTpl>& pinocchio::urdf::buildModel | ( | const std::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.
[in] | urdfTree | the tree build from the URDF |
[in] | rootJoint | The joint at the root of the model tree. |
[in] | verbose | Print parsing info. |
[out] | model | Reference model where to put the parsed information. |
ModelTpl<Scalar, Options, JointCollectionTpl>& pinocchio::urdf::buildModel | ( | const std::shared_ptr<::urdf::ModelInterface > | urdfTree, |
ModelTpl< Scalar, Options, JointCollectionTpl > & | model, | ||
const bool | verbose = false |
||
) |
Build the model from a URDF model.
[in] | urdfTree | the tree build from the URDF |
[in] | verbose | Print parsing info. |
[out] | model | Reference model where to put the parsed information. |
ModelTpl<Scalar, Options, JointCollectionTpl>& pinocchio::urdf::buildModel | ( | const std::string & | filename, |
const typename ModelTpl< Scalar, Options, JointCollectionTpl >::JointModel & | rootJoint, | ||
const std::string & | rootJointName, | ||
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.
[in] | filename | The URDF complete file path. |
[in] | rootJoint | The joint at the root of the model tree. |
[in] | rootJointName | Name of the rootJoint. |
[in] | verbose | Print parsing info. |
[out] | model | Reference model where to put the parsed information. |
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.
[in] | filename | The URDF complete file path. |
[in] | rootJoint | The joint at the root of the model tree. |
[in] | verbose | Print parsing info. |
[out] | model | Reference model where to put the parsed information. |
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.
[in] | filename | The URDF complete file path. |
[in] | verbose | Print parsing info. |
[out] | model | Reference model where to put the parsed information. |
ModelTpl<Scalar, Options, JointCollectionTpl>& pinocchio::urdf::buildModelFromXML | ( | const std::string & | xml_stream, |
const typename ModelTpl< Scalar, Options, JointCollectionTpl >::JointModel & | rootJoint, | ||
const std::string & | rootJointName, | ||
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.
[in] | xml_stream | stream containing the URDF model. |
[in] | rootJoint | The joint at the root of the model tree. |
[in] | rootJointName | Name of the rootJoint. |
[in] | verbose | Print parsing info. |
[out] | model | Reference model where to put the parsed information. |
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.
[in] | xml_stream | stream containing the URDF model. |
[in] | rootJoint | The joint at the root of the model tree. |
[in] | verbose | Print parsing info. |
[out] | model | Reference model where to put the parsed information. |
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.
[in] | xml_stream | stream containing the URDF model. |
[in] | verbose | Print parsing info. |
[out] | model | Reference model where to put the parsed information. |