Classes | Functions
pinocchio::urdf::details Namespace Reference

Classes

struct  UrdfTree
 

Functions

template<typename GeometryType >
static void addLinkGeometryToGeomModel (const UrdfTree &tree, ::hpp::fcl::MeshLoaderPtr &meshLoader, ::urdf::LinkConstSharedPtr link, UrdfGeomVisitorBase &visitor, GeometryModel &geomModel, const std::vector< std::string > &package_dirs)
 Add the geometries attached to a URDF link to a GeometryModel, looking either for collisions or visuals. More...
 
static Inertia convertFromUrdf (const ::urdf::Inertial &Y)
 Convert URDF Inertial quantity to Spatial Inertia. More...
 
static Inertia convertFromUrdf (const ::urdf::InertialSharedPtr &Y)
 
SE3 convertFromUrdf (const ::urdf::Pose &M)
 Convert URDF Pose quantity to SE3. More...
 
template<>
PINOCCHIO_URDF_SHARED_PTR(const T) getLinkGeometry(const inline ::urdf::CollisionConstSharedPtr getLinkGeometry<::urdf::Collision > (const ::urdf::LinkConstSharedPtr link)
 Get the first geometry attached to a link. More...
 
template<>
inline ::urdf::VisualConstSharedPtr getLinkGeometry<::urdf::Visual > (const ::urdf::LinkConstSharedPtr link)
 
template<typename T >
const std::vector< PINOCCHIO_URDF_SHARED_PTR(T)> & getLinkGeometryArray (const ::urdf::LinkConstSharedPtr link)
 Get the array of geometries attached to a link. More...
 
template<>
const std::vector<::urdf::CollisionSharedPtr > & getLinkGeometryArray<::urdf::Collision > (const ::urdf::LinkConstSharedPtr link)
 
template<>
const std::vector<::urdf::VisualSharedPtr > & getLinkGeometryArray<::urdf::Visual > (const ::urdf::LinkConstSharedPtr link)
 
static FrameIndex getParentLinkFrame (const ::urdf::LinkConstSharedPtr link, UrdfVisitorBase &model)
 
template<typename urdfObject >
bool getVisualMaterial (const PINOCCHIO_URDF_SHARED_PTR(urdfObject) urdf_object, std::string &meshTexturePath, Eigen::Vector4d &meshColor, const std::vector< std::string > &package_dirs)
 Get the material values from the link visual object. More...
 
template<>
bool getVisualMaterial<::urdf::Collision > (const ::urdf::CollisionSharedPtr, std::string &meshTexturePath, Eigen::Vector4d &meshColor, const std::vector< std::string > &)
 
template<>
bool getVisualMaterial<::urdf::Visual > (const ::urdf::VisualSharedPtr urdf_visual, std::string &meshTexturePath, Eigen::Vector4d &meshColor, const std::vector< std::string > &package_dirs)
 
void parseRootTree (const ::urdf::ModelInterface *urdfTree, UrdfVisitorBase &model)
 Parse a tree with a specific root joint linking the model to the environment. The function returns an exception as soon as a necessary Inertia or Joint information are missing. More...
 
void parseRootTree (const std::string &filename, UrdfVisitorBase &model)
 
void parseRootTreeFromXML (const std::string &xmlString, UrdfVisitorBase &model)
 
void parseTree (::urdf::LinkConstSharedPtr link, UrdfVisitorBase &model)
 Recursive procedure for reading the URDF tree. The function returns an exception as soon as a necessary Inertia or Joint information are missing. More...
 
void parseTreeForGeom (UrdfGeomVisitorBase &visitor, const std::istream &xmlStream, const GeometryType type, GeometryModel &geomModel, const std::vector< std::string > &package_dirs, ::hpp::fcl::MeshLoaderPtr meshLoader)
 
void recursiveParseTreeForGeom (const UrdfTree &tree, ::hpp::fcl::MeshLoaderPtr &meshLoader, ::urdf::LinkConstSharedPtr link, UrdfGeomVisitorBase &visitor, GeometryModel &geomModel, const std::vector< std::string > &package_dirs, const GeometryType type)
 Recursive procedure for reading the URDF tree, looking for geometries This function fill the geometric model with geometry objects retrieved from the URDF tree. More...
 
template<typename Vector3 >
static void retrieveMeshScale (const ::urdf::MeshSharedPtr &mesh, const Eigen::MatrixBase< Vector3 > &scale)
 

Function Documentation

◆ addLinkGeometryToGeomModel()

template<typename GeometryType >
static void pinocchio::urdf::details::addLinkGeometryToGeomModel ( const UrdfTree tree,
::hpp::fcl::MeshLoaderPtr &  meshLoader,
::urdf::LinkConstSharedPtr  link,
UrdfGeomVisitorBase &  visitor,
GeometryModel geomModel,
const std::vector< std::string > &  package_dirs 
)
static

Add the geometries attached to a URDF link to a GeometryModel, looking either for collisions or visuals.

Parameters
[in]treeThe URDF kinematic tree
[in]meshLoaderThe FCL mesh loader to avoid duplications of already loaded geometries
[in]linkThe current URDF link
modelThe model to which is the GeometryModel associated
geomModelThe GeometryModel where the Collision Objects must be added
[in]package_dirsA vector containing the different directories where to search for packages

Definition at line 363 of file src/parsers/urdf/geometry.cpp.

◆ convertFromUrdf() [1/3]

static Inertia pinocchio::urdf::details::convertFromUrdf ( const ::urdf::Inertial &  Y)
static

Convert URDF Inertial quantity to Spatial Inertia.

Parameters
[in]YThe input URDF Inertia.
Returns
The converted Spatial Inertia pinocchio::Inertia.

Definition at line 30 of file src/parsers/urdf/model.cpp.

◆ convertFromUrdf() [2/3]

static Inertia pinocchio::urdf::details::convertFromUrdf ( const ::urdf::InertialSharedPtr &  Y)
static

Definition at line 44 of file src/parsers/urdf/model.cpp.

◆ convertFromUrdf() [3/3]

SE3 pinocchio::urdf::details::convertFromUrdf ( const ::urdf::Pose &  M)

Convert URDF Pose quantity to SE3.

Parameters
[in]MThe input URDF Pose.
Returns
The converted pose/transform pinocchio::SE3.

Definition at line 10 of file utils.cpp.

◆ getLinkGeometry<::urdf::Collision >()

template<>
PINOCCHIO_URDF_SHARED_PTR (const T) getLinkGeometry( const inline ::urdf::CollisionConstSharedPtr pinocchio::urdf::details::getLinkGeometry<::urdf::Collision > ( const ::urdf::LinkConstSharedPtr  link) const
inline

Get the first geometry attached to a link.

Parameters
[in]linkThe URDF link
Returns
Either the first collision or visual

Definition at line 260 of file src/parsers/urdf/geometry.cpp.

◆ getLinkGeometry<::urdf::Visual >()

template<>
inline ::urdf::VisualConstSharedPtr pinocchio::urdf::details::getLinkGeometry<::urdf::Visual > ( const ::urdf::LinkConstSharedPtr  link)

Definition at line 267 of file src/parsers/urdf/geometry.cpp.

◆ getLinkGeometryArray()

template<typename T >
const std::vector<PINOCCHIO_URDF_SHARED_PTR(T)>& pinocchio::urdf::details::getLinkGeometryArray ( const ::urdf::LinkConstSharedPtr  link)
inline

Get the array of geometries attached to a link.

Parameters
[in]linkThe URDF link
Returns
the array of either collisions or visuals

◆ getLinkGeometryArray<::urdf::Collision >()

template<>
const std::vector<::urdf::CollisionSharedPtr>& pinocchio::urdf::details::getLinkGeometryArray<::urdf::Collision > ( const ::urdf::LinkConstSharedPtr  link)
inline

Definition at line 336 of file src/parsers/urdf/geometry.cpp.

◆ getLinkGeometryArray<::urdf::Visual >()

template<>
const std::vector<::urdf::VisualSharedPtr>& pinocchio::urdf::details::getLinkGeometryArray<::urdf::Visual > ( const ::urdf::LinkConstSharedPtr  link)
inline

Definition at line 343 of file src/parsers/urdf/geometry.cpp.

◆ getParentLinkFrame()

static FrameIndex pinocchio::urdf::details::getParentLinkFrame ( const ::urdf::LinkConstSharedPtr  link,
UrdfVisitorBase &  model 
)
static

Definition at line 52 of file src/parsers/urdf/model.cpp.

◆ getVisualMaterial()

template<typename urdfObject >
bool pinocchio::urdf::details::getVisualMaterial ( const PINOCCHIO_URDF_SHARED_PTR(urdfObject)  urdf_object,
std::string &  meshTexturePath,
Eigen::Vector4d &  meshColor,
const std::vector< std::string > &  package_dirs 
)
inline

Get the material values from the link visual object.

Parameters
[in]Visual/CollisionThe Visual or the Collision object.
[out]meshTexturePathThe absolute file path containing the texture description.
[out]meshColorThe mesh RGBA vector.
[in]package_dirsA vector containing the different directories where to search for packages

◆ getVisualMaterial<::urdf::Collision >()

template<>
bool pinocchio::urdf::details::getVisualMaterial<::urdf::Collision > ( const ::urdf::CollisionSharedPtr  ,
std::string &  meshTexturePath,
Eigen::Vector4d &  meshColor,
const std::vector< std::string > &   
)
inline

Definition at line 290 of file src/parsers/urdf/geometry.cpp.

◆ getVisualMaterial<::urdf::Visual >()

template<>
bool pinocchio::urdf::details::getVisualMaterial<::urdf::Visual > ( const ::urdf::VisualSharedPtr  urdf_visual,
std::string &  meshTexturePath,
Eigen::Vector4d &  meshColor,
const std::vector< std::string > &  package_dirs 
)
inline

Definition at line 302 of file src/parsers/urdf/geometry.cpp.

◆ parseRootTree() [1/2]

void pinocchio::urdf::details::parseRootTree ( const ::urdf::ModelInterface *  urdfTree,
UrdfVisitorBase &  model 
)

Parse a tree with a specific root joint linking the model to the environment. The function returns an exception as soon as a necessary Inertia or Joint information are missing.

Parameters
[in]linkThe current URDF link.
[in]modelThe model where the link must be added.

Definition at line 266 of file src/parsers/urdf/model.cpp.

◆ parseRootTree() [2/2]

void pinocchio::urdf::details::parseRootTree ( const std::string &  filename,
UrdfVisitorBase &  model 
)

Definition at line 279 of file src/parsers/urdf/model.cpp.

◆ parseRootTreeFromXML()

void pinocchio::urdf::details::parseRootTreeFromXML ( const std::string &  xmlString,
UrdfVisitorBase &  model 
)

Definition at line 291 of file src/parsers/urdf/model.cpp.

◆ parseTree()

void pinocchio::urdf::details::parseTree ( ::urdf::LinkConstSharedPtr  link,
UrdfVisitorBase &  model 
)

Recursive procedure for reading the URDF tree. The function returns an exception as soon as a necessary Inertia or Joint information are missing.

Parameters
[in]linkThe current URDF link.
[in]modelThe model where the link must be added.

Definition at line 67 of file src/parsers/urdf/model.cpp.

◆ parseTreeForGeom()

void pinocchio::urdf::details::parseTreeForGeom ( UrdfGeomVisitorBase &  visitor,
const std::istream &  xmlStream,
const GeometryType  type,
GeometryModel geomModel,
const std::vector< std::string > &  package_dirs,
::hpp::fcl::MeshLoaderPtr  meshLoader 
)

Definition at line 487 of file src/parsers/urdf/geometry.cpp.

◆ recursiveParseTreeForGeom()

void pinocchio::urdf::details::recursiveParseTreeForGeom ( const UrdfTree tree,
::hpp::fcl::MeshLoaderPtr &  meshLoader,
::urdf::LinkConstSharedPtr  link,
UrdfGeomVisitorBase &  visitor,
GeometryModel geomModel,
const std::vector< std::string > &  package_dirs,
const GeometryType  type 
)

Recursive procedure for reading the URDF tree, looking for geometries This function fill the geometric model with geometry objects retrieved from the URDF tree.

Parameters
[in]treeThe URDF kinematic tree
[in]meshLoaderThe FCL mesh loader to avoid duplications of already loaded geometries
[in]linkThe current URDF link
modelThe model to which is the GeometryModel associated
geomModelThe GeometryModel where the Collision Objects must be added
[in]package_dirsA vector containing the different directories where to search for packages
[in]typeThe type of objects that must be loaded ( can be VISUAL or COLLISION)

Definition at line 456 of file src/parsers/urdf/geometry.cpp.

◆ retrieveMeshScale()

template<typename Vector3 >
static void pinocchio::urdf::details::retrieveMeshScale ( const ::urdf::MeshSharedPtr &  mesh,
const Eigen::MatrixBase< Vector3 > &  scale 
)
static

Definition at line 118 of file src/parsers/urdf/geometry.cpp.



pinocchio
Author(s):
autogenerated on Sat Jun 1 2024 02:40:42