Autoware.Auto
history.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__HISTORY_HPP_
19 #define STATE_ESTIMATION_NODES__HISTORY_HPP_
20 
21 #include <common/types.hpp>
23 #include <mpark_variant_vendor/variant.hpp>
25 
26 #include <chrono>
27 #include <map>
28 #include <memory>
29 #include <utility>
30 
31 namespace autoware
32 {
33 namespace prediction
34 {
35 
36 namespace detail
37 {
38 
50 template<std::int32_t kNumOfStates>
52  const Eigen::Matrix<common::types::float32_t, kNumOfStates, 1> & sample,
53  const Eigen::Matrix<common::types::float32_t, kNumOfStates, 1> & mean,
54  const Eigen::Matrix<common::types::float32_t, kNumOfStates, kNumOfStates> & covariance_factor,
55  const common::types::float32_t mahalanobis_threshold)
56 {
58  sample, mean, covariance_factor) < mahalanobis_threshold * mahalanobis_threshold;
59 }
60 
61 } // namespace detail
62 
64 struct PredictionEvent {};
65 
71 template<typename FilterT>
72 struct ResetEvent
73 {
74  typename FilterT::state_vec_t state;
75  typename FilterT::square_mat_t covariance_factor;
76 };
77 
91 template<
92  typename FilterT,
93  std::int32_t kNumOfStates,
94  typename ... EventT>
95 class History
96 {
100  class HistoryEntry;
105  class EkfStateUpdater;
106 
108  using Timestamp = std::chrono::system_clock::time_point;
110  using HistoryMap = std::multimap<Timestamp, HistoryEntry>;
111 
112 public:
120  explicit History(
121  FilterT & filter,
122  const std::size_t max_history_size,
123  const common::types::float32_t mahalanobis_threshold)
124  : m_filter{filter},
125  m_max_history_size{max_history_size},
126  m_mahalanobis_threshold{mahalanobis_threshold} {}
127 
135  void emplace_event(const Timestamp & timestamp, const HistoryEntry & entry);
137  inline bool empty() const noexcept {return m_history.empty();}
139  inline std::size_t size() const noexcept {return m_history.size();}
141  inline const Timestamp & get_last_timestamp() const noexcept {return m_history.rbegin()->first;}
143  inline const HistoryEntry & get_last_event() const noexcept {return m_history.rbegin()->second;}
145  const FilterT & get_filter() const noexcept {return m_filter;}
147  FilterT & get_filter() noexcept {return m_filter;}
148 
149 private:
153  inline void drop_oldest_event_if_needed()
154  {
155  if ((m_history.size() >= m_max_history_size) && (m_max_history_size > 0U)) {
156  (void) m_history.erase(m_history.begin());
157  }
158  }
159 
165  void update_impacted_events(const typename HistoryMap::iterator & start_iter);
166 
167  HistoryMap m_history{};
168  FilterT & m_filter{};
169  std::size_t m_max_history_size{};
170  common::types::float32_t m_mahalanobis_threshold{};
171 };
172 
173 template<typename FilterT, std::int32_t kNumOfStates, typename ... EventT>
174 class History<FilterT, kNumOfStates, EventT...>::HistoryEntry
175 {
176 public:
177  template<typename SingleEventT>
178  // cppcheck-suppress noExplicitConstructor; Conversion to the variant type takes place.
179  HistoryEntry(const SingleEventT & event) : m_event {event} {}
180 
182  void update_stored_state(const typename FilterT::state_vec_t & state) noexcept
183  {
184  m_stored_state = state;
185  }
187  const typename FilterT::state_vec_t & stored_state() const noexcept {return m_stored_state;}
189  void update_stored_covariance_factor(const typename FilterT::square_mat_t & factor) noexcept
190  {
191  m_stored_covariance_factor = factor;
192  }
194  const typename FilterT::square_mat_t & stored_covariance_factor() const noexcept
195  {
196  return m_stored_covariance_factor;
197  }
199  const mpark::variant<EventT...> & event() const {return m_event;}
200 
201 private:
203  typename FilterT::state_vec_t m_stored_state{FilterT::state_vec_t::Zero()};
205  typename FilterT::square_mat_t m_stored_covariance_factor{FilterT::square_mat_t::Zero()};
207  mpark::variant<EventT...> m_event;
208 };
209 
210 template<typename FilterT, std::int32_t kNumOfStates, typename ... EventT>
211 class History<FilterT, kNumOfStates, EventT...>::EkfStateUpdater
212 {
213 public:
214  explicit EkfStateUpdater(
215  FilterT & filter,
216  const common::types::float32_t mahalanobis_threshold,
217  const std::chrono::system_clock::duration & dt = std::chrono::milliseconds{0})
218  : m_filter {filter}, m_mahalanobis_threshold{mahalanobis_threshold}, m_dt{dt}
219  {}
220 
228  template<typename MeasurementT>
229  void operator()(const MeasurementT & event)
230  {
231  m_filter.temporal_update(m_dt);
232  // TODO(#887): I see a couple of ways to check mahalanobis distance in case the measurement does
233  // not cover the full state. Here I upscale it to the full state, copying the values of the
234  // current state for ones missing in the observation. We can alternatively apply the H matrix
235  // and only compute the distance in the measurement world. Don't really know which one is best
236  // here.
238  event.get_values_in_full_state(m_filter.get_state()),
239  m_filter.get_state(),
240  m_filter.get_covariance(),
241  m_mahalanobis_threshold)) {return;}
242  (void) m_filter.observation_update(
243  event.get_values(),
244  MeasurementT::template get_observation_to_state_mapping<kNumOfStates>(),
245  event.get_variances());
246  }
247 
249  void operator()(const ResetEvent<FilterT> & event)
250  {
251  m_filter.reset(event.state, event.covariance_factor);
252  }
253 
256  {
257  m_filter.temporal_update(m_dt);
258  }
259 
260 private:
261  FilterT & m_filter{};
262  common::types::float32_t m_mahalanobis_threshold{};
263  std::chrono::system_clock::duration m_dt{};
264 };
265 
266 template<typename FilterT, std::int32_t kNumOfStates, typename ... EventT>
268  const Timestamp & timestamp, const HistoryEntry & entry)
269 {
270  drop_oldest_event_if_needed();
271  const auto iterator_to_inserted_position = m_history.emplace(timestamp, entry);
272  update_impacted_events(iterator_to_inserted_position);
273 }
274 
275 template<typename FilterT, std::int32_t kNumOfStates, typename ... EventT>
277  const typename HistoryMap::iterator & start_iter)
278 {
279  Timestamp previous_timestamp{};
280  if (start_iter == m_history.begin()) {
281  if (!mpark::holds_alternative<ResetEvent<FilterT>>(start_iter->second.event())) {
282  (void) m_history.erase(start_iter);
283  throw std::runtime_error(
284  "Non-reset event inserted to the beginning of history. This might "
285  "happen if a very old event is inserted into the queue. Consider "
286  "increasing the queue size or debug program latencies.");
287  }
288  } else {
289  const auto prev_iter = std::prev(start_iter);
290  previous_timestamp = prev_iter->first;
291  const auto & prev_entry = prev_iter->second;
292  m_filter.reset(prev_entry.stored_state(), prev_entry.stored_covariance_factor());
293  }
294  for (auto iter = start_iter; iter != m_history.end(); ++iter) {
295  const auto current_timestamp = iter->first;
296  auto & entry = iter->second;
297  mpark::visit(
298  EkfStateUpdater{m_filter, m_mahalanobis_threshold, current_timestamp - previous_timestamp},
299  entry.event());
300  entry.update_stored_state(m_filter.get_state());
301  entry.update_stored_covariance_factor(m_filter.get_covariance());
302  previous_timestamp = iter->first;
303  }
304 }
305 
306 
307 } // namespace prediction
308 } // namespace autoware
309 
310 
311 #endif // STATE_ESTIMATION_NODES__HISTORY_HPP_
autoware::prediction::History::HistoryEntry::stored_state
const FilterT::state_vec_t & stored_state() const noexcept
Get the stored state.
Definition: history.hpp:187
autoware::prediction::History::HistoryEntry::stored_covariance_factor
const FilterT::square_mat_t & stored_covariance_factor() const noexcept
Get the stored covariance in the form of its left factor.
Definition: history.hpp:194
autoware::prediction::History::EkfStateUpdater::operator()
void operator()(const PredictionEvent &)
An operator that applies the prediction event to the filter implementation.
Definition: history.hpp:255
steady_time_grid.hpp
types.hpp
This file includes common type definition.
autoware::prediction::detail::passes_mahalanobis_gate
bool passes_mahalanobis_gate(const Eigen::Matrix< common::types::float32_t, kNumOfStates, 1 > &sample, const Eigen::Matrix< common::types::float32_t, kNumOfStates, 1 > &mean, const Eigen::Matrix< common::types::float32_t, kNumOfStates, kNumOfStates > &covariance_factor, const common::types::float32_t mahalanobis_threshold)
Definition: history.hpp:51
autoware::prediction::History::EkfStateUpdater::operator()
void operator()(const ResetEvent< FilterT > &event)
An operator that resets the state of the filter implementation.
Definition: history.hpp:249
autoware::prediction::History::History
History(FilterT &filter, const std::size_t max_history_size, const common::types::float32_t mahalanobis_threshold)
Construct history from a filter pointer with a specific size.
Definition: history.hpp:120
autoware::prediction::ResetEvent::state
FilterT::state_vec_t state
Definition: history.hpp:74
autoware::prediction::ResetEvent::covariance_factor
FilterT::square_mat_t covariance_factor
Definition: history.hpp:75
motion::motion_common::sample
void sample(const Trajectory &in, Trajectory &out, std::chrono::nanoseconds period, SlerpF slerp_fn)
Sample a trajectory using interpolation; does not extrapolate.
Definition: motion_common.hpp:194
autoware::prediction::History::HistoryEntry::event
const mpark::variant< EventT... > & event() const
Get the event stored in this history entry.
Definition: history.hpp:199
autoware::prediction::ResetEvent
An event to reset the state of the filter.
Definition: history.hpp:72
autoware
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
autoware::prediction::History::get_last_event
const HistoryEntry & get_last_event() const noexcept
Get last event in history.
Definition: history.hpp:143
autoware::prediction::History::get_filter
const FilterT & get_filter() const noexcept
Get the filter as a const ref.
Definition: history.hpp:145
autoware::prediction::History::HistoryEntry
Definition: history.hpp:174
autoware::prediction::History::emplace_event
void emplace_event(const Timestamp &timestamp, const HistoryEntry &entry)
Add an event to history. If it is added to the middle the following ones are automatically replayed o...
Definition: history.hpp:267
autoware::common::type_traits::visit
COMMON_PUBLIC std::enable_if_t< I==sizeof...(TypesT)> visit(std::tuple< TypesT... > &, Callable)
Visit every element in a tuple.
Definition: type_traits.hpp:62
mahalanobis_distance.hpp
autoware::common::types::float32_t
float float32_t
Definition: types.hpp:45
autoware::prediction::PredictionEvent
An event to indicate a prediction step.
Definition: history.hpp:64
autoware::prediction::History
This class encapsulates a history of events used with EKF.
Definition: history.hpp:95
autoware::prediction::History::empty
bool empty() const noexcept
Check if the history is empty.
Definition: history.hpp:137
autoware::prediction::History::get_last_timestamp
const Timestamp & get_last_timestamp() const noexcept
Get last timestamp in history.
Definition: history.hpp:141
autoware::prediction::History::EkfStateUpdater::operator()
void operator()(const MeasurementT &event)
An operator that passes a measurement event to the filter implementation.
Definition: history.hpp:229
autoware::prediction::History::HistoryEntry::HistoryEntry
HistoryEntry(const SingleEventT &event)
Definition: history.hpp:179
autoware::prediction::History::EkfStateUpdater::EkfStateUpdater
EkfStateUpdater(FilterT &filter, const common::types::float32_t mahalanobis_threshold, const std::chrono::system_clock::duration &dt=std::chrono::milliseconds{0})
Definition: history.hpp:214
autoware::prediction::History::EkfStateUpdater
Definition: history.hpp:211
autoware::prediction::History::HistoryEntry::update_stored_state
void update_stored_state(const typename FilterT::state_vec_t &state) noexcept
Update the stored state.
Definition: history.hpp:182
autoware::prediction::History::size
std::size_t size() const noexcept
Get size of history.
Definition: history.hpp:139
autoware::common::helper_functions::calculate_squared_mahalanobis_distance
types::float32_t calculate_squared_mahalanobis_distance(const Eigen::Matrix< T, kNumOfStates, 1 > &sample, const Eigen::Matrix< T, kNumOfStates, 1 > &mean, const Eigen::Matrix< T, kNumOfStates, kNumOfStates > &covariance_factor)
Calculate square of mahalanobis distance.
Definition: mahalanobis_distance.hpp:34
autoware::prediction::History::HistoryEntry::update_stored_covariance_factor
void update_stored_covariance_factor(const typename FilterT::square_mat_t &factor) noexcept
Set the covariance left factor to be stored there.
Definition: history.hpp:189
autoware::prediction::History::get_filter
FilterT & get_filter() noexcept
Get the filter.
Definition: history.hpp:147