Autoware.Auto
state_estimation_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 //
15 // Co-developed by Tier IV, Inc. and Apex.AI, Inc.
16 
17 
18 #ifndef STATE_ESTIMATION__STATE_ESTIMATION_INTERFACE_HPP_
19 #define STATE_ESTIMATION__STATE_ESTIMATION_INTERFACE_HPP_
20 
21 
25 
26 #include <chrono>
27 
28 namespace autoware
29 {
30 namespace common
31 {
32 namespace state_estimation
33 {
34 
40 template<typename Derived>
41 class STATE_ESTIMATION_PUBLIC StateEstimationInterface
42  : public common::helper_functions::crtp<Derived>
43 {
44 public:
52  auto predict(const std::chrono::nanoseconds & dt) {return this->impl().crtp_predict(dt);}
53 
65  template<typename MeasurementT>
66  auto correct(const MeasurementT & measurement)
67  {
68  static_assert(
69  std::is_base_of<MeasurementInterface<MeasurementT>, MeasurementT>::value,
70  "\n\nMeasurement must inherit from MeasurementInterface\n\n");
71  return this->impl().template crtp_correct<MeasurementT>(measurement);
72  }
73 
82  template<typename StateT>
83  void reset(const StateT & state, const typename StateT::Matrix & covariance)
84  {
85  static_assert(
86  std::is_same<typename Derived::State, StateT>::value,
87  "\n\nProvided type StateT must match the filter implementation State type.\n\n");
88  this->impl().crtp_reset(state, covariance);
89  }
90 
92  auto & state() {return this->impl().crtp_state();}
94  const auto & state() const {return this->impl().crtp_state();}
95 
97  auto & covariance() {return this->impl().crtp_covariance();}
99  const auto & covariance() const {return this->impl().crtp_covariance();}
100 };
101 
102 
103 } // namespace state_estimation
104 } // namespace common
105 } // namespace autoware
106 
107 #endif // STATE_ESTIMATION__STATE_ESTIMATION_INTERFACE_HPP_
autoware::common::state_estimation::StateEstimationInterface::covariance
const auto & covariance() const
Return current covariance.
Definition: state_estimation_interface.hpp:99
autoware::common::state_estimation::MeasurementInterface
A CRTP interface to any measurement.
Definition: measurement_interface.hpp:39
autoware::common::state_estimation::StateEstimationInterface::covariance
auto & covariance()
Return current covariance.
Definition: state_estimation_interface.hpp:97
autoware::common::state_estimation::StateEstimationInterface::predict
auto predict(const std::chrono::nanoseconds &dt)
Predict the state by dt into the future.
Definition: state_estimation_interface.hpp:52
autoware
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
autoware::common::state_estimation::StateEstimationInterface
Interface for a filter that can be used to track an object.
Definition: state_estimation_interface.hpp:41
autoware::common::helper_functions::crtp
Definition: crtp.hpp:29
autoware::common::state_estimation::StateEstimationInterface::state
const auto & state() const
Return current state.
Definition: state_estimation_interface.hpp:94
measurement_interface.hpp
autoware::common::state_estimation::StateEstimationInterface::correct
auto correct(const MeasurementT &measurement)
Correct the state with a measurement.
Definition: state_estimation_interface.hpp:66
crtp.hpp
This file includes common helper functions.
autoware::common::state_estimation::StateEstimationInterface::state
auto & state()
Return current state.
Definition: state_estimation_interface.hpp:92
autoware::common::state_estimation::StateEstimationInterface::reset
void reset(const StateT &state, const typename StateT::Matrix &covariance)
Reset the internal state of the vector to the given state and covariance.
Definition: state_estimation_interface.hpp:83
visibility_control.hpp