Public Types | Public Member Functions | Static Public Member Functions | Private Attributes
ecl::Angle< T, enable_if< is_float< T > >::type > Class Template Reference

Interface for angular measurements. More...

#include <angle.hpp>

List of all members.

Public Types

typedef
ecl::linear_algebra::Matrix< T, 2, 2 > 
RotationMatrix

Public Member Functions

 Angle (const T &angle=0.0)
 Constructs an angle in radians.
 Angle (const RotationMatrix &rotation)
 Construct from a 2x2 rotation matrix.
degrees ()
 Returns the value of the angle in unit degrees.
 operator const T & () const
 Convenient equivalence to the c/c++ float type.
Angle< T > operator* (const T &scalar) const
 Multiplier.
void operator*= (const T &scalar)
 Multiplier that works on this instance.
Angle< T > operator+ (const T &angle) const
 Sum operator.
Angle< T > operator+ (const Angle< T > &angle) const
 Sum operator.
void operator+= (const T &angle)
 Sum operator that works on this instance.
void operator+= (const Angle< T > &angle)
 Sum operator that works on this instance.
Angle< T > operator- (const T &angle) const
 Difference operator.
Angle< T > operator- (const Angle< T > &angle) const
 Difference operator.
void operator-= (const T &angle)
 Difference operator that works on this instance.
void operator-= (const Angle< T > &angle)
 Difference operator that works on this instance.
const Angle< T > & operator= (const T &angle)
 Allow assignment from float types.
RotationMatrix rotationMatrix () const
 Convert to a 2x2 rotation matrix.

Static Public Member Functions

static Angle< T > Degrees (const T &angle)
 Generates an angle instance from an angle in degrees.
static Angle< T > Radians (const T &angle)
 Generates an angle instance from an angle in radians.

Private Attributes

value

Detailed Description

template<typename T>
class ecl::Angle< T, enable_if< is_float< T > >::type >

Interface for angular measurements.

This is a simple interface designed for scientific calculations (thus the default format is in radians). It allows free interaction with float types, does automatic wrapping on [-pi, pi] under the hood and provides some generic methods for conversions and wrapping on plain double types.

Template Parameters:
T: must be a float type (e.g. float, double, float32, float64)

Definition at line 136 of file angle.hpp.


Member Typedef Documentation

template<typename T >
typedef ecl::linear_algebra::Matrix<T,2,2> ecl::Angle< T, enable_if< is_float< T > >::type >::RotationMatrix

Definition at line 141 of file angle.hpp.


Constructor & Destructor Documentation

template<typename T >
ecl::Angle< T, enable_if< is_float< T > >::type >::Angle ( const T &  angle = 0.0) [inline]

Constructs an angle in radians.

Configures the angle from the input double value. Automatically wraps this value if it doesn't fall within [-pi,pi].

Parameters:
angle: input angle (radians).

Definition at line 150 of file angle.hpp.

template<typename T >
ecl::Angle< T, enable_if< is_float< T > >::type >::Angle ( const RotationMatrix rotation) [inline]

Construct from a 2x2 rotation matrix.

Parameters:
rotation: input rotation matrix.

Definition at line 155 of file angle.hpp.


Member Function Documentation

template<typename T >
T ecl::Angle< T, enable_if< is_float< T > >::type >::degrees ( )

Returns the value of the angle in unit degrees.

This does not change the internal formatting for the angle (which is in radians). It simply returns its equivalent in unit degrees. The returned value will be wrapped on [-180, 180].

Returns:
T : the angle in degrees.
template<typename T >
static Angle<T> ecl::Angle< T, enable_if< is_float< T > >::type >::Degrees ( const T &  angle) [static]

Generates an angle instance from an angle in degrees.

Generates an angle specified in degrees as a double to a fully constructed Angle instance.

 Angle angle = Angle::Degrees(45);
Parameters:
angle: the angle (degrees).
Returns:
Angle : the constructed instance.
template<typename T >
ecl::Angle< T, enable_if< is_float< T > >::type >::operator const T & ( ) const [inline]

Convenient equivalence to the c/c++ float type.

Allows for easy manipulation, especially within calculations. This breaks the rule which dictates that we should never use them as they create uncertainty about an object. Here it's just ridiculously convenient and more to the point, intuitive, so we do so.

Definition at line 270 of file angle.hpp.

template<typename T >
Angle<T> ecl::Angle< T, enable_if< is_float< T > >::type >::operator* ( const T &  scalar) const

Multiplier.

Note this also ensures the angle is wrapped.

Parameters:
scalar: scalar multipler to apply.
Returns:
Angle : the wrapped angle instance.
template<typename T >
void ecl::Angle< T, enable_if< is_float< T > >::type >::operator*= ( const T &  scalar)

Multiplier that works on this instance.

Note this also ensures the angle is wrapped.

Parameters:
scalar: scalar multipler to apply.
template<typename T >
Angle<T> ecl::Angle< T, enable_if< is_float< T > >::type >::operator+ ( const T &  angle) const

Sum operator.

Note this also ensures the angle is wrapped.

Parameters:
angle: angle to add (radians).
Returns:
Angle : the wrapped angle instance.
template<typename T >
Angle<T> ecl::Angle< T, enable_if< is_float< T > >::type >::operator+ ( const Angle< T > &  angle) const

Sum operator.

Note this also ensures the angle is wrapped.

Parameters:
angle: angle to add (radians).
Returns:
Angle : the wrapped angle instance.
template<typename T >
void ecl::Angle< T, enable_if< is_float< T > >::type >::operator+= ( const T &  angle)

Sum operator that works on this instance.

Note this also ensures the angle is wrapped.

Parameters:
angle: angle to add (radians).
template<typename T >
void ecl::Angle< T, enable_if< is_float< T > >::type >::operator+= ( const Angle< T > &  angle)

Sum operator that works on this instance.

Note this also ensures the angle is wrapped.

Parameters:
angle: angle to add (radians).
template<typename T >
Angle<T> ecl::Angle< T, enable_if< is_float< T > >::type >::operator- ( const T &  angle) const

Difference operator.

Note this also ensures the angle is wrapped.

Parameters:
angle: angle to subtract (radians).
Returns:
Angle : the wrapped angle instance.
template<typename T >
Angle<T> ecl::Angle< T, enable_if< is_float< T > >::type >::operator- ( const Angle< T > &  angle) const

Difference operator.

Note this also ensures the angle is wrapped.

Parameters:
angle: angle to subtract (radians).
Returns:
Angle : the wrapped angle instance.
template<typename T >
void ecl::Angle< T, enable_if< is_float< T > >::type >::operator-= ( const T &  angle)

Difference operator that works on this instance.

Note this also ensures the angle is wrapped.

Parameters:
angle: angle to subtract (radians).
template<typename T >
void ecl::Angle< T, enable_if< is_float< T > >::type >::operator-= ( const Angle< T > &  angle)

Difference operator that works on this instance.

Note this also ensures the angle is wrapped.

Parameters:
angle: angle to subtract (radians).
template<typename T >
const Angle<T>& ecl::Angle< T, enable_if< is_float< T > >::type >::operator= ( const T &  angle)

Allow assignment from float types.

This allows convenient assignment from float types. It does automatic wrapping on the input value.

Parameters:
angle: input angle (radians).
Returns:
Angle : the wrapped angle instance.
template<typename T >
static Angle<T> ecl::Angle< T, enable_if< is_float< T > >::type >::Radians ( const T &  angle) [static]

Generates an angle instance from an angle in radians.

Generates an angle specified in radians as a double to a fully constructed Angle instance.

 Angle angle = Angle::Radians(ecl::math::pi);
Parameters:
angle: the angle (radians).
Returns:
Angle : the constructed instance.
template<typename T >
RotationMatrix ecl::Angle< T, enable_if< is_float< T > >::type >::rotationMatrix ( ) const [inline]

Convert to a 2x2 rotation matrix.

Returns:
RotationMatrix : representation as a 2x2 rotation matrix.

Definition at line 287 of file angle.hpp.


Member Data Documentation

template<typename T >
T ecl::Angle< T, enable_if< is_float< T > >::type >::value [private]

Definition at line 323 of file angle.hpp.


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


ecl_geometry
Author(s): Daniel Stonier
autogenerated on Thu Jun 6 2019 21:17:52