Gazebo Math

API Reference

8.0.0~pre1
Cone< Precision > Class Template Reference

A representation of a cone. More...

#include <gz/math/Cone.hh>

Public Member Functions

 Cone ()=default
 Default constructor. The default radius and length are both zero. The default rotational offset is Quaternion<Precision>::Identity.
 
 Cone (const Precision _length, const Precision _radius, const Material &_mat, const Quaternion< Precision > &_rotOffset=Quaternion< Precision >::Identity)
 Construct a cone with a length, radius, material and optionally a rotational offset.
 
 Cone (const Precision _length, const Precision _radius, const Quaternion< Precision > &_rotOffset=Quaternion< Precision >::Identity)
 Construct a cone with a length, radius, and optionally a rotational offset.
 
Precision DensityFromMass (const Precision _mass) const
 Compute the cone's density given a mass value. The cone is assumed to be solid with uniform density. This function requires the cone's radius and length to be set to values greater than zero. The Material of the cone is ignored.
 
Precision Length () const
 Get the length in meters.
 
std::optional< MassMatrix3< Precision > > MassMatrix () const
 Get the mass matrix for this cone. This function is only meaningful if the cone's radius, length, and material have been set. Optionally, set the rotational offset.
 
bool MassMatrix (MassMatrix3d &_massMat) const
 Get the mass matrix for this cone. This function is only meaningful if the cone's radius, length, and material have been set. Optionally, set the rotational offset.
 
const MaterialMat () const
 Get the material associated with this cone.
 
bool operator== (const Cone &_cone) const
 Check if this cone is equal to the provided cone. Radius, length, and material properties will be checked.
 
Precision Radius () const
 Get the radius in meters.
 
Quaternion< PrecisionRotationalOffset () const
 Get the rotational offset. By default, a cone's length is aligned with the Z axis. The rotational offset encodes a rotation from the z axis.
 
bool SetDensityFromMass (const Precision _mass)
 Set the density of this cone based on a mass value. Density is computed using Precision DensityFromMass(const Precision _mass) const. The cone is assumed to be solid with uniform density. This function requires the cone's radius and length to be set to values greater than zero. The existing Material density value is overwritten only if the return value from this true.
 
void SetLength (const Precision _length)
 Set the length in meters.
 
void SetMat (const Material &_mat)
 Set the material associated with this cone.
 
void SetRadius (const Precision _radius)
 Set the radius in meters.
 
void SetRotationalOffset (const Quaternion< Precision > &_rotOffset)
 Set the rotation offset.
 
Precision Volume () const
 Get the volume of the cone in m^3.
 

Detailed Description

template<typename Precision>
class gz::math::Cone< Precision >

A representation of a cone.

The cone class supports defining a cone with a radius, length, rotational offset, and material properties. Radius and length are in meters. See Material for more on material properties. By default, a cone's length is aligned with the Z axis where the base of the cone is proximal to the origin and vertex points in positive Z. The rotational offset encodes a rotation from the z axis.

Constructor & Destructor Documentation

◆ Cone() [1/3]

template<typename Precision >
Cone ( )
default

Default constructor. The default radius and length are both zero. The default rotational offset is Quaternion<Precision>::Identity.

◆ Cone() [2/3]

template<typename Precision >
Cone ( const Precision  _length,
const Precision  _radius,
const Quaternion< Precision > &  _rotOffset = QuaternionPrecision >::Identity 
)

Construct a cone with a length, radius, and optionally a rotational offset.

Parameters
[in]_lengthLength of the cone.
[in]_radiusRadius of the cone.
[in]_rotOffsetRotational offset of the cone.

◆ Cone() [3/3]

template<typename Precision >
Cone ( const Precision  _length,
const Precision  _radius,
const Material _mat,
const Quaternion< Precision > &  _rotOffset = QuaternionPrecision >::Identity 
)

Construct a cone with a length, radius, material and optionally a rotational offset.

Parameters
[in]_lengthLength of the cone.
[in]_radiusRadius of the cone.
[in]_matMaterial property for the cone.
[in]_rotOffsetRotational offset of the cone.

Member Function Documentation

◆ DensityFromMass()

template<typename Precision >
Precision DensityFromMass ( const Precision  _mass) const

Compute the cone's density given a mass value. The cone is assumed to be solid with uniform density. This function requires the cone's radius and length to be set to values greater than zero. The Material of the cone is ignored.

Parameters
[in]_massMass of the cone, in kg. This value should be greater than zero.
Returns
Density of the cone in kg/m^3. A negative value is returned if radius, length or _mass is <= 0.

◆ Length()

template<typename Precision >
Precision Length ( ) const

Get the length in meters.

Returns
The length of the cone in meters.

◆ MassMatrix() [1/2]

template<typename Precision >
std::optional< MassMatrix3< Precision > > MassMatrix ( ) const

Get the mass matrix for this cone. This function is only meaningful if the cone's radius, length, and material have been set. Optionally, set the rotational offset.

Returns
The computed mass matrix if parameters are valid (radius > 0), (length > 0) and (density > 0). Otherwise std::nullopt is returned.

◆ MassMatrix() [2/2]

template<typename Precision >
bool MassMatrix ( MassMatrix3d _massMat) const

Get the mass matrix for this cone. This function is only meaningful if the cone's radius, length, and material have been set. Optionally, set the rotational offset.

Parameters
[out]_massMatThe computed mass matrix will be stored here.
Returns
False if computation of the mass matrix failed, which could be due to an invalid radius (<=0), length (<=0), or density (<=0).

◆ Mat()

template<typename Precision >
const Material & Mat ( ) const

Get the material associated with this cone.

Returns
The material assigned to this cone

◆ operator==()

template<typename Precision >
bool operator== ( const Cone< Precision > &  _cone) const

Check if this cone is equal to the provided cone. Radius, length, and material properties will be checked.

◆ Radius()

template<typename Precision >
Precision Radius ( ) const

Get the radius in meters.

Returns
The radius of the cone in meters.

◆ RotationalOffset()

template<typename Precision >
Quaternion< Precision > RotationalOffset ( ) const

Get the rotational offset. By default, a cone's length is aligned with the Z axis. The rotational offset encodes a rotation from the z axis.

Returns
The cone's rotational offset.
See also
void SetRotationalOffset(const Quaternion<Precision> &_rot)

◆ SetDensityFromMass()

template<typename Precision >
bool SetDensityFromMass ( const Precision  _mass)

Set the density of this cone based on a mass value. Density is computed using Precision DensityFromMass(const Precision _mass) const. The cone is assumed to be solid with uniform density. This function requires the cone's radius and length to be set to values greater than zero. The existing Material density value is overwritten only if the return value from this true.

Parameters
[in]_massMass of the cone, in kg. This value should be greater than zero.
Returns
True if the density was set. False is returned if the cone's radius, length, or the _mass value are <= 0.
See also
Precision DensityFromMass(const Precision _mass) const

◆ SetLength()

template<typename Precision >
void SetLength ( const Precision  _length)

Set the length in meters.

Parameters
[in]_lengthThe length of the cone in meters.

◆ SetMat()

template<typename Precision >
void SetMat ( const Material _mat)

Set the material associated with this cone.

Parameters
[in]_matThe material assigned to this cone

◆ SetRadius()

template<typename Precision >
void SetRadius ( const Precision  _radius)

Set the radius in meters.

Parameters
[in]_radiusThe radius of the cone in meters.

◆ SetRotationalOffset()

template<typename Precision >
void SetRotationalOffset ( const Quaternion< Precision > &  _rotOffset)

Set the rotation offset.

Parameters
[in]_rotOffsetrotational offset quaternion. See Quaternion<Precision> RotationalOffset() for details on the rotational offset.
See also
Quaternion<Precision> RotationalOffset() const

◆ Volume()

template<typename Precision >
Precision Volume ( ) const

Get the volume of the cone in m^3.

Returns
Volume of the cone in m^3.

The documentation for this class was generated from the following file: