Autoware.Auto
autoware::common::state_vector::GenericState< ScalarT, VariableTs > Class Template Reference

A representation of a generic state vectors with specified variables. More...

#include <generic_state.hpp>

Public Types

using Variables = std::tuple< VariableTs... >
 
using Vector = Eigen::Matrix< ScalarT, kSize, 1 >
 
using Matrix = Eigen::Matrix< ScalarT, kSize, kSize >
 
using Scalar = ScalarT
 

Public Member Functions

 GenericState ()=default
 Default constructor. More...
 
 GenericState (const Vector &vector)
 Constructs a new instance from an Eigen vector. More...
 
Vectorvector () noexcept
 Get underlying Eigen vector. More...
 
const Vectorvector () const noexcept
 Get underlying Eigen vector. More...
 
ScalarT & operator[] (const Eigen::Index idx)
 Get an element of the vector. More...
 
const ScalarT & operator[] (const Eigen::Index idx) const
 Get an element of the vector. More...
 
template<typename VariableT >
ScalarT & at () noexcept
 Get vector element at a given variable. More...
 
template<typename VariableT >
ScalarT & at (const VariableT) noexcept
 Get vector element at a given variable. More...
 
template<typename VariableT >
const ScalarT & at () const noexcept
 Get vector element at a given variable. More...
 
template<typename VariableT >
const ScalarT & at (const VariableT) const noexcept
 Get vector element at a given variable. More...
 
template<typename OtherStateT >
OtherStateT copy_into (OtherStateT other_state=OtherStateT{}) const noexcept
 Copy values of this state into another state. More...
 
GenericStateoperator+= (const GenericState &rhs) noexcept
 Addition assignment operator. More...
 
GenericStateoperator+= (const Vector &rhs) noexcept
 Addition assignment operator. More...
 
GenericStateoperator-= (const GenericState &rhs) noexcept
 Subtraction assignment operator. More...
 
GenericStateoperator-= (const Vector &rhs) noexcept
 Subtraction assignment operator. More...
 
constexpr void wrap_all_angles () noexcept
 Wrap all variables that represent angles using the common::helper_functions::wrap_angle. More...
 
template<typename NewScalarT >
GenericState< NewScalarT, VariableTs... > cast () const noexcept
 Cast to another scalar type. More...
 

Static Public Member Functions

template<typename VariableT >
constexpr static Eigen::Index index_of () noexcept
 Get an index of the variable in the state. More...
 
constexpr static Eigen::Index size () noexcept
 Get the size of the state. More...
 
constexpr static Variables variables () noexcept
 Get a variables tuple used for iteration over all variables. More...
 

Friends

constexpr friend bool operator== (const GenericState &lhs, const GenericState &rhs)
 An equality operator. More...
 
std::ostream & operator<< (std::ostream &out, const GenericState &state)
 Allow using << operator with this class. More...
 
template<typename T >
GenericState operator- (GenericState lhs, const T &rhs) noexcept
 Subtraction operator. More...
 
template<typename T >
GenericState operator+ (GenericState lhs, const T &rhs) noexcept
 Addition operator. More...
 
constexpr friend GenericState wrap_all_angles (GenericState state) noexcept
 Wrap all variables that represent angles using the common::helper_functions::wrap_angle. More...
 

Detailed Description

template<typename ScalarT, typename ... VariableTs>
class autoware::common::state_vector::GenericState< ScalarT, VariableTs >

A representation of a generic state vectors with specified variables.

Template Parameters
VariableTsVariables which this state consists of.

Member Typedef Documentation

◆ Matrix

template<typename ScalarT , typename ... VariableTs>
using autoware::common::state_vector::GenericState< ScalarT, VariableTs >::Matrix = Eigen::Matrix<ScalarT, kSize, kSize>

◆ Scalar

template<typename ScalarT , typename ... VariableTs>
using autoware::common::state_vector::GenericState< ScalarT, VariableTs >::Scalar = ScalarT

◆ Variables

template<typename ScalarT , typename ... VariableTs>
using autoware::common::state_vector::GenericState< ScalarT, VariableTs >::Variables = std::tuple<VariableTs...>

◆ Vector

template<typename ScalarT , typename ... VariableTs>
using autoware::common::state_vector::GenericState< ScalarT, VariableTs >::Vector = Eigen::Matrix<ScalarT, kSize, 1>

Constructor & Destructor Documentation

◆ GenericState() [1/2]

template<typename ScalarT , typename ... VariableTs>
autoware::common::state_vector::GenericState< ScalarT, VariableTs >::GenericState ( )
default

Default constructor.

◆ GenericState() [2/2]

template<typename ScalarT , typename ... VariableTs>
autoware::common::state_vector::GenericState< ScalarT, VariableTs >::GenericState ( const Vector vector)
inlineexplicit

Constructs a new instance from an Eigen vector.

Parameters
[in]vectorAn Eigen vector.

Member Function Documentation

◆ at() [1/4]

template<typename ScalarT , typename ... VariableTs>
template<typename VariableT >
const ScalarT& autoware::common::state_vector::GenericState< ScalarT, VariableTs >::at ( ) const
inlinenoexcept

Get vector element at a given variable.

Template Parameters
VariableTA variable from the state.
Returns
A reference to the element representing this variable.

◆ at() [2/4]

template<typename ScalarT , typename ... VariableTs>
template<typename VariableT >
ScalarT& autoware::common::state_vector::GenericState< ScalarT, VariableTs >::at ( )
inlinenoexcept

Get vector element at a given variable.

Template Parameters
VariableTA variable from the state.
Returns
A reference to the element representing this variable.

◆ at() [3/4]

template<typename ScalarT , typename ... VariableTs>
template<typename VariableT >
const ScalarT& autoware::common::state_vector::GenericState< ScalarT, VariableTs >::at ( const  VariableT) const
inlinenoexcept

Get vector element at a given variable.

Template Parameters
VariableTA variable from the state.
Returns
A reference to the element representing this variable.

◆ at() [4/4]

template<typename ScalarT , typename ... VariableTs>
template<typename VariableT >
ScalarT& autoware::common::state_vector::GenericState< ScalarT, VariableTs >::at ( const  VariableT)
inlinenoexcept

Get vector element at a given variable.

Template Parameters
VariableTA variable from the state.
Returns
A reference to the element representing this variable.

◆ cast()

template<typename ScalarT , typename ... VariableTs>
template<typename NewScalarT >
GenericState<NewScalarT, VariableTs...> autoware::common::state_vector::GenericState< ScalarT, VariableTs >::cast ( ) const
inlinenoexcept

Cast to another scalar type.

Returns
The state with a different scalar type.

◆ copy_into()

template<typename ScalarT , typename ... VariableTs>
template<typename OtherStateT >
OtherStateT autoware::common::state_vector::GenericState< ScalarT, VariableTs >::copy_into ( OtherStateT  other_state = OtherStateT{}) const
inlinenoexcept

Copy values of this state into another state.

This function copies (a subset of) variables from the current state into another state. If other_state is provided, it is used as a "donor" state, i.e., the values already in this other_state are unchanged unless overwritten by the ones present in the current state. If no other_state is given, a new zero-initialized instance of OtherStateT will be created and this state will be used for the further update using the variables from the current state. Please see tests for examples of usage.

Note
This function also handles a rearrangement of the variables if the OtherStateT has the variables in a different order from the current state.
This function copies only variables that are present in both states. It silently does nothing if there are no common variables between the states.
Parameters
[in]other_stateOther state.
Template Parameters
OtherStateTType of the other state.
Returns
The updated other state.

◆ index_of()

template<typename ScalarT , typename ... VariableTs>
template<typename VariableT >
constexpr static Eigen::Index autoware::common::state_vector::GenericState< ScalarT, VariableTs >::index_of ( )
inlinestaticconstexprnoexcept

Get an index of the variable in the state.

Template Parameters
VariableTA variable from the state.
Returns
An index of the given variable in the state vector.

◆ operator+=() [1/2]

template<typename ScalarT , typename ... VariableTs>
GenericState& autoware::common::state_vector::GenericState< ScalarT, VariableTs >::operator+= ( const GenericState< ScalarT, VariableTs > &  rhs)
inlinenoexcept

Addition assignment operator.

Parameters
[in]rhsOther state vector
Returns
A reference to this state.

◆ operator+=() [2/2]

template<typename ScalarT , typename ... VariableTs>
GenericState& autoware::common::state_vector::GenericState< ScalarT, VariableTs >::operator+= ( const Vector rhs)
inlinenoexcept

Addition assignment operator.

Parameters
[in]rhsOther state vector as an Eigen vector.
Warning
This can be unsafe if the order of the variables in the Eigen vector is different from the one used within this state class.
Returns
A reference to this state.

◆ operator-=() [1/2]

template<typename ScalarT , typename ... VariableTs>
GenericState& autoware::common::state_vector::GenericState< ScalarT, VariableTs >::operator-= ( const GenericState< ScalarT, VariableTs > &  rhs)
inlinenoexcept

Subtraction assignment operator.

Parameters
[in]rhsOther state vector as an Eigen vector.
Returns
A reference to this state.

◆ operator-=() [2/2]

template<typename ScalarT , typename ... VariableTs>
GenericState& autoware::common::state_vector::GenericState< ScalarT, VariableTs >::operator-= ( const Vector rhs)
inlinenoexcept

Subtraction assignment operator.

Parameters
[in]rhsOther state vector as an Eigen vector.
Warning
This can be unsafe if the order of the variables in the Eigen vector is different from the one used within this state class.
Returns
A reference to this state.

◆ operator[]() [1/2]

template<typename ScalarT , typename ... VariableTs>
ScalarT& autoware::common::state_vector::GenericState< ScalarT, VariableTs >::operator[] ( const Eigen::Index  idx)
inline

Get an element of the vector.

Parameters
[in]idxThe index of the vector element.
Returns
A reference to the vector element.

◆ operator[]() [2/2]

template<typename ScalarT , typename ... VariableTs>
const ScalarT& autoware::common::state_vector::GenericState< ScalarT, VariableTs >::operator[] ( const Eigen::Index  idx) const
inline

Get an element of the vector.

Parameters
[in]idxThe index of the vector element.
Returns
A reference to the vector element.

◆ size()

template<typename ScalarT , typename ... VariableTs>
constexpr static Eigen::Index autoware::common::state_vector::GenericState< ScalarT, VariableTs >::size ( )
inlinestaticconstexprnoexcept

Get the size of the state.

Note
This can also be called on an instance of the state.
Returns
Number of variables in this state.

◆ variables()

template<typename ScalarT , typename ... VariableTs>
constexpr static Variables autoware::common::state_vector::GenericState< ScalarT, VariableTs >::variables ( )
inlinestaticconstexprnoexcept

Get a variables tuple used for iteration over all variables.

◆ vector() [1/2]

template<typename ScalarT , typename ... VariableTs>
const Vector& autoware::common::state_vector::GenericState< ScalarT, VariableTs >::vector ( ) const
inlinenoexcept

Get underlying Eigen vector.

Returns
A const reference to the underlying Eigen vector.

◆ vector() [2/2]

template<typename ScalarT , typename ... VariableTs>
Vector& autoware::common::state_vector::GenericState< ScalarT, VariableTs >::vector ( )
inlinenoexcept

Get underlying Eigen vector.

Returns
A reference to the underlying Eigen vector.

◆ wrap_all_angles()

template<typename ScalarT , typename ... VariableTs>
constexpr void autoware::common::state_vector::GenericState< ScalarT, VariableTs >::wrap_all_angles ( )
inlineconstexprnoexcept

Wrap all variables that represent angles using the common::helper_functions::wrap_angle.

Friends And Related Function Documentation

◆ operator+

template<typename ScalarT , typename ... VariableTs>
template<typename T >
GenericState operator+ ( GenericState< ScalarT, VariableTs >  lhs,
const T &  rhs 
)
friend

Addition operator.

Parameters
[in]lhsLeft hand side of the addition.
[in]rhsRight hand side of the addition.
Template Parameters
TEither a state vector type or an underlying Eigen vector type.
Returns
A state that results from this operation.

◆ operator-

template<typename ScalarT , typename ... VariableTs>
template<typename T >
GenericState operator- ( GenericState< ScalarT, VariableTs >  lhs,
const T &  rhs 
)
friend

Subtraction operator.

Parameters
[in]lhsLeft hand side of the subtraction.
[in]rhsRight hand side of the subtraction.
Template Parameters
TEither a state vector type or an underlying Eigen vector type.
Returns
A state that results from this operation.

◆ operator<<

template<typename ScalarT , typename ... VariableTs>
std::ostream& operator<< ( std::ostream &  out,
const GenericState< ScalarT, VariableTs > &  state 
)
friend

Allow using << operator with this class.

        This function adds the variables to the output stream along with their names. 

◆ operator==

template<typename ScalarT , typename ... VariableTs>
constexpr friend bool operator== ( const GenericState< ScalarT, VariableTs > &  lhs,
const GenericState< ScalarT, VariableTs > &  rhs 
)
friend

An equality operator.

◆ wrap_all_angles

template<typename ScalarT , typename ... VariableTs>
constexpr friend GenericState wrap_all_angles ( GenericState< ScalarT, VariableTs >  state)
friend

Wrap all variables that represent angles using the common::helper_functions::wrap_angle.


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