Go to the documentation of this file.
18 #ifndef STATE_ESTIMATION__STATE_ESTIMATION_INTERFACE_HPP_
19 #define STATE_ESTIMATION__STATE_ESTIMATION_INTERFACE_HPP_
32 namespace state_estimation
40 template<
typename Derived>
52 auto predict(
const std::chrono::nanoseconds & dt) {
return this->impl().crtp_predict(dt);}
65 template<
typename MeasurementT>
66 auto correct(
const MeasurementT & measurement)
70 "\n\nMeasurement must inherit from MeasurementInterface\n\n");
71 return this->impl().template crtp_correct<MeasurementT>(measurement);
82 template<
typename StateT>
83 void reset(
const StateT & state,
const typename StateT::Matrix & covariance)
86 std::is_same<typename Derived::State, StateT>::value,
87 "\n\nProvided type StateT must match the filter implementation State type.\n\n");
88 this->impl().crtp_reset(state, covariance);
92 auto &
state() {
return this->impl().crtp_state();}
94 const auto &
state()
const {
return this->impl().crtp_state();}
97 auto &
covariance() {
return this->impl().crtp_covariance();}
99 const auto &
covariance()
const {
return this->impl().crtp_covariance();}
107 #endif // STATE_ESTIMATION__STATE_ESTIMATION_INTERFACE_HPP_
const auto & covariance() const
Return current covariance.
Definition: state_estimation_interface.hpp:99
A CRTP interface to any measurement.
Definition: measurement_interface.hpp:39
auto & covariance()
Return current covariance.
Definition: state_estimation_interface.hpp:97
auto predict(const std::chrono::nanoseconds &dt)
Predict the state by dt into the future.
Definition: state_estimation_interface.hpp:52
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
Interface for a filter that can be used to track an object.
Definition: state_estimation_interface.hpp:41
const auto & state() const
Return current state.
Definition: state_estimation_interface.hpp:94
auto correct(const MeasurementT &measurement)
Correct the state with a measurement.
Definition: state_estimation_interface.hpp:66
This file includes common helper functions.
auto & state()
Return current state.
Definition: state_estimation_interface.hpp:92
void reset(const StateT &state, const typename StateT::Matrix &covariance)
Reset the internal state of the vector to the given state and covariance.
Definition: state_estimation_interface.hpp:83