Autoware.Auto
measurement_transformation.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 
19 
20 #ifndef MEASUREMENT_CONVERSION__MEASUREMENT_TRANSFORMATION_HPP_
21 #define MEASUREMENT_CONVERSION__MEASUREMENT_TRANSFORMATION_HPP_
22 
27 
28 #include <Eigen/Geometry>
29 
30 namespace autoware
31 {
32 namespace common
33 {
34 namespace state_estimation
35 {
36 
44 template<typename MeasurementT>
45 MeasurementT transform_measurement(
46  const MeasurementT &,
47  const Eigen::Isometry3d &)
48 {
49  static_assert(
50  sizeof(MeasurementT) == 0,
51  "Only specializations for transform_measurement() function are allowed!");
52 }
53 
63 template<typename MeasurementT, typename MessageT>
65  const MessageT & msg,
66  const Eigen::Isometry3d & tf__world__frame_id)
67 {
68  const auto measurement = convert_to<MeasurementT>::from(msg);
69  return transform_measurement(measurement, tf__world__frame_id);
70 }
71 
72 
73 // Doxygen is buggy when the parameters are repeated here, so they are omitted.
74 
78 template<>
79 MEASUREMENT_CONVERSION_PUBLIC PoseMeasurementXYZ64 transform_measurement(
80  const PoseMeasurementXYZ64 & measurement,
81  const Eigen::Isometry3d & tf__world__frame_id);
82 
86 template<>
87 MEASUREMENT_CONVERSION_PUBLIC Stamped<PoseMeasurementXYZ64> transform_measurement(
88  const Stamped<PoseMeasurementXYZ64> & measurement,
89  const Eigen::Isometry3d & tf__world__frame_id);
90 
91 } // namespace state_estimation
92 } // namespace common
93 } // namespace autoware
94 
95 
96 #endif // MEASUREMENT_CONVERSION__MEASUREMENT_TRANSFORMATION_HPP_
eigen_utils.hpp
measurement_typedefs.hpp
autoware::common::state_estimation::message_to_transformed_measurement
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
visibility_control.hpp
autoware::common::state_estimation::transform_measurement
MeasurementT transform_measurement(const MeasurementT &, const Eigen::Isometry3d &)
Interface for transforming a measurement into a different coordinate system.
Definition: measurement_transformation.hpp:45
autoware
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
measurement_conversion.hpp
autoware::common::state_estimation::PoseMeasurementXYZ64
PoseMeasurementXYZ< common::types::float64_t > PoseMeasurementXYZ64
Definition: measurement_typedefs.hpp:55
autoware::common::state_estimation::convert_to
A default template structure used for message conversion. Only its specializations are to be used.
Definition: measurement_conversion.hpp:60