#kalman-filter #filter #kalman #navigation #orientation

no-std eskf

基于误差状态卡尔曼滤波器(ESKF)的导航滤波器

3 个不稳定版本

0.2.0 2021年3月22日
0.1.1 2021年3月18日
0.1.0 2021年3月18日

#139机器人

MIT/Apache

1.5MB
374

误差状态卡尔曼滤波器(ESKF)

Continuous integration Crates.io version Docs.rs version

这个 crate 实现了一个基于 误差状态卡尔曼滤波器 的导航滤波器。

这个 crate 支持 no_std 环境,但对数学的优化尝试很少,以优化 no_std

误差状态卡尔曼滤波器(ESKF)

一个 误差状态卡尔曼滤波器 是一个基于常规卡尔曼滤波器的导航滤波器,更具体地说,是基于 扩展卡尔曼滤波器,它通过建模系统的“误差状态”而不是显式地建模系统的运动。

导航滤波器用于跟踪通过 惯性测量单元(IMU) 和某种观察滤波器真实状态的手段(如 GPS、LIDAR 或视觉里程计)来感知其状态的物体的 位置速度方向

用法

use eskf;
use nalgebra::{Vector3, Point3};
use std::time::Duration;

// Create a default filter, modelling a perfect IMU without drift
let mut filter = eskf::Builder::new().build();
// Read measurements from IMU
let imu_acceleration = Vector3::new(0.0, 0.0, -9.81);
let imu_rotation = Vector3::zeros();
// Tell the filter what we just measured
filter.predict(imu_acceleration, imu_rotation, Duration::from_millis(1000));
// Check the new state of the filter
// filter.position or filter.velocity...
// ...
// After some time we get an observation of the actual state
filter.observe_position(
    Point3::new(0.0, 0.0, 0.0),
    eskf::ESKF::variance_from_element(0.1))
        .expect("Filter update failed");
// Since we have supplied an observation of the actual state of the filter the states have now
// been updated. The uncertainty of the filter is also updated to reflect this new information.

依赖项