Go to the documentation of this file.
22 #ifndef KALMAN_FILTER__GENERIC_STATE_HPP_
23 #define KALMAN_FILTER__GENERIC_STATE_HPP_
41 template<
typename StateT>
49 template<
typename ScalarT,
typename ... VariableTs>
54 "\n\nState can only be generated from variables, i.e. types that inherit from Variable.\n\n");
56 std::is_arithmetic<ScalarT>::value,
"\n\nThe provided scalar type is not arithmetic.\n\n");
58 sizeof...(VariableTs) > 0,
"\n\nCannot create state without variables.\n\n");
60 constexpr
static std::int32_t kSize =
sizeof...(VariableTs);
64 using Vector = Eigen::Matrix<ScalarT, kSize, 1>;
65 using Matrix = Eigen::Matrix<ScalarT, kSize, kSize>;
118 template<
typename VariableT>
119 inline ScalarT &
at() noexcept
131 template<
typename VariableT>
132 inline ScalarT &
at(
const VariableT) noexcept
144 template<
typename VariableT>
145 inline const ScalarT &
at() const noexcept
157 template<
typename VariableT>
158 inline const ScalarT &
at(
const VariableT)
const noexcept
193 template<
typename OtherStateT>
194 inline OtherStateT
copy_into(OtherStateT other_state = OtherStateT{})
const noexcept
198 "\n\nOtherStateT is not a GenericState.\n\n");
199 auto copy_variables = [&other_state,
this](
auto variable) {
200 other_state.at(variable) = this->at(variable);
202 const auto & variables_tuple =
203 std::conditional_t<(OtherStateT::size() > kSize), GenericState, OtherStateT>::variables();
215 template<
typename VariableT>
237 return lhs.m_state.isApprox(rhs.m_state);
246 auto print = [&out, &state](
auto element) {
255 Vector m_state{Vector::Zero()};
263 template<
typename StateT>
264 struct KALMAN_FILTER_PUBLIC is_state :
public std::false_type {};
272 template<
typename ScalarT,
typename ... VariableTs>
274 :
public std::true_type {};
277 template<
typename ... Ts>
281 template<
typename ... Ts>
287 #endif // KALMAN_FILTER__GENERIC_STATE_HPP_
const ScalarT & at(const VariableT) const noexcept
Get vector element at a given variable.
Definition: generic_state.hpp:158
This file defines the common variables used within the filter implementations.
friend std::ostream & operator<<(std::ostream &out, const GenericState &state)
Allow using << operator with this class.
Definition: generic_state.hpp:243
Eigen::Matrix< ScalarT, kSize, 1 > Vector
Definition: generic_state.hpp:64
GenericState(const Vector &vector)
Constructs a new instance from an Eigen vector.
Definition: generic_state.hpp:78
ScalarT & at(const VariableT) noexcept
Get vector element at a given variable.
Definition: generic_state.hpp:132
Eigen::Matrix< ScalarT, kSize, kSize > Matrix
Definition: generic_state.hpp:65
This file includes common type definition.
constexpr static Eigen::Index size() noexcept
Get the size of the state.
Definition: generic_state.hpp:229
const Vector & vector() const noexcept
Get underlying Eigen vector.
Definition: generic_state.hpp:92
Forward-declare is_state trait.
Definition: generic_state.hpp:42
Vector & vector() noexcept
Get underlying Eigen vector.
Definition: generic_state.hpp:86
A class to compute a conjunction over given traits.
Definition: type_traits.hpp:101
const ScalarT & operator[](const Eigen::Index idx) const
Get an element of the vector.
Definition: generic_state.hpp:109
ScalarT & operator[](const Eigen::Index idx)
Get an element of the vector.
Definition: generic_state.hpp:101
const ScalarT & at() const noexcept
Get vector element at a given variable.
Definition: generic_state.hpp:145
COMMON_PUBLIC std::string get_type_name()
Get a demangled name of a type.
Definition: type_name.hpp:34
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
Find an index of a type in a tuple.
Definition: type_traits.hpp:34
ScalarT Scalar
Definition: generic_state.hpp:66
std::tuple< VariableTs... > Variables
Definition: generic_state.hpp:63
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
float float32_t
Definition: types.hpp:45
constexpr static Variables variables() noexcept
Get a variables tuple used for iteration over all variables.
Definition: generic_state.hpp:232
A trait to check if a type is a variable by checking if it inherits from Variable.
Definition: variable.hpp:53
double float64_t
Definition: types.hpp:47
A representation of a generic state vectors with specified variables.
Definition: generic_state.hpp:50
constexpr static Eigen::Index index_of() noexcept
Get an index of the variable in the state.
Definition: generic_state.hpp:216
OtherStateT copy_into(OtherStateT other_state=OtherStateT{}) const noexcept
Copy values of this state into another state.
Definition: generic_state.hpp:194
constexpr friend bool operator==(const GenericState &lhs, const GenericState &rhs)
An equality operator.
Definition: generic_state.hpp:235
ScalarT & at() noexcept
Get vector element at a given variable.
Definition: generic_state.hpp:119
std::size_t Index
Index type for identifying bins of the hash/lattice.
Definition: spatial_hash_config.hpp:49