18 #ifndef STATE_ESTIMATION_NODES__HISTORY_HPP_
19 #define STATE_ESTIMATION_NODES__HISTORY_HPP_
23 #include <mpark_variant_vendor/variant.hpp>
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,
58 sample, mean, covariance_factor) < mahalanobis_threshold * mahalanobis_threshold;
71 template<
typename FilterT>
74 typename FilterT::state_vec_t
state;
93 std::int32_t kNumOfStates,
108 using Timestamp = std::chrono::system_clock::time_point;
110 using HistoryMap = std::multimap<Timestamp, HistoryEntry>;
122 const std::size_t max_history_size,
125 m_max_history_size{max_history_size},
126 m_mahalanobis_threshold{mahalanobis_threshold} {}
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();}
145 const FilterT &
get_filter() const noexcept {
return m_filter;}
153 inline void drop_oldest_event_if_needed()
155 if ((m_history.size() >= m_max_history_size) && (m_max_history_size > 0U)) {
156 (void) m_history.erase(m_history.begin());
165 void update_impacted_events(
const typename HistoryMap::iterator & start_iter);
167 HistoryMap m_history{};
168 FilterT & m_filter{};
169 std::size_t m_max_history_size{};
173 template<
typename FilterT, std::int32_t kNumOfStates,
typename ... EventT>
177 template<
typename SingleEventT>
184 m_stored_state = state;
187 const typename FilterT::state_vec_t &
stored_state() const noexcept {
return m_stored_state;}
191 m_stored_covariance_factor = factor;
196 return m_stored_covariance_factor;
199 const mpark::variant<EventT...> &
event()
const {
return m_event;}
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;
210 template<
typename FilterT, std::int32_t kNumOfStates,
typename ... EventT>
217 const std::chrono::system_clock::duration & dt = std::chrono::milliseconds{0})
218 : m_filter {filter}, m_mahalanobis_threshold{mahalanobis_threshold}, m_dt{dt}
228 template<
typename MeasurementT>
231 m_filter.temporal_update(m_dt);
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(
244 MeasurementT::template get_observation_to_state_mapping<kNumOfStates>(),
245 event.get_variances());
257 m_filter.temporal_update(m_dt);
261 FilterT & m_filter{};
263 std::chrono::system_clock::duration m_dt{};
266 template<
typename FilterT, std::int32_t kNumOfStates,
typename ... EventT>
268 const Timestamp & timestamp,
const HistoryEntry & entry)
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);
275 template<
typename FilterT, std::int32_t kNumOfStates,
typename ... EventT>
277 const typename HistoryMap::iterator & start_iter)
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.");
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());
294 for (
auto iter = start_iter; iter != m_history.end(); ++iter) {
295 const auto current_timestamp = iter->first;
296 auto & entry = iter->second;
298 EkfStateUpdater{m_filter, m_mahalanobis_threshold, current_timestamp - previous_timestamp},
300 entry.update_stored_state(m_filter.get_state());
301 entry.update_stored_covariance_factor(m_filter.get_covariance());
302 previous_timestamp = iter->first;
311 #endif // STATE_ESTIMATION_NODES__HISTORY_HPP_