Go to the documentation of this file.
20 #ifndef MEASUREMENT_CONVERSION__MEASUREMENT_TRANSFORMATION_HPP_
21 #define MEASUREMENT_CONVERSION__MEASUREMENT_TRANSFORMATION_HPP_
28 #include <Eigen/Geometry>
34 namespace state_estimation
44 template<
typename MeasurementT>
47 const Eigen::Isometry3d &)
50 sizeof(MeasurementT) == 0,
51 "Only specializations for transform_measurement() function are allowed!");
63 template<
typename MeasurementT,
typename MessageT>
66 const Eigen::Isometry3d & tf__world__frame_id)
81 const Eigen::Isometry3d & tf__world__frame_id);
88 const Stamped<PoseMeasurementXYZ64> & measurement,
89 const Eigen::Isometry3d & tf__world__frame_id);
96 #endif // MEASUREMENT_CONVERSION__MEASUREMENT_TRANSFORMATION_HPP_
MeasurementT message_to_transformed_measurement(const MessageT &msg, const Eigen::Isometry3d &tf__world__frame_id)
Convenience function for converting a message into a measurement and transforming it into a different...
Definition: measurement_transformation.hpp:64
MeasurementT transform_measurement(const MeasurementT &, const Eigen::Isometry3d &)
Interface for transforming a measurement into a different coordinate system.
Definition: measurement_transformation.hpp:45
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
PoseMeasurementXYZ< common::types::float64_t > PoseMeasurementXYZ64
Definition: measurement_typedefs.hpp:55
A default template structure used for message conversion. Only its specializations are to be used.
Definition: measurement_conversion.hpp:60