Autoware.Auto
noise_interface.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__NOISE_INTERFACE_HPP_
23
#define MOTION_MODEL__NOISE_INTERFACE_HPP_
24
25
#include <
kalman_filter/visibility_control.hpp
>
26
27
#include <chrono>
28
29
namespace
autoware
30
{
31
namespace
prediction
32
{
33
40
template
<
typename
Derived>
41
class
KALMAN_FILTER_PUBLIC
NoiseInterface
42
{
43
public
:
51
inline
auto
covariance
(
const
std::chrono::nanoseconds & dt)
const
52
{
53
return
static_cast<
const
Derived &
>
(*this).crtp_covariance(dt);
54
}
55
};
56
57
}
// namespace prediction
58
}
// namespace autoware
59
60
#endif // MOTION_MODEL__NOISE_INTERFACE_HPP_
visibility_control.hpp
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
autoware::prediction::NoiseInterface::covariance
auto covariance(const std::chrono::nanoseconds &dt) const
Get a covariance matrix for this noise model.
Definition:
noise_interface.hpp:51