Go to the documentation of this file.
18 #ifndef STATE_ESTIMATION_NODES__MEASUREMENT_CONVERSION_HPP_
19 #define STATE_ESTIMATION_NODES__MEASUREMENT_CONVERSION_HPP_
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>
56 template<
typename MeasurementT,
typename MessageT>
58 const MessageT &,
const Eigen::Isometry3f &)
61 sizeof(MessageT) == -1,
62 "You have to have a specialization for message_to_measurement() function!");
64 throw std::runtime_error(
"You have to have a specialization for message_to_measurement()!");
77 template<std::
int32_t kStateDimentionality,
typename FloatT>
80 const Eigen::Transform<FloatT, 3, Eigen::TransformTraits::Isometry> & isometry)
82 static_assert(kStateDimentionality <= 3,
"We only handle scaling the isometry down.");
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);
103 const Eigen::Isometry3f & tf_world_message);
115 const geometry_msgs::msg::TwistWithCovarianceStamped & msg,
116 const Eigen::Isometry3f & tf_world_message);
128 const geometry_msgs::msg::PoseWithCovarianceStamped & msg,
129 const Eigen::Isometry3f & tf_world_message);
135 #endif // STATE_ESTIMATION_NODES__MEASUREMENT_CONVERSION_HPP_
static const index_t POSE_Y
index of y position
Definition: constant_acceleration.hpp:50
MeasurementT message_to_measurement(const MessageT &, const Eigen::Isometry3f &)
Interface for converting a message into a measurement.
Definition: measurement_conversion.hpp:57
static const index_t VELOCITY_X
index of x velocity
Definition: constant_acceleration.hpp:51
autoware_auto_msgs::msg::VehicleOdometry Odometry
Definition: safety_state_machine.hpp:43
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
Definition: measurement.hpp:46
geometry_msgs::msg::TransformStamped Transform
Definition: recordreplay_planner_node.hpp:56
static const index_t VELOCITY_Y
index of y velocity
Definition: constant_acceleration.hpp:52
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
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
float float32_t
Definition: types.hpp:36
static const index_t POSE_X
index of x position
Definition: constant_acceleration.hpp:49
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
This file defines the constant velocity motion model.
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