22 #ifndef MOTION_MODEL__WIENER_NOISE_HPP_ 23 #define MOTION_MODEL__WIENER_NOISE_HPP_ 46 template<
typename StateT>
59 const std::array<
typename State::Scalar, State::size()> & acceleration_variances)
60 : m_acceleration_variances{acceleration_variances} {}
75 "\n\nThis function must be specialized for specific states.\n\n");
79 std::array<typename State::Scalar, State::size()> m_acceleration_variances{};
92 const std::chrono::nanoseconds & dt)
const;
104 const std::chrono::nanoseconds & dt)
const;
109 #endif // MOTION_MODEL__WIENER_NOISE_HPP_ A class that describes the Wiener process noise.
Definition: wiener_noise.hpp:47
StateT State
Definition: wiener_noise.hpp:50
A CRTP interface for implementing noise models used for providing motion model noise covariance...
Definition: noise_interface.hpp:41
This file holds a collection of states that are commonly used in this package.
WienerNoise(const std::array< typename State::Scalar, State::size()> &acceleration_variances)
Constructor from acceleration variances.
Definition: wiener_noise.hpp:58
State::Matrix crtp_covariance(const std::chrono::nanoseconds &) const
A CRTP-called covariance getter.
Definition: wiener_noise.hpp:71
Eigen::Matrix< ScalarT, kSize, kSize > Matrix
Definition: generic_state.hpp:65
This file contains a definition for the noise interface.
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24