11#include "config/parameters.hpp"
12#include "custom_interfaces/msg/velocities.hpp"
19 Eigen::Vector3d
_state_ = Eigen::Vector3d::Zero();
54 void predict(Eigen::Vector3d& state, Eigen::Matrix3d& covariance,
55 const Eigen::Matrix3d& process_noise_matrix,
const rclcpp::Time last_update,
71 void correct_wheels(Eigen::Vector3d& state, Eigen::Matrix3d& covariance,
73 double steering_angle);
75 void correct_imu(Eigen::Vector3d& state, Eigen::Matrix3d& covariance,
bool steering_angle_received_
common_lib::structures::Velocities get_velocities() override
std::shared_ptr< VEObservationModel > observation_model_
Eigen::Matrix3d _covariance_
bool _has_made_prediction_
rclcpp::Time _last_update_
common_lib::sensor_data::ImuData imu_data_
void predict(Eigen::Vector3d &state, Eigen::Matrix3d &covariance, const Eigen::Matrix3d &process_noise_matrix, const rclcpp::Time last_update, common_lib::sensor_data::ImuData &imu_data)
Predict velocities at the next index based on IMU measurements and current state.
std::shared_ptr< BaseVelocityProcessModel > process_model
void correct_wheels(Eigen::Vector3d &state, Eigen::Matrix3d &covariance, common_lib::sensor_data::WheelEncoderData &wss_data, double motor_rpm, double steering_angle)
Correct the state estimate based on wheel speed sensor, resolver, and steering data.
void imu_callback(const common_lib::sensor_data::ImuData &imu_data) override
Callback function for the IMU data that should be called by adapters when new IMU data is available.
Eigen::MatrixXd _wheels_measurement_noise_matrix_
void correct_imu(Eigen::Vector3d &state, Eigen::Matrix3d &covariance, common_lib::sensor_data::ImuData &imu_data)
void motor_rpm_callback(double motor_rpm) override
Callback function for the motor RPM data that should be called by adapters when new motor RPM data is...
common_lib::sensor_data::WheelEncoderData wss_data_
Eigen::MatrixXd _imu_measurement_noise_matrix_
Eigen::Matrix3d _process_noise_matrix_
void wss_callback(const common_lib::sensor_data::WheelEncoderData &wss_data) override
Callback function for the wheel speed sensor data that should be called by adapters when new wheel sp...
common_lib::car_parameters::CarParameters car_parameters_
void steering_callback(double steering_angle) override
Callback function for the steering angle data that should be called by adapters when new steering ang...
Interface for velocity estimators.
Struct for wheel encoder data.