Go to the documentation of this file.
18 #ifndef MEASUREMENT__LINEAR_MEASUREMENT_HPP_
19 #define MEASUREMENT__LINEAR_MEASUREMENT_HPP_
43 template<
typename StateT>
47 template<
typename OtherStateT>
48 using MappingMatrixFrom =
49 Eigen::Matrix<
typename StateT::Scalar, StateT::size(), OtherStateT::size()>;
62 const typename StateT::Vector & measurement,
63 const typename StateT::Vector & variances)
64 : m_measurement{measurement},
65 m_variances{variances},
66 m_covariance{variances.array().square().matrix().asDiagonal()} {}
73 inline StateT &
crtp_state() noexcept {
return m_measurement;}
75 inline const StateT &
crtp_state() const noexcept {
return m_measurement;}
77 inline typename StateT::Vector &
crtp_variances() noexcept {
return m_variances;}
79 inline const typename StateT::Vector &
crtp_variances() const noexcept {
return m_variances;}
81 inline typename StateT::Matrix &
crtp_covariance() noexcept {
return m_covariance;}
83 inline const typename StateT::Matrix &
crtp_covariance() const noexcept {
return m_covariance;}
100 template<
typename OtherStateT>
103 return other_state.template copy_into<StateT>();
116 template<
typename OtherStateT>
119 return m_measurement.copy_into(other_state);
135 template<
typename OtherStateT>
138 MappingMatrixFrom<OtherStateT>
m{MappingMatrixFrom<OtherStateT>::Zero()};
139 auto fill_mapping_matrix = [&
m,
this](
auto variable) {
140 using VariableT = std::decay_t<decltype(variable)>;
141 constexpr
auto index_in_this_state = StateT::template index_of<VariableT>();
142 constexpr
auto index_in_other_state = OtherStateT::template index_of<VariableT>();
143 m(index_in_this_state, index_in_other_state) = 1;
158 StateT m_measurement{};
160 typename StateT::Vector m_variances{StateT::Vector::Zero()};
162 typename StateT::Matrix m_covariance{StateT::Matrix::Zero()};
168 #endif // MEASUREMENT__LINEAR_MEASUREMENT_HPP_
A CRTP interface to any measurement.
Definition: measurement_interface.hpp:37
const StateT::Vector & crtp_variances() const noexcept
Get variances function that is to be called by the CRTP interface.
Definition: linear_measurement.hpp:79
StateT & crtp_state() noexcept
Get state vector function that is to be called by the CRTP interface.
Definition: linear_measurement.hpp:73
auto & variances()
Get variances as a vector. Note that these represent sigmas, not sigmas^2.
Definition: measurement_interface.hpp:59
const StateT::Matrix & crtp_covariance() const noexcept
Get covariance function that is to be called by the CRTP interface.
Definition: linear_measurement.hpp:83
auto & state()
Get measurement as a state vector.
Definition: measurement_interface.hpp:40
StateT crtp_create_new_instance_from(const OtherStateT &other_state) const
Create a new instance of the measurement from another state.
Definition: linear_measurement.hpp:101
const StateT & crtp_state() const noexcept
Get state vector function that is to be called by the CRTP interface.
Definition: linear_measurement.hpp:75
LinearMeasurement(const typename StateT::Vector &measurement, const typename StateT::Vector &variances)
Construct a new instance of the measurement from a state vector.
Definition: linear_measurement.hpp:61
friend bool operator==(const LinearMeasurement &lhs, const LinearMeasurement &rhs)
An equality operator.
Definition: linear_measurement.hpp:150
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
OnlineData m
Definition: linear_tire.snippet.hpp:36
StateT::Vector & crtp_variances() noexcept
Get variances function that is to be called by the CRTP interface.
Definition: linear_measurement.hpp:77
COMMON_PUBLIC std::enable_if_t< I==sizeof...(TypesT)> visit(std::tuple< TypesT... > &, Callable)
Visit every element in a tuple.
Definition: type_traits.hpp:62
This defines measurement interface class.
MappingMatrixFrom< OtherStateT > crtp_mapping_matrix_from(const OtherStateT &) const
Get the mapping matrix between the two states called by the CRTP interface.
Definition: linear_measurement.hpp:136
A class that represents a linear measurement.
Definition: linear_measurement.hpp:44
StateT::Matrix & crtp_covariance() noexcept
Get covariance function that is to be called by the CRTP interface.
Definition: linear_measurement.hpp:81
OtherStateT crtp_map_into(const OtherStateT &other_state) const noexcept
Copy this measurement into another state space.
Definition: linear_measurement.hpp:117
StateT State
Definition: linear_measurement.hpp:52