Autoware.Auto
measurement_conversion.hpp
Go to the documentation of this file.
1 // Copyright 2020 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 
17 
18 #ifndef STATE_ESTIMATION_NODES__MEASUREMENT_CONVERSION_HPP_
19 #define STATE_ESTIMATION_NODES__MEASUREMENT_CONVERSION_HPP_
20 
23 #include <nav_msgs/msg/odometry.hpp>
24 #include <geometry_msgs/msg/pose_with_covariance_stamped.hpp>
25 #include <geometry_msgs/msg/twist_with_covariance_stamped.hpp>
26 #include <rclcpp/time.hpp>
27 #include <Eigen/Geometry>
28 
29 namespace autoware
30 {
31 namespace prediction
32 {
33 
34 using MeasurementPose = Measurement<common::types::float32_t,
37 
43 
47 
56 template<typename MeasurementT, typename MessageT>
58  const MessageT &, const Eigen::Isometry3f &)
59 {
60  static_assert(
61  sizeof(MessageT) == -1,
62  "You have to have a specialization for message_to_measurement() function!");
63  // We only have this throw here to make linter happy as this is a non-void function.
64  throw std::runtime_error("You have to have a specialization for message_to_measurement()!");
65 }
66 
77 template<std::int32_t kStateDimentionality, typename FloatT>
78 static constexpr Eigen::Transform<
79  FloatT, kStateDimentionality, Eigen::TransformTraits::Isometry> downscale_isometry(
80  const Eigen::Transform<FloatT, 3, Eigen::TransformTraits::Isometry> & isometry)
81 {
82  static_assert(kStateDimentionality <= 3, "We only handle scaling the isometry down.");
83  using Isometry = Eigen::Transform<
84  FloatT, kStateDimentionality, Eigen::TransformTraits::Isometry>;
85  Isometry result{Isometry::Identity()};
86  result.linear() = isometry.rotation()
87  .template block<kStateDimentionality, kStateDimentionality>(0, 0);
88  result.translation() = isometry.translation().topRows(kStateDimentionality);
89  return result;
90 }
91 
100 template<>
101 STATE_ESTIMATION_NODES_PUBLIC MeasurementPoseAndSpeed message_to_measurement(
102  const nav_msgs::msg::Odometry & msg,
103  const Eigen::Isometry3f & tf_world_message);
104 
113 template<>
114 STATE_ESTIMATION_NODES_PUBLIC MeasurementSpeed message_to_measurement(
115  const geometry_msgs::msg::TwistWithCovarianceStamped & msg,
116  const Eigen::Isometry3f & tf_world_message);
117 
126 template<>
127 STATE_ESTIMATION_NODES_PUBLIC MeasurementPose message_to_measurement(
128  const geometry_msgs::msg::PoseWithCovarianceStamped & msg,
129  const Eigen::Isometry3f & tf_world_message);
130 
131 } // namespace prediction
132 } // namespace autoware
133 
134 
135 #endif // STATE_ESTIMATION_NODES__MEASUREMENT_CONVERSION_HPP_
autoware::motion::motion_model::ConstantAcceleration::States::POSE_Y
static const index_t POSE_Y
index of y position
Definition: constant_acceleration.hpp:50
autoware::prediction::message_to_measurement
MeasurementT message_to_measurement(const MessageT &, const Eigen::Isometry3f &)
Interface for converting a message into a measurement.
Definition: measurement_conversion.hpp:57
autoware::motion::motion_model::ConstantAcceleration::States::VELOCITY_X
static const index_t VELOCITY_X
index of x velocity
Definition: constant_acceleration.hpp:51
autoware::drivers::vehicle_interface::Odometry
autoware_auto_msgs::msg::VehicleOdometry Odometry
Definition: safety_state_machine.hpp:43
autoware
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
measurement.hpp
autoware::prediction::Measurement
Definition: measurement.hpp:46
motion::planning::recordreplay_planner_nodes::Transform
geometry_msgs::msg::TransformStamped Transform
Definition: recordreplay_planner_node.hpp:56
autoware::motion::motion_model::ConstantAcceleration::States::VELOCITY_Y
static const index_t VELOCITY_Y
index of y velocity
Definition: constant_acceleration.hpp:52
autoware::prediction::MeasurementSpeed
Measurement< common::types::float32_t, motion::motion_model::ConstantAcceleration::States::VELOCITY_X, motion::motion_model::ConstantAcceleration::States::VELOCITY_Y > MeasurementSpeed
Definition: measurement_conversion.hpp:46
autoware::prediction::downscale_isometry
static constexpr Eigen::Transform< FloatT, kStateDimentionality, Eigen::TransformTraits::Isometry > downscale_isometry(const Eigen::Transform< FloatT, 3, Eigen::TransformTraits::Isometry > &isometry)
Downscale the isometry to a lower dimention if needed.
Definition: measurement_conversion.hpp:79
autoware::common::types::float32_t
float float32_t
Definition: types.hpp:36
autoware::motion::motion_model::ConstantAcceleration::States::POSE_X
static const index_t POSE_X
index of x position
Definition: constant_acceleration.hpp:49
autoware::prediction::MeasurementPose
Measurement< common::types::float32_t, motion::motion_model::ConstantAcceleration::States::POSE_X, motion::motion_model::ConstantAcceleration::States::POSE_Y > MeasurementPose
Definition: measurement_conversion.hpp:36
constant_acceleration.hpp
This file defines the constant velocity motion model.
autoware::prediction::MeasurementPoseAndSpeed
Measurement< common::types::float32_t, motion::motion_model::ConstantAcceleration::States::POSE_X, motion::motion_model::ConstantAcceleration::States::POSE_Y, motion::motion_model::ConstantAcceleration::States::VELOCITY_X, motion::motion_model::ConstantAcceleration::States::VELOCITY_Y > MeasurementPoseAndSpeed
Definition: measurement_conversion.hpp:42