Loading [MathJax]/extensions/tex2jax.js
Go to the documentation of this file.
17#ifndef STATE_ESTIMATION__MEASUREMENT__MEASUREMENT_INTERFACE_HPP_
18#define STATE_ESTIMATION__MEASUREMENT__MEASUREMENT_INTERFACE_HPP_
30namespace state_estimation
38template<
typename Derived>
44 using ReturnType = std::decay_t<decltype(this->impl().crtp_state())>;
47 "\n\nFunction crtp_state must return a state.\n\n");
48 return this->impl().crtp_state();
53 using ReturnType = std::decay_t<decltype(this->impl().crtp_state())>;
56 "\n\nFunction crtp_state must return a state.\n\n");
57 return this->impl().crtp_state();
61 auto &
covariance() {
return this->impl().crtp_covariance();}
62 const auto &
covariance()
const {
return this->impl().crtp_covariance();}
79 template<
typename OtherStateT>
84 "\n\nThe other state must be a state.\n\n");
86 std::decay_t<decltype(this->impl().crtp_create_new_instance_from(other_state))>;
89 "\n\nFunction crtp_create_new_instance_from must return a state.\n\n");
90 return this->impl().crtp_create_new_instance_from(other_state);
106 template<
typename OtherStateT>
107 OtherStateT
map_into(
const OtherStateT & other_state)
const
111 "\n\nThe other state must be a state.\n\n");
112 return this->impl().crtp_map_into(other_state);
130 template<
typename OtherStateT>
135 "The other state must be a state.");
136 return this->impl().crtp_mapping_matrix_from(other_state);
145 #endif // STATE_ESTIMATION__MEASUREMENT__MEASUREMENT_INTERFACE_HPP_
auto & state()
Get measurement as a state vector.
Definition: measurement_interface.hpp:42
Forward-declare is_state trait.
Definition: generic_state.hpp:51
const auto & state() const
Get measurement as a state vector.
Definition: measurement_interface.hpp:51
A CRTP interface to any measurement.
Definition: measurement_interface.hpp:39
auto & covariance()
Get covariance of the measurement as a matrix.
Definition: measurement_interface.hpp:61
const auto & covariance() const
Definition: measurement_interface.hpp:62
OtherStateT map_into(const OtherStateT &other_state) const
Map this measurement into another state space.
Definition: measurement_interface.hpp:107
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:131
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
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:80