A representation of a generic state vectors with specified variables.
More...
#include <generic_state.hpp>
|
| using | Variables = std::tuple< VariableTs... > |
| |
| using | Vector = Eigen::Matrix< ScalarT, kSize, 1 > |
| |
| using | Matrix = Eigen::Matrix< ScalarT, kSize, kSize > |
| |
| using | Scalar = ScalarT |
| |
|
| | GenericState ()=default |
| | Default constructor. More...
|
| |
| | GenericState (const Vector &vector) |
| | Constructs a new instance from an Eigen vector. More...
|
| |
| Vector & | vector () noexcept |
| | Get underlying Eigen vector. More...
|
| |
| const Vector & | vector () 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...
|
| |
|
| 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...
|
| |
template<typename ScalarT, typename ... VariableTs>
class autoware::prediction::GenericState< ScalarT, VariableTs >
A representation of a generic state vectors with specified variables.
- Template Parameters
-
| VariableTs | Variables which this state consists of. |
◆ Matrix
template<typename ScalarT , typename ... VariableTs>
◆ Scalar
template<typename ScalarT , typename ... VariableTs>
◆ Variables
template<typename ScalarT , typename ... VariableTs>
◆ Vector
template<typename ScalarT , typename ... VariableTs>
◆ GenericState() [1/2]
template<typename ScalarT , typename ... VariableTs>
◆ GenericState() [2/2]
template<typename ScalarT , typename ... VariableTs>
Constructs a new instance from an Eigen vector.
- Parameters
-
| [in] | vector | An Eigen vector. |
◆ at() [1/4]
template<typename ScalarT , typename ... VariableTs>
template<typename VariableT >
Get vector element at a given variable.
- Template Parameters
-
| VariableT | A variable from the state. |
- Returns
- A reference to the element representing this variable.
◆ at() [2/4]
template<typename ScalarT , typename ... VariableTs>
template<typename VariableT >
Get vector element at a given variable.
- Template Parameters
-
| VariableT | A variable from the state. |
- Returns
- A reference to the element representing this variable.
◆ at() [3/4]
template<typename ScalarT , typename ... VariableTs>
template<typename VariableT >
Get vector element at a given variable.
- Template Parameters
-
| VariableT | A variable from the state. |
- Returns
- A reference to the element representing this variable.
◆ at() [4/4]
template<typename ScalarT , typename ... VariableTs>
template<typename VariableT >
Get vector element at a given variable.
- Template Parameters
-
| VariableT | A variable from the state. |
- Returns
- A reference to the element representing this variable.
◆ copy_into()
template<typename ScalarT , typename ... VariableTs>
template<typename OtherStateT >
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.
This function can be used in a couple different situations:
- when a smaller current state must be copied into a bigger other state,
overwriting some of that bigger state's variables;
- when a reduction of the current state onto a smaller state is required;
- when a rearrangement of the variables is needed.
Please see tests for examples of usage.
- Note
- This function only is correctly compiled if either StateT is a subset of OtherStateT, or OtherStateT is a subset of the StateT. Otherwise, a compilation error will be issued.
- Parameters
-
| [in] | other_state | Other state. |
- Template Parameters
-
| OtherStateT | Type of the other state. |
- Returns
- The updated other state.
◆ index_of()
template<typename ScalarT , typename ... VariableTs>
template<typename VariableT >
|
|
inlinestaticconstexprnoexcept |
Get an index of the variable in the state.
- Template Parameters
-
| VariableT | A variable from the state. |
- Returns
- An index of the given variable in the state vector.
◆ operator[]() [1/2]
template<typename ScalarT , typename ... VariableTs>
Get an element of the vector.
- Parameters
-
| [in] | idx | The index of the vector element. |
- Returns
- A reference to the vector element.
◆ operator[]() [2/2]
template<typename ScalarT , typename ... VariableTs>
Get an element of the vector.
- Parameters
-
| [in] | idx | The index of the vector element. |
- Returns
- A reference to the vector element.
◆ size()
template<typename ScalarT , typename ... VariableTs>
|
|
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>
|
|
inlinestaticconstexprnoexcept |
Get a variables tuple used for iteration over all variables.
◆ vector() [1/2]
template<typename ScalarT , typename ... VariableTs>
Get underlying Eigen vector.
- Returns
- A const reference to the underlying Eigen vector.
◆ vector() [2/2]
template<typename ScalarT , typename ... VariableTs>
Get underlying Eigen vector.
- Returns
- A reference to the underlying Eigen vector.
◆ 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 |
The documentation for this class was generated from the following file: