Go to the documentation of this file.
20 #ifndef MEASUREMENT_CONVERSION__MEASUREMENT_TYPEDEFS_HPP_
21 #define MEASUREMENT_CONVERSION__MEASUREMENT_TYPEDEFS_HPP_
31 namespace state_estimation
34 template<
typename MeasurementT>
40 template<
typename NewScalarT>
43 using NewMeasurementT = decltype(
measurement.template cast<NewScalarT>());
51 template<
typename ScalarT>
57 template<
typename ScalarT>
69 #endif // MEASUREMENT_CONVERSION__MEASUREMENT_TYPEDEFS_HPP_
auto cast() const noexcept
Definition: measurement_typedefs.hpp:41
This file defines the common variables used within the filter implementations.
Definition: measurement_typedefs.hpp:35
std::chrono::system_clock::time_point timestamp
Definition: measurement_typedefs.hpp:37
MeasurementT measurement
Definition: measurement_typedefs.hpp:38
This file includes common type definition.
Definition: common_variables.hpp:40
A representation of a generic state vectors with specified variables.
Definition: generic_state.hpp:60
A variable that represents the roll angle of an object.
Definition: common_variables.hpp:67
A class that represents a linear measurement.
Definition: linear_measurement.hpp:46
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
Definition: common_variables.hpp:39
A variable that represents the pitch angle of an object.
Definition: common_variables.hpp:58
LinearMeasurement< state_vector::GenericState< ScalarT, state_vector::variable::X, state_vector::variable::Y, state_vector::variable::Z > > PoseMeasurementXYZ
Definition: measurement_typedefs.hpp:53
Definition: common_variables.hpp:38
A variable that represents the roll angle of an object.
Definition: common_variables.hpp:49