A CRTP interface to any measurement.
More...
#include <measurement_interface.hpp>
|
auto & | state () |
| Get measurement as a state vector. More...
|
|
const auto & | state () const |
| Get measurement as a state vector. More...
|
|
auto & | covariance () |
| Get covariance of the measurement as a matrix. More...
|
|
const auto & | covariance () const |
|
template<typename OtherStateT > |
auto | create_new_instance_from (const OtherStateT &other_state) const |
| Create a new instance of the measurement from another state. More...
|
|
template<typename OtherStateT > |
OtherStateT | map_into (const OtherStateT &other_state) const |
| Map this measurement into another state space. More...
|
|
template<typename OtherStateT > |
auto | mapping_matrix_from (const OtherStateT &other_state) const |
| Get a matrix that maps a state to this measurement's state space. More...
|
|
|
const Derived & | impl () const |
|
Derived & | impl () |
|
template<typename Derived>
struct autoware::common::state_estimation::MeasurementInterface< Derived >
A CRTP interface to any measurement.
- Template Parameters
-
Derived | Derived class that is expected to inherit from this class. |
◆ covariance() [1/2]
template<typename Derived >
Get covariance of the measurement as a matrix.
◆ covariance() [2/2]
template<typename Derived >
◆ create_new_instance_from()
template<typename Derived >
template<typename OtherStateT >
Create a new instance of the measurement from another state.
- Note
- While it might seem like this function could be static, it is explicitly not static to allow for future implementation to cache some internal workspace required for this computation along with the mapping matrix computation. To allow these optimized implementation to be a drop-in replacement for the naive implementations, this function is not static.
- Parameters
-
[in] | other_state | The other state. |
- Template Parameters
-
OtherStateT | Type of the other state. |
- Returns
- Return a state that is a mapping of the OtherStateT to this measurement's state.
◆ map_into()
template<typename Derived >
template<typename OtherStateT >
Map this measurement into another state space.
- Note
- It is implementation defined, but the other_state values are usually maintained for all variables not updated through this mapping. Please see the concrete implementation documentation when in doubt.
- Parameters
-
[in] | other_state | The other state. |
- Template Parameters
-
OtherStateT | Type of the other state. |
- Returns
- An instance of OtherStateT with updated variables observed by this measurement.
◆ mapping_matrix_from()
template<typename Derived >
template<typename OtherStateT >
Get a matrix that maps a state to this measurement's state space.
For a measurement of dimensionality M the resulting matrix converts a state vector of type OtherStateT (of dimensionality N) to a state vector of this measurement (of dimensionality M). This matrix is, generally speaking, the Jacobian of a mapping function h, such as mapped_state = h(other_state), implemented in create_new_instance_from.
- Parameters
-
[in] | other_state | The other state to be converted into the measurement state space. |
- Template Parameters
-
OtherStateT | Type of the other state. |
- Returns
- Returns a mapping matrix that maps from OtherStateT to this measurement's state.
◆ state() [1/2]
template<typename Derived >
Get measurement as a state vector.
◆ state() [2/2]
template<typename Derived >
Get measurement as a state vector.
The documentation for this struct was generated from the following file: