|
Autoware.Auto
|
|
Functionality relating to prediction, including state estimation, kinematic prediction, maneuver-based prediction, map-aware prediction etc... More...
Namespaces | |
| kalman_filter | |
| Contains the kalman filter package and related classes and functionality. | |
| state_estimation_nodes | |
Classes | |
| class | KalmanFilterWrapper |
| This class provides a high level interface to the Kalman Filter allowing to predict the state of the filter with time and observe it by receiving ROS messages. More... | |
| class | Measurement |
| class | MeasurementBasedTimeKeeper |
| This is a time storage class that keeps the time with respect to the clock that timestamped the last measurement. More... | |
| class | Time |
| This class describes a time point with respect to some time reference frame. More... | |
Enumerations | |
| enum | TimeReferenceFrame { TimeReferenceFrame::kGlobal, TimeReferenceFrame::kMeasurement } |
| This class describes a time reference frame. This is used to define in which clock a particular time point lives. More... | |
Functions | |
| template<typename MeasurementT , typename MessageT > | |
| MeasurementT | message_to_measurement (const MessageT &, const Eigen::Isometry3f &) |
| Interface for converting a message into a measurement. More... | |
| template<std::int32_t kStateDimentionality, typename FloatT > | |
| 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. More... | |
| template<> | |
| STATE_ESTIMATION_NODES_PUBLIC MeasurementPoseAndSpeed | message_to_measurement (const nav_msgs::msg::Odometry &msg, const Eigen::Isometry3f &tf_world_message) |
| Specialization of message_to_measurement for odometry message. More... | |
| template<> | |
| STATE_ESTIMATION_NODES_PUBLIC MeasurementSpeed | message_to_measurement (const geometry_msgs::msg::TwistWithCovarianceStamped &msg, const Eigen::Isometry3f &tf_world_message) |
| Specialization of message_to_measurement for twist message. More... | |
| template<> | |
| STATE_ESTIMATION_NODES_PUBLIC MeasurementPose | message_to_measurement (const geometry_msgs::msg::PoseWithCovarianceStamped &msg, const Eigen::Isometry3f &tf_world_message) |
| Specialization of message_to_measurement for pose message. More... | |
Functionality relating to prediction, including state estimation, kinematic prediction, maneuver-based prediction, map-aware prediction etc...
| using autoware::prediction::ConstantAccelerationFilter = typedef KalmanFilterWrapper<motion::motion_model::ConstantAcceleration, 6, 2> |
| using autoware::prediction::GlobalTime = typedef Time<TimeReferenceFrame::kGlobal> |
Utility typedef to define time based on some global clock.
Utility typedef to define time based on a measurement clock.
| typedef Measurement< common::types::float32_t, ConstantAcceleration::States::POSE_X, ConstantAcceleration::States::POSE_Y > autoware::prediction::MeasurementPose |
| typedef Measurement< common::types::float32_t, ConstantAcceleration::States::VELOCITY_X, ConstantAcceleration::States::VELOCITY_Y > autoware::prediction::MeasurementSpeed |
|
strong |
|
staticconstexpr |
Downscale the isometry to a lower dimention if needed.
| [in] | isometry | The isometry transform |
| kStateDimentionality | Dimentionality of the space. |
| FloatT | Type of scalar. |
| MeasurementPose autoware::prediction::message_to_measurement | ( | const geometry_msgs::msg::PoseWithCovarianceStamped & | msg, |
| const Eigen::Isometry3f & | tf_world_message | ||
| ) |
Specialization of message_to_measurement for pose message.
| [in] | msg | The pose message. |
| [in] | tf_world_message | A transform from message frame to world frame. |
| MeasurementSpeed autoware::prediction::message_to_measurement | ( | const geometry_msgs::msg::TwistWithCovarianceStamped & | msg, |
| const Eigen::Isometry3f & | tf_world_message | ||
| ) |
Specialization of message_to_measurement for twist message.
| [in] | msg | The twist message. |
| [in] | tf_world_message | A transform from message frame to world frame. |
| MeasurementT autoware::prediction::message_to_measurement | ( | const MessageT & | , |
| const Eigen::Isometry3f & | |||
| ) |
Interface for converting a message into a measurement.
| MeasurementT | Type of measurement. |
| MessageT | Type of ROS 2 message. |
| MeasurementPoseAndSpeed autoware::prediction::message_to_measurement | ( | const nav_msgs::msg::Odometry & | msg, |
| const Eigen::Isometry3f & | tf_world_message | ||
| ) |
Specialization of message_to_measurement for odometry message.
| [in] | msg | The odometry message. |
| [in] | tf_world_message | A transform from message frame to world frame. |