Autoware.Auto
measurement.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 STATE_ESTIMATION_NODES__MEASUREMENT_HPP_
19 #define STATE_ESTIMATION_NODES__MEASUREMENT_HPP_
20 
21 #include <common/types.hpp>
23 
24 #include <Eigen/Core>
25 
26 #include <chrono>
27 #include <cstdint>
28 #include <tuple>
29 
30 namespace autoware
31 {
32 namespace prediction
33 {
45 template<typename T, std::uint32_t... kMeasurementModalities>
46 class STATE_ESTIMATION_NODES_PUBLIC Measurement
47 {
48  static constexpr std::int32_t EntriesCount = sizeof...(kMeasurementModalities);
49 
50  using MeasurementModalityArray =
51  std::array<std::uint32_t, static_cast<std::size_t>(EntriesCount)>;
52 
53  template<typename S, std::int32_t kSize>
54  using Vector = Eigen::Matrix<S, kSize, 1U>;
55  template<typename S, std::int32_t kNumOfColumns>
56  using MapMatrix = Eigen::Matrix<S, EntriesCount, kNumOfColumns>;
57 
58  using MeasurementVector = Vector<T, EntriesCount>;
59  using VarianceVector = Vector<T, EntriesCount>;
60 
61 public:
68  explicit Measurement(
69  const std::chrono::system_clock::time_point & acquisition_time,
70  const MeasurementVector & values, const VarianceVector & variances = {})
71  : m_acquisition_time{acquisition_time}, m_measurement_values{values}, m_variances{variances} {}
72 
77  inline const MeasurementVector & get_values() const noexcept {return m_measurement_values;}
78 
83  inline const VarianceVector & get_variances() const noexcept {return m_variances;}
84 
89  inline const std::chrono::system_clock::time_point & get_acquisition_time() const noexcept
90  {
91  return m_acquisition_time;
92  }
93 
104  template<std::int32_t kNumOfStates>
105  static MapMatrix<T, kNumOfStates> get_observation_to_state_mapping()
106  {
107  using MatrixT = MapMatrix<T, kNumOfStates>;
108  MatrixT observation_to_state_mapping{MatrixT::Zero()};
109  for (auto i = 0U; i < kMeasurementModalitiesArray.size(); ++i) {
110  observation_to_state_mapping(i, kMeasurementModalitiesArray[i]) = static_cast<T>(1.0);
111  }
112  return observation_to_state_mapping;
113  }
114 
132  template<std::int32_t kFullStateSize>
133  Vector<T, kFullStateSize> get_values_in_full_state(
134  const Vector<T, kFullStateSize> & donor_state = Vector<T, kFullStateSize>::Zero()) const
135  {
136  static_assert(kFullStateSize >= EntriesCount, "State too small to contain this measurement.");
137  Vector<T, kFullStateSize> state{donor_state};
138  for (auto i = 0U; i < kMeasurementModalitiesArray.size(); ++i) {
139  state[kMeasurementModalitiesArray[i]] = m_measurement_values[i];
140  }
141  return state;
142  }
143 
144 private:
146  static constexpr MeasurementModalityArray kMeasurementModalitiesArray {
147  kMeasurementModalities ...};
149  std::chrono::system_clock::time_point m_acquisition_time;
151  MeasurementVector m_measurement_values{};
153  VarianceVector m_variances{};
154 };
155 
156 template<typename T, std::uint32_t... kMeasurementModalities>
157 constexpr typename Measurement<T, kMeasurementModalities...>::MeasurementModalityArray
158 Measurement<T, kMeasurementModalities...>::kMeasurementModalitiesArray;
159 
160 } // namespace prediction
161 } // namespace autoware
162 
163 
164 #endif // STATE_ESTIMATION_NODES__MEASUREMENT_HPP_
autoware::prediction::Measurement::Measurement
Measurement(const std::chrono::system_clock::time_point &acquisition_time, const MeasurementVector &values, const VarianceVector &variances={})
Definition: measurement.hpp:68
catr_diff.T
T
Definition: catr_diff.py:22
types.hpp
This file includes common type definition.
autoware::prediction::Measurement::get_values
const MeasurementVector & get_values() const noexcept
Definition: measurement.hpp:77
autoware
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
autoware::prediction::Measurement::get_variances
const VarianceVector & get_variances() const noexcept
Definition: measurement.hpp:83
autoware::prediction::Measurement
Definition: measurement.hpp:46
autoware::prediction::Measurement::get_observation_to_state_mapping
static MapMatrix< T, kNumOfStates > get_observation_to_state_mapping()
Definition: measurement.hpp:105
autoware::prediction::Measurement::get_values_in_full_state
Vector< T, kFullStateSize > get_values_in_full_state(const Vector< T, kFullStateSize > &donor_state=Vector< T, kFullStateSize >::Zero()) const
Definition: measurement.hpp:133
visibility_control.hpp
autoware::prediction::Measurement::get_acquisition_time
const std::chrono::system_clock::time_point & get_acquisition_time() const noexcept
Definition: measurement.hpp:89