Go to the documentation of this file.
18 #ifndef MEASUREMENT__MEASUREMENT_INTERFACE_HPP_
19 #define MEASUREMENT__MEASUREMENT_INTERFACE_HPP_
24 #include <type_traits>
36 template<
typename Derived>
42 using ReturnType = std::decay_t<decltype(this->impl().crtp_state())>;
44 return this->impl().crtp_state();
49 using ReturnType = std::decay_t<decltype(this->impl().crtp_state())>;
51 return this->impl().crtp_state();
55 auto &
covariance() {
return this->impl().crtp_covariance();}
56 const auto &
covariance()
const {
return this->impl().crtp_covariance();}
59 auto &
variances() {
return this->impl().crtp_variances();}
61 const auto &
variances()
const {
return this->impl().crtp_variances();}
78 template<
typename OtherStateT>
83 std::decay_t<decltype(this->impl().crtp_create_new_instance_from(other_state))>;
86 "\n\nFunction crtp_create_new_instance_from must return a state.\n\n");
87 return this->impl().crtp_create_new_instance_from(other_state);
103 template<
typename OtherStateT>
104 OtherStateT
map_into(
const OtherStateT & other_state)
const
107 return this->impl().crtp_map_into(other_state);
125 template<
typename OtherStateT>
129 return this->impl().crtp_mapping_matrix_from(other_state);
137 #endif // MEASUREMENT__MEASUREMENT_INTERFACE_HPP_
A CRTP interface to any measurement.
Definition: measurement_interface.hpp:37
auto & variances()
Get variances as a vector. Note that these represent sigmas, not sigmas^2.
Definition: measurement_interface.hpp:59
auto mapping_matrix_from(const OtherStateT &other_state) const
Get a matrix that maps a state to this measurement's state space.
Definition: measurement_interface.hpp:126
const auto & variances() const
Get variances as a vector. Note that these represent sigmas, not sigmas^2.
Definition: measurement_interface.hpp:61
Forward-declare is_state trait.
Definition: generic_state.hpp:42
const auto & covariance() const
Definition: measurement_interface.hpp:56
auto & state()
Get measurement as a state vector.
Definition: measurement_interface.hpp:40
This file defines a class for a generic state vector representation.
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
auto & covariance()
Get covariance of the measurement as a matrix.
Definition: measurement_interface.hpp:55
This file includes common helper functions.
auto create_new_instance_from(const OtherStateT &other_state) const
Create a new instance of the measurement from another state.
Definition: measurement_interface.hpp:79
const auto & state() const
Get measurement as a state vector.
Definition: measurement_interface.hpp:47
OtherStateT map_into(const OtherStateT &other_state) const
Map this measurement into another state space.
Definition: measurement_interface.hpp:104