Geometry provides access to a shape, such as a Box. More...
#include <Geometry.hh>
Public Member Functions | |
| Geometry () | |
| Default constructor. More... | |
| std::optional< gz::math::AxisAlignedBox > | AxisAlignedBox (const Mesh::AxisAlignedBoxCalculator &_meshAabbCalculator) const |
| Calculate and return the AxisAlignedBox for the Geometry. More... | |
| const Box * | BoxShape () const |
| Get the box geometry, or nullptr if the contained geometry is not a box. More... | |
| std::optional< gz::math::Inertiald > | CalculateInertial (sdf::Errors &_errors, const ParserConfig &_config, double _density, sdf::ElementPtr _autoInertiaParams) |
| Calculate and return the Inertial values for the Geometry. More... | |
| const Capsule * | CapsuleShape () const |
| Get the capsule geometry, or nullptr if the contained geometry is not a capsule. More... | |
| const Cone * | ConeShape () const |
| Get the cone geometry, or nullptr if the contained geometry is not a cone. More... | |
| const Cylinder * | CylinderShape () const |
| Get the cylinder geometry, or nullptr if the contained geometry is not a cylinder. More... | |
| sdf::ElementPtr | Element () const |
| Get a pointer to the SDF element that was used during load. More... | |
| const Ellipsoid * | EllipsoidShape () const |
| Get the ellipsoid geometry, or nullptr if the contained geometry is not an ellipsoid. More... | |
| const Heightmap * | HeightmapShape () const |
| Get the heightmap geometry, or nullptr if the contained geometry is not a heightmap. More... | |
| Errors | Load (ElementPtr _sdf) |
| Load the geometry based on a element pointer. More... | |
| Errors | Load (sdf::ElementPtr _sdf, const ParserConfig &_config) |
| Load the geometry based on a element pointer. More... | |
| const Mesh * | MeshShape () const |
| Get the mesh geometry, or nullptr if the contained geometry is not a mesh. More... | |
| const Plane * | PlaneShape () const |
| Get the plane geometry, or nullptr if the contained geometry is not a plane. More... | |
| const std::vector< Polyline > & | PolylineShape () const |
| Get the polyline geometry. More... | |
| void | SetBoxShape (const Box &_box) |
| Set the box shape. More... | |
| void | SetCapsuleShape (const Capsule &_capsule) |
| Set the capsule shape. More... | |
| void | SetConeShape (const Cone &_cone) |
| Set the cone shape. More... | |
| void | SetCylinderShape (const Cylinder &_cylinder) |
| Set the cylinder shape. More... | |
| void | SetEllipsoidShape (const Ellipsoid &_ellipsoid) |
| Set the ellipsoid shape. More... | |
| void | SetHeightmapShape (const Heightmap &_heightmap) |
| Set the heightmap shape. More... | |
| void | SetMeshShape (const Mesh &_mesh) |
| Set the mesh shape. More... | |
| void | SetPlaneShape (const Plane &_plane) |
| Set the plane shape. More... | |
| void | SetPolylineShape (const std::vector< Polyline > &_polyline) |
| Set the polyline shape. More... | |
| void | SetSphereShape (const Sphere &_sphere) |
| Set the sphere shape. More... | |
| void | SetType (const GeometryType _type) |
| Set the type of geometry. More... | |
| const Sphere * | SphereShape () const |
| Get the sphere geometry, or nullptr if the contained geometry is not a sphere. More... | |
| sdf::ElementPtr | ToElement () const |
| Create and return an SDF element filled with data from this geometry. More... | |
| sdf::ElementPtr | ToElement (sdf::Errors &_errors) const |
| Create and return an SDF element filled with data from this geometry. More... | |
| GeometryType | Type () const |
| Get the type of geometry. More... | |
Geometry provides access to a shape, such as a Box.
Use the Type function to determine the type of shape contained within a Geometry. Access to shape data, such as a box's size, is achieved through the shape accessors, such as const Box *BoxShape() const.
| sdf::SDF_VERSION_NAMESPACE::Geometry::Geometry | ( | ) |
Default constructor.
| std::optional<gz::math::AxisAlignedBox> sdf::SDF_VERSION_NAMESPACE::Geometry::AxisAlignedBox | ( | const Mesh::AxisAlignedBoxCalculator & | _meshAabbCalculator | ) | const |
Calculate and return the AxisAlignedBox for the Geometry.
| _meshAabbCalculator | The function to calculate the AABB of a mesh |
| const Box* sdf::SDF_VERSION_NAMESPACE::Geometry::BoxShape | ( | ) | const |
Get the box geometry, or nullptr if the contained geometry is not a box.
| std::optional<gz::math::Inertiald> sdf::SDF_VERSION_NAMESPACE::Geometry::CalculateInertial | ( | sdf::Errors & | _errors, |
| const ParserConfig & | _config, | ||
| double | _density, | ||
| sdf::ElementPtr | _autoInertiaParams | ||
| ) |
Calculate and return the Inertial values for the Geometry.
| [out] | _errors | A vector of Errors object. Each object would contain an error code and an error message. |
| [in] | _config | Parser Config |
| [in] | _density | The density of the geometry element. |
| [in] | _autoInertiaParams | ElementPtr to <auto_inertia_params> |
| const Capsule* sdf::SDF_VERSION_NAMESPACE::Geometry::CapsuleShape | ( | ) | const |
Get the capsule geometry, or nullptr if the contained geometry is not a capsule.
| const Cone* sdf::SDF_VERSION_NAMESPACE::Geometry::ConeShape | ( | ) | const |
Get the cone geometry, or nullptr if the contained geometry is not a cone.
| const Cylinder* sdf::SDF_VERSION_NAMESPACE::Geometry::CylinderShape | ( | ) | const |
Get the cylinder geometry, or nullptr if the contained geometry is not a cylinder.
| sdf::ElementPtr sdf::SDF_VERSION_NAMESPACE::Geometry::Element | ( | ) | const |
| const Ellipsoid* sdf::SDF_VERSION_NAMESPACE::Geometry::EllipsoidShape | ( | ) | const |
Get the ellipsoid geometry, or nullptr if the contained geometry is not an ellipsoid.
| const Heightmap* sdf::SDF_VERSION_NAMESPACE::Geometry::HeightmapShape | ( | ) | const |
Get the heightmap geometry, or nullptr if the contained geometry is not a heightmap.
| Errors sdf::SDF_VERSION_NAMESPACE::Geometry::Load | ( | ElementPtr | _sdf | ) |
| Errors sdf::SDF_VERSION_NAMESPACE::Geometry::Load | ( | sdf::ElementPtr | _sdf, |
| const ParserConfig & | _config | ||
| ) |
| const Mesh* sdf::SDF_VERSION_NAMESPACE::Geometry::MeshShape | ( | ) | const |
Get the mesh geometry, or nullptr if the contained geometry is not a mesh.
| const Plane* sdf::SDF_VERSION_NAMESPACE::Geometry::PlaneShape | ( | ) | const |
Get the plane geometry, or nullptr if the contained geometry is not a plane.
| const std::vector<Polyline>& sdf::SDF_VERSION_NAMESPACE::Geometry::PolylineShape | ( | ) | const |
Get the polyline geometry.
Vector is empty if the contained geometry is not a polyline.
| void sdf::SDF_VERSION_NAMESPACE::Geometry::SetBoxShape | ( | const Box & | _box | ) |
Set the box shape.
| [in] | _box | The box shape. |
| void sdf::SDF_VERSION_NAMESPACE::Geometry::SetCapsuleShape | ( | const Capsule & | _capsule | ) |
Set the capsule shape.
| [in] | _capsule | The capsule shape. |
| void sdf::SDF_VERSION_NAMESPACE::Geometry::SetConeShape | ( | const Cone & | _cone | ) |
Set the cone shape.
| [in] | _cone | The cone shape. |
| void sdf::SDF_VERSION_NAMESPACE::Geometry::SetCylinderShape | ( | const Cylinder & | _cylinder | ) |
Set the cylinder shape.
| [in] | _cylinder | The cylinder shape. |
| void sdf::SDF_VERSION_NAMESPACE::Geometry::SetEllipsoidShape | ( | const Ellipsoid & | _ellipsoid | ) |
Set the ellipsoid shape.
| [in] | _ellipsoid | The ellipsoid shape. |
| void sdf::SDF_VERSION_NAMESPACE::Geometry::SetHeightmapShape | ( | const Heightmap & | _heightmap | ) |
Set the heightmap shape.
| [in] | _heightmap | The heightmap shape. |
| void sdf::SDF_VERSION_NAMESPACE::Geometry::SetMeshShape | ( | const Mesh & | _mesh | ) |
Set the mesh shape.
| [in] | _mesh | The mesh shape. |
| void sdf::SDF_VERSION_NAMESPACE::Geometry::SetPlaneShape | ( | const Plane & | _plane | ) |
Set the plane shape.
| [in] | _plane | The plane shape. |
| void sdf::SDF_VERSION_NAMESPACE::Geometry::SetPolylineShape | ( | const std::vector< Polyline > & | _polyline | ) |
Set the polyline shape.
| [in] | _polyline | The polyline shape. |
| void sdf::SDF_VERSION_NAMESPACE::Geometry::SetSphereShape | ( | const Sphere & | _sphere | ) |
Set the sphere shape.
| [in] | _sphere | The sphere shape. |
| void sdf::SDF_VERSION_NAMESPACE::Geometry::SetType | ( | const GeometryType | _type | ) |
Set the type of geometry.
| [in] | _type | The geometry type. |
| const Sphere* sdf::SDF_VERSION_NAMESPACE::Geometry::SphereShape | ( | ) | const |
Get the sphere geometry, or nullptr if the contained geometry is not a sphere.
| sdf::ElementPtr sdf::SDF_VERSION_NAMESPACE::Geometry::ToElement | ( | ) | const |
| sdf::ElementPtr sdf::SDF_VERSION_NAMESPACE::Geometry::ToElement | ( | sdf::Errors & | _errors | ) | const |
| GeometryType sdf::SDF_VERSION_NAMESPACE::Geometry::Type | ( | ) | const |
Get the type of geometry.