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... | |
SE3 | convertFromUrdf (const ::urdf::Pose &M) |
Convert URDF Pose quantity to SE3. More... | |
static Inertia | convertFromUrdf (const ::urdf::Inertial &Y) |
Convert URDF Inertial quantity to Spatial Inertia. More... | |
static Inertia | convertFromUrdf (const ::urdf::InertialSharedPtr &Y) |
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) |
|
static |
Add the geometries attached to a URDF link to a GeometryModel, looking either for collisions or visuals.
[in] | tree | The URDF kinematic tree |
[in] | meshLoader | The FCL mesh loader to avoid duplications of already loaded geometries |
[in] | link | The current URDF link |
model | The model to which is the GeometryModel associated | |
geomModel | The GeometryModel where the Collision Objects must be added | |
[in] | package_dirs | A vector containing the different directories where to search for packages |
Definition at line 345 of file src/parsers/urdf/geometry.cpp.
SE3 pinocchio::urdf::details::convertFromUrdf | ( | const ::urdf::Pose & | M | ) |
Convert URDF Pose quantity to SE3.
[in] | M | The input URDF Pose. |
|
static |
Convert URDF Inertial quantity to Spatial Inertia.
[in] | Y | The input URDF Inertia. |
Definition at line 30 of file src/parsers/urdf/model.cpp.
|
static |
Definition at line 45 of file src/parsers/urdf/model.cpp.
|
inline |
Get the first geometry attached to a link.
[in] | link | The URDF link |
Definition at line 253 of file src/parsers/urdf/geometry.cpp.
inline ::urdf::VisualConstSharedPtr pinocchio::urdf::details::getLinkGeometry< ::urdf::Visual > | ( | const ::urdf::LinkConstSharedPtr | link | ) |
Definition at line 260 of file src/parsers/urdf/geometry.cpp.
|
inline |
Get the array of geometries attached to a link.
[in] | link | The URDF link |
|
inline |
Definition at line 320 of file src/parsers/urdf/geometry.cpp.
|
inline |
Definition at line 327 of file src/parsers/urdf/geometry.cpp.
|
static |
Definition at line 51 of file src/parsers/urdf/model.cpp.
|
inline |
Get the material values from the link visual object.
[in] | Visual/Collision | The Visual or the Collision object. |
[out] | meshTexturePath | The absolute file path containing the texture description. |
[out] | meshColor | The mesh RGBA vector. |
[in] | package_dirs | A vector containing the different directories where to search for packages |
|
inline |
Definition at line 281 of file src/parsers/urdf/geometry.cpp.
|
inline |
Definition at line 291 of file src/parsers/urdf/geometry.cpp.
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.
[in] | link | The current URDF link. |
[in] | model | The model where the link must be added. |
Definition at line 273 of file src/parsers/urdf/model.cpp.
void pinocchio::urdf::details::parseRootTree | ( | const std::string & | filename, |
UrdfVisitorBase & | model | ||
) |
Definition at line 287 of file src/parsers/urdf/model.cpp.
void pinocchio::urdf::details::parseRootTreeFromXML | ( | const std::string & | xmlString, |
UrdfVisitorBase & | model | ||
) |
Definition at line 298 of file src/parsers/urdf/model.cpp.
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.
[in] | link | The current URDF link. |
[in] | model | The model where the link must be added. |
Definition at line 66 of file src/parsers/urdf/model.cpp.
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 459 of file src/parsers/urdf/geometry.cpp.
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.
[in] | tree | The URDF kinematic tree |
[in] | meshLoader | The FCL mesh loader to avoid duplications of already loaded geometries |
[in] | link | The current URDF link |
model | The model to which is the GeometryModel associated | |
geomModel | The GeometryModel where the Collision Objects must be added | |
[in] | package_dirs | A vector containing the different directories where to search for packages |
[in] | type | The type of objects that must be loaded ( can be VISUAL or COLLISION) |
Definition at line 431 of file src/parsers/urdf/geometry.cpp.
|
static |
Definition at line 102 of file src/parsers/urdf/geometry.cpp.