Gazebo Math

API Reference

7.4.0
PiecewiseScalarField3< ScalarField3T, ScalarT > Class Template Reference

The PiecewiseScalarField3 class constructs a scalar field F in R^3 as a union of scalar fields Pn, defined over regions Rn i.e. piecewise. More...

#include <gz/math/PiecewiseScalarField3.hh>

Classes

struct  Piece
 A scalar field P in R^3 and the region R in which it is defined. More...
 

Public Member Functions

 PiecewiseScalarField3 ()=default
 Constructor. More...
 
 PiecewiseScalarField3 (const std::vector< Piece > &_pieces)
 Constructor. More...
 
ScalarT Evaluate (const Vector3< ScalarT > &_p) const
 Evaluate the piecewise scalar field at _p More...
 
ScalarT Minimum () const
 Compute the piecewise scalar field minimum. More...
 
ScalarT Minimum (Vector3< ScalarT > &_pMin) const
 Compute the piecewise scalar field minimum Note that, since this method computes the minimum for each region independently, it implicitly assumes continuity in the boundaries between regions, if any. More...
 
ScalarT operator() (const Vector3< ScalarT > &_p) const
 Call operator overload. More...
 

Static Public Member Functions

static PiecewiseScalarField3 Throughout (ScalarField3T _field)
 Define piecewise scalar field as _field throughout R^3 space. More...
 

Detailed Description

template<typename ScalarField3T, typename ScalarT>
class gz::math::PiecewiseScalarField3< ScalarField3T, ScalarT >

The PiecewiseScalarField3 class constructs a scalar field F in R^3 as a union of scalar fields Pn, defined over regions Rn i.e. piecewise.

Template Parameters
ScalarField3Ta callable type taking a single Vector3<ScalarT> value as argument and returning a ScalarT value. Additionally:
  • for PiecewiseScalarField3 to have a stream operator overload, ScalarField3T must support stream operator overload;
  • for PiecewiseScalarField3::Minimum to be callable, ScalarField3T must implement a ScalarT Minimum(const Region3<ScalarT> &, Vector3<ScalarT> &) method that computes its minimum in the given region and returns an argument value that yields said minimum.
ScalarTa numeric type for which std::numeric_limits<> traits have been specialized.

Example

#include <iostream>
int main(int argc, char **argv)
{
const double kConstant = 1.;
gz::math::Vector4d(0., 1., 0., 1.));
gz::math::Vector4d(1., 0., 1., 0.));
gz::math::Vector4d(1., 0., 0., -1.));
using AdditivelySeparableScalarField3dT =
using PiecewiseScalarField3dT =
AdditivelySeparableScalarField3dT>;
const PiecewiseScalarField3dT scalarField({
{gz::math::Region3d( // x < 0 halfspace
AdditivelySeparableScalarField3dT(
kConstant, xPoly, yPoly, zPoly)},
{gz::math::Region3d( // x >= 0 halfspace
AdditivelySeparableScalarField3dT(
-kConstant, xPoly, yPoly, zPoly)}});
// A printable piecewise scalar field.
std::cout << "A piecewise scalar field in R^3 is made up of "
<< "several pieces e.g. P(x, y, z) = "
<< scalarField << std::endl;
// A piecewise scalar field can be evaluated.
std::cout << "Evaluating P(x, y, z) at (1, 0, 0) yields "
<< scalarField(gz::math::Vector3d::UnitX)
std::cout << "Evaluating P(x, y, z) at (-1, 0, 0) yields "
<< scalarField(-gz::math::Vector3d::UnitX)
// A piecewise scalar field can be queried for its minimum
// (provided the underlying scalar function allows it).
std::cout << "The global minimum of P(x, y, z) is "
<< scalarField.Minimum() << std::endl;
}

Constructor & Destructor Documentation

◆ PiecewiseScalarField3() [1/2]

PiecewiseScalarField3 ( )
default

Constructor.

◆ PiecewiseScalarField3() [2/2]

PiecewiseScalarField3 ( const std::vector< Piece > &  _pieces)
inlineexplicit

Constructor.

Parameters
[in]_piecesscalar fields Pn and the regions Rn in which these are defined. Regions should not overlap.

References std::endl().

Member Function Documentation

◆ Evaluate()

ScalarT Evaluate ( const Vector3< ScalarT > &  _p) const
inline

Evaluate the piecewise scalar field at _p

Parameters
[in]_ppiecewise scalar field argument
Returns
the result of evaluating F(_p), or NaN if the scalar field is not defined at _p

References std::find_if(), and numeric_limits::quiet_NaN().

Referenced by PiecewiseScalarField3< ScalarField3T, ScalarT >::operator()().

◆ Minimum() [1/2]

ScalarT Minimum ( ) const
inline

Compute the piecewise scalar field minimum.

Returns
the scalar field minimum, or NaN if the scalar field is not defined anywhere (i.e. default constructed)

◆ Minimum() [2/2]

ScalarT Minimum ( Vector3< ScalarT > &  _pMin) const
inline

Compute the piecewise scalar field minimum Note that, since this method computes the minimum for each region independently, it implicitly assumes continuity in the boundaries between regions, if any.

Parameters
[out]_pMinscalar field argument that yields the minimum, or NaN if the scalar field is not defined anywhere (i.e. default constructed)
Returns
the scalar field minimum, or NaN if the scalar field is not defined anywhere (i.e. default constructed)

References numeric_limits::infinity(), and numeric_limits::quiet_NaN().

◆ operator()()

ScalarT operator() ( const Vector3< ScalarT > &  _p) const
inline

Call operator overload.

See also
PiecewiseScalarField3::Evaluate()
Parameters
[in]_ppiecewise scalar field argument
Returns
the result of evaluating F(_p), or NaN if the scalar field is not defined at _p

References PiecewiseScalarField3< ScalarField3T, ScalarT >::Evaluate().

◆ Throughout()

static PiecewiseScalarField3 Throughout ( ScalarField3T  _field)
inlinestatic

Define piecewise scalar field as _field throughout R^3 space.

Parameters
[in]_fielda scalar field in R^3
Returns
_field as a piecewise scalar field

References std::move().


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