Autoware.Auto
wiener_noise.hpp
Go to the documentation of this file.
1 // Copyright 2021 the Autoware Foundation
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 //    http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 //
15 // Developed by Apex.AI, Inc.
16 
21 
22 #ifndef MOTION_MODEL__WIENER_NOISE_HPP_
23 #define MOTION_MODEL__WIENER_NOISE_HPP_
24 
28 
29 #include <array>
30 
31 namespace autoware
32 {
33 namespace prediction
34 {
35 
46 template<typename StateT>
47 class KALMAN_FILTER_PUBLIC WienerNoise : public NoiseInterface<WienerNoise<StateT>>
48 {
49 public:
50  using State = StateT;
51 
58  explicit WienerNoise(
59  const std::array<typename State::Scalar, State::size()> & acceleration_variances)
60  : m_acceleration_variances{acceleration_variances} {}
61 
62 protected:
63  // Required to allow the crtp interface call the following functions.
65 
71  typename State::Matrix crtp_covariance(const std::chrono::nanoseconds &) const
72  {
73  static_assert(
74  sizeof(StateT) == 0U,
75  "\n\nThis function must be specialized for specific states.\n\n");
76  }
77 
78 private:
79  std::array<typename State::Scalar, State::size()> m_acceleration_variances{};
80 };
81 
89 template<>
90 KALMAN_FILTER_PUBLIC state::ConstAccelerationXY::Matrix
92  const std::chrono::nanoseconds & dt) const;
93 
101 template<>
102 KALMAN_FILTER_PUBLIC state::ConstAccelerationXYYaw::Matrix
104  const std::chrono::nanoseconds & dt) const;
105 
106 } // namespace prediction
107 } // namespace autoware
108 
109 #endif // MOTION_MODEL__WIENER_NOISE_HPP_
visibility_control.hpp
autoware::prediction::GenericState::Matrix
Eigen::Matrix< ScalarT, kSize, kSize > Matrix
Definition: generic_state.hpp:65
autoware::prediction::WienerNoise::WienerNoise
WienerNoise(const std::array< typename State::Scalar, State::size()> &acceleration_variances)
Constructor from acceleration variances.
Definition: wiener_noise.hpp:58
autoware::prediction::NoiseInterface
A CRTP interface for implementing noise models used for providing motion model noise covariance.
Definition: noise_interface.hpp:41
autoware
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
noise_interface.hpp
This file contains a definition for the noise interface.
autoware::prediction::WienerNoise::crtp_covariance
State::Matrix crtp_covariance(const std::chrono::nanoseconds &) const
A CRTP-called covariance getter.
Definition: wiener_noise.hpp:71
autoware::prediction::WienerNoise
A class that describes the Wiener process noise.
Definition: wiener_noise.hpp:47
autoware::prediction::WienerNoise::State
StateT State
Definition: wiener_noise.hpp:50
common_states.hpp
This file holds a collection of states that are commonly used in this package.