Autoware.Auto
kalman_filter_wrapper.hpp File Reference
#include <common/types.hpp>
#include <measurement_conversion/measurement_typedefs.hpp>
#include <nav_msgs/msg/odometry.hpp>
#include <state_estimation/kalman_filter/kalman_filter.hpp>
#include <state_estimation_nodes/filter_typedefs.hpp>
#include <state_estimation_nodes/history.hpp>
#include <state_estimation_nodes/steady_time_grid.hpp>
#include <state_estimation_nodes/visibility_control.hpp>
#include <state_vector/common_states.hpp>
#include <Eigen/Core>
#include <Eigen/Geometry>
#include <chrono>
#include <cstdint>
#include <limits>
#include <memory>
#include <string>
#include <vector>
Include dependency graph for kalman_filter_wrapper.hpp:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

class  autoware::common::state_estimation::KalmanFilterWrapper< FilterT >
 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...
 

Namespaces

 autoware
 This file defines the lanelet2_map_provider_node class.
 
 autoware::common
 
 autoware::common::state_estimation
 

Typedefs

using autoware::common::state_estimation::ConstantAccelerationFilterWrapperXY = KalmanFilterWrapper< ConstAccelerationKalmanFilterXY >
 
using autoware::common::state_estimation::ConstantAccelerationFilterWrapperXYZRPY = KalmanFilterWrapper< ConstAccelerationKalmanFilterXYZRPY >