Autoware.Auto
measurement_interface.hpp
Go to the documentation of this file.
1 // Copyright 2021 Apex.AI, Inc
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 
17 
18 #ifndef MEASUREMENT__MEASUREMENT_INTERFACE_HPP_
19 #define MEASUREMENT__MEASUREMENT_INTERFACE_HPP_
20 
23 
24 #include <type_traits>
25 
26 namespace autoware
27 {
28 namespace prediction
29 {
30 
36 template<typename Derived>
37 struct KALMAN_FILTER_PUBLIC MeasurementInterface : public common::helper_functions::crtp<Derived>
38 {
40  auto & state()
41  {
42  using ReturnType = std::decay_t<decltype(this->impl().crtp_state())>;
43  static_assert(is_state<ReturnType>::value, "\n\nFunction crtp_state must return a state.\n\n");
44  return this->impl().crtp_state();
45  }
47  const auto & state() const
48  {
49  using ReturnType = std::decay_t<decltype(this->impl().crtp_state())>;
50  static_assert(is_state<ReturnType>::value, "\n\nFunction crtp_state must return a state.\n\n");
51  return this->impl().crtp_state();
52  }
53 
55  auto & covariance() {return this->impl().crtp_covariance();}
56  const auto & covariance() const {return this->impl().crtp_covariance();}
57 
59  auto & variances() {return this->impl().crtp_variances();}
61  const auto & variances() const {return this->impl().crtp_variances();}
62 
78  template<typename OtherStateT>
79  auto create_new_instance_from(const OtherStateT & other_state) const
80  {
81  static_assert(is_state<OtherStateT>::value, "\n\nThe other state must be a state.\n\n");
82  using ReturnType =
83  std::decay_t<decltype(this->impl().crtp_create_new_instance_from(other_state))>;
84  static_assert(
86  "\n\nFunction crtp_create_new_instance_from must return a state.\n\n");
87  return this->impl().crtp_create_new_instance_from(other_state);
88  }
89 
103  template<typename OtherStateT>
104  OtherStateT map_into(const OtherStateT & other_state) const
105  {
106  static_assert(is_state<OtherStateT>::value, "\n\nThe other state must be a state.\n\n");
107  return this->impl().crtp_map_into(other_state);
108  }
109 
125  template<typename OtherStateT>
126  auto mapping_matrix_from(const OtherStateT & other_state) const
127  {
128  static_assert(is_state<OtherStateT>::value, "The other state must be a state.");
129  return this->impl().crtp_mapping_matrix_from(other_state);
130  }
131 };
132 
133 
134 } // namespace prediction
135 } // namespace autoware
136 
137 #endif // MEASUREMENT__MEASUREMENT_INTERFACE_HPP_
OtherStateT map_into(const OtherStateT &other_state) const
Map this measurement into another state space.
Definition: measurement_interface.hpp:104
auto mapping_matrix_from(const OtherStateT &other_state) const
Get a matrix that maps a state to this measurement&#39;s state space.
Definition: measurement_interface.hpp:126
auto & variances()
Get variances as a vector. Note that these represent sigmas, not sigmas^2.
Definition: measurement_interface.hpp:59
const auto & state() const
Get measurement as a state vector.
Definition: measurement_interface.hpp:47
auto create_new_instance_from(const OtherStateT &other_state) const
Create a new instance of the measurement from another state.
Definition: measurement_interface.hpp:79
This file includes common helper functions.
A CRTP interface to any measurement.
Definition: measurement_interface.hpp:37
auto & covariance()
Get covariance of the measurement as a matrix.
Definition: measurement_interface.hpp:55
const auto & variances() const
Get variances as a vector. Note that these represent sigmas, not sigmas^2.
Definition: measurement_interface.hpp:61
const auto & covariance() const
Definition: measurement_interface.hpp:56
This file defines a class for a generic state vector representation.
Forward-declare is_state trait.
Definition: generic_state.hpp:42
auto & state()
Get measurement as a state vector.
Definition: measurement_interface.hpp:40
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24