#include <geometry-object.hpp>
Public Types | |
enum | { Options = traits<GeometryObject>::Options } |
typedef std::shared_ptr< fcl::CollisionGeometry > | CollisionGeometryPtr |
typedef traits< GeometryObject >::Scalar | Scalar |
typedef SE3Tpl< Scalar, Options > | SE3 |
Public Types inherited from pinocchio::ModelItem< GeometryObject > | |
enum | |
typedef SE3Tpl< Scalar, Options > | SE3 |
Public Types inherited from pinocchio::NumericalBase< GeometryObject > | |
typedef traits< GeometryObject >::Scalar | Scalar |
Public Member Functions | |
GeometryObject | clone () const |
Perform a deep copy of this. It will create a copy of the underlying FCL geometry. More... | |
GeometryObject (const GeometryObject &other)=default | |
PINOCCHIO_DEPRECATED | GeometryObject (const std::string &name, const FrameIndex parent_frame, const JointIndex parent_joint, const CollisionGeometryPtr &collision_geometry, const SE3 &placement, const std::string &meshPath="", const Eigen::Vector3d &meshScale=Eigen::Vector3d::Ones(), const bool overrideMaterial=false, const Eigen::Vector4d &meshColor=Eigen::Vector4d(0, 0, 0, 1), const std::string &meshTexturePath="", const GeometryMaterial &meshMaterial=GeometryNoMaterial()) |
Full constructor. More... | |
PINOCCHIO_DEPRECATED | GeometryObject (const std::string &name, const JointIndex parent_joint, const CollisionGeometryPtr &collision_geometry, const SE3 &placement, const std::string &meshPath="", const Eigen::Vector3d &meshScale=Eigen::Vector3d::Ones(), const bool overrideMaterial=false, const Eigen::Vector4d &meshColor=Eigen::Vector4d(0, 0, 0, 1), const std::string &meshTexturePath="", const GeometryMaterial &meshMaterial=GeometryNoMaterial()) |
Reduced constructor. More... | |
GeometryObject (const std::string &name, const JointIndex parent_joint, const FrameIndex parent_frame, const SE3 &placement, const CollisionGeometryPtr &collision_geometry, const std::string &meshPath="", const Eigen::Vector3d &meshScale=Eigen::Vector3d::Ones(), const bool overrideMaterial=false, const Eigen::Vector4d &meshColor=Eigen::Vector4d(0, 0, 0, 1), const std::string &meshTexturePath="", const GeometryMaterial &meshMaterial=GeometryNoMaterial()) | |
Full constructor. More... | |
GeometryObject (const std::string &name, const JointIndex parent_joint, const SE3 &placement, const CollisionGeometryPtr &collision_geometry, const std::string &meshPath="", const Eigen::Vector3d &meshScale=Eigen::Vector3d::Ones(), const bool overrideMaterial=false, const Eigen::Vector4d &meshColor=Eigen::Vector4d(0, 0, 0, 1), const std::string &meshTexturePath="", const GeometryMaterial &meshMaterial=GeometryNoMaterial()) | |
Reduced constructor. More... | |
bool | operator!= (const GeometryObject &other) const |
GeometryObject & | operator= (const GeometryObject &other)=default |
bool | operator== (const GeometryObject &other) const |
Public Member Functions inherited from pinocchio::ModelItem< GeometryObject > | |
ModelItem () | |
Default constructor of ModelItem. More... | |
ModelItem (const std::string &name, const JointIndex parent_joint, const FrameIndex parent_frame, const SE3 &frame_placement) | |
Builds a kinematic element defined by its name, its joint parent id, its parent frame id and its placement. More... | |
bool | operator== (const ModelItem &other) const |
Public Member Functions inherited from pinocchio::serialization::Serializable< GeometryObject > | |
void | loadFromBinary (boost::asio::streambuf &container) |
Loads a Derived object from a binary container. More... | |
void | loadFromBinary (const std::string &filename) |
Loads a Derived object from an binary file. More... | |
void | loadFromBinary (StaticBuffer &container) |
Loads a Derived object from a static binary container. More... | |
void | loadFromString (const std::string &str) |
Loads a Derived object from a string. More... | |
void | loadFromStringStream (std::istringstream &is) |
Loads a Derived object from a stream string. More... | |
void | loadFromText (const std::string &filename) |
Loads a Derived object from a text file. More... | |
void | loadFromXML (const std::string &filename, const std::string &tag_name) |
Loads a Derived object from an XML file. More... | |
void | saveToBinary (boost::asio::streambuf &container) const |
Saves a Derived object as a binary container. More... | |
void | saveToBinary (const std::string &filename) const |
Saves a Derived object as an binary file. More... | |
void | saveToBinary (StaticBuffer &container) const |
Saves a Derived object as a static binary container. More... | |
std::string | saveToString () const |
Saves a Derived object to a string. More... | |
void | saveToStringStream (std::stringstream &ss) const |
Saves a Derived object to a string stream. More... | |
void | saveToText (const std::string &filename) const |
Saves a Derived object as a text file. More... | |
void | saveToXML (const std::string &filename, const std::string &tag_name) const |
Saves a Derived object as an XML file. More... | |
Public Attributes | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef ModelItem< GeometryObject > | Base |
bool | disableCollision |
If true, no collision or distance check will be done between the Geometry and any other geometry. More... | |
CollisionGeometryPtr | geometry |
The FCL CollisionGeometry (might be a Mesh, a Geometry Primitive, etc.) More... | |
Eigen::Vector4d | meshColor |
RGBA color value of the GeometryObject::geometry object. More... | |
GeometryMaterial | meshMaterial |
Material associated to the mesh. This material should be used only if overrideMaterial is set to true. In other case, the mesh default material must be used. More... | |
std::string | meshPath |
Absolute path to the mesh file (if the geometry pointee is also a Mesh) More... | |
Eigen::Vector3d | meshScale |
Scaling vector applied to the GeometryObject::geometry object. More... | |
std::string | meshTexturePath |
Absolute path to the mesh texture file. More... | |
bool | overrideMaterial |
Decide whether to override the Material. More... | |
Public Attributes inherited from pinocchio::ModelItem< GeometryObject > | |
std::string | name |
Name of the kinematic element. More... | |
FrameIndex | parentFrame |
Index of the parent frame. More... | |
JointIndex | parentJoint |
Index of the parent joint. More... | |
SE3 | placement |
Position of kinematic element in parent joint frame. More... | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef traits< GeometryObject >::Scalar | Scalar |
Friends | |
std::ostream & | operator<< (std::ostream &os, const GeometryObject &geomObject) |
Definition at line 87 of file multibody/geometry-object.hpp.
typedef std::shared_ptr<fcl::CollisionGeometry> pinocchio::GeometryObject::CollisionGeometryPtr |
Definition at line 102 of file multibody/geometry-object.hpp.
Definition at line 94 of file multibody/geometry-object.hpp.
typedef SE3Tpl<Scalar, Options> pinocchio::GeometryObject::SE3 |
Definition at line 100 of file multibody/geometry-object.hpp.
anonymous enum |
Enumerator | |
---|---|
Options |
Definition at line 95 of file multibody/geometry-object.hpp.
|
inline |
Full constructor.
[in] | name | Name of the geometry object. |
[in] | parent_joint | Index of the parent joint (that supports the geometry). |
[in] | parent_frame | Index of the parent frame. |
[in] | placement | Placement of the geometry with respect to the joint frame. |
[in] | collision_geometry | The FCL collision geometry object. |
[in] | meshPath | Path of the mesh (may be needed extarnally to load the mesh inside a viewer for instance) [if applicable]. |
[in] | meshScale | Scale of the mesh [if applicable]. |
[in] | overrideMaterial | If true, this option allows to overrite the material [if applicable]. |
[in] | meshColor | Color of the mesh [if applicable]. |
[in] | meshTexturePath | Path to the file containing the texture information [if applicable]. |
[in] | meshMaterial | Material of the mesh [if applicable]. |
Definition at line 151 of file multibody/geometry-object.hpp.
|
inline |
Reduced constructor.
[in] | name | Name of the geometry object. |
[in] | parent_joint | Index of the parent joint (that supports the geometry). |
[in] | placement | Placement of the geometry with respect to the joint frame. |
[in] | collision_geometry | The FCL collision geometry object. |
[in] | meshPath | Path of the mesh (may be needed extarnally to load the mesh inside a viewer for instance) [if applicable]. |
[in] | meshScale | Scale of the mesh [if applicable]. |
[in] | overrideMaterial | If true, this option allows to overrite the material [if applicable]. |
[in] | meshColor | Color of the mesh [if applicable]. |
[in] | meshTexturePath | Path to the file containing the texture information [if applicable]. |
[in] | meshMaterial | Material of the mesh [if applicable]. |
Definition at line 191 of file multibody/geometry-object.hpp.
|
inline |
Full constructor.
[in] | name | Name of the geometry object. |
[in] | parent_frame | Index of the parent frame. |
[in] | parent_joint | Index of the parent joint (that supports the geometry). |
[in] | collision_geometry | The FCL collision geometry object. |
[in] | placement | Placement of the geometry with respect to the joint frame. |
[in] | meshPath | Path of the mesh (may be needed extarnally to load the mesh inside a viewer for instance) [if applicable]. |
[in] | meshScale | Scale of the mesh [if applicable]. |
[in] | overrideMaterial | If true, this option allows to overrite the material [if applicable]. |
[in] | meshColor | Color of the mesh [if applicable]. |
[in] | meshTexturePath | Path to the file containing the texture information [if applicable]. |
[in] | meshMaterial | Material of the mesh [if applicable]. |
Definition at line 231 of file multibody/geometry-object.hpp.
|
inline |
Reduced constructor.
[in] | name | Name of the geometry object. |
[in] | parent_joint | Index of the parent joint (that supports the geometry). |
[in] | collision_geometry | The FCL collision geometry object. |
[in] | placement | Placement of the geometry with respect to the joint frame. |
[in] | meshPath | Path of the mesh (may be needed extarnally to load the mesh inside a viewer for instance) [if applicable]. |
[in] | meshScale | Scale of the mesh [if applicable]. |
[in] | overrideMaterial | If true, this option allows to overrite the material [if applicable]. |
[in] | meshColor | Color of the mesh [if applicable]. |
[in] | meshTexturePath | Path to the file containing the texture information [if applicable]. |
[in] | meshMaterial | Material of the mesh [if applicable]. |
Definition at line 273 of file multibody/geometry-object.hpp.
|
default |
|
inline |
Perform a deep copy of this. It will create a copy of the underlying FCL geometry.
Definition at line 302 of file multibody/geometry-object.hpp.
|
inline |
Definition at line 327 of file multibody/geometry-object.hpp.
|
default |
|
inline |
Definition at line 314 of file multibody/geometry-object.hpp.
|
friend |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef ModelItem<GeometryObject> pinocchio::GeometryObject::Base |
Definition at line 93 of file multibody/geometry-object.hpp.
bool pinocchio::GeometryObject::disableCollision |
If true, no collision or distance check will be done between the Geometry and any other geometry.
Definition at line 134 of file multibody/geometry-object.hpp.
CollisionGeometryPtr pinocchio::GeometryObject::geometry |
The FCL CollisionGeometry (might be a Mesh, a Geometry Primitive, etc.)
Definition at line 110 of file multibody/geometry-object.hpp.
Eigen::Vector4d pinocchio::GeometryObject::meshColor |
RGBA color value of the GeometryObject::geometry object.
Definition at line 122 of file multibody/geometry-object.hpp.
GeometryMaterial pinocchio::GeometryObject::meshMaterial |
Material associated to the mesh. This material should be used only if overrideMaterial is set to true. In other case, the mesh default material must be used.
Definition at line 127 of file multibody/geometry-object.hpp.
std::string pinocchio::GeometryObject::meshPath |
Absolute path to the mesh file (if the geometry pointee is also a Mesh)
Definition at line 113 of file multibody/geometry-object.hpp.
Eigen::Vector3d pinocchio::GeometryObject::meshScale |
Scaling vector applied to the GeometryObject::geometry object.
Definition at line 116 of file multibody/geometry-object.hpp.
std::string pinocchio::GeometryObject::meshTexturePath |
Absolute path to the mesh texture file.
Definition at line 130 of file multibody/geometry-object.hpp.
bool pinocchio::GeometryObject::overrideMaterial |
Decide whether to override the Material.
Definition at line 119 of file multibody/geometry-object.hpp.