以下所有内容均为高翔大神所注的《自动驾驶与机器人中的SLAM技术》中的内容
融合导航
- EKF和优化的关系
- 组合导航eskf中的预测部分,主要是F矩阵的构建
cpp
template <typename S>
bool ESKF<S>::Predict(const IMU& imu) {
assert(imu.timestamp_ >= current_time_);
double dt = imu.timestamp_ - current_time_;
if (dt > (5 * options_.imu_dt_) || dt < 0) {
// 时间间隔不对,可能是第一个IMU数据,没有历史信息
LOG(INFO) << "skip this imu because dt_ = " << dt;
current_time_ = imu.timestamp_;
return false;
}
// nominal state 递推
VecT new_p = p_ + v_ * dt + 0.5 * (R_ * (imu.acce_ - ba_)) * dt * dt + 0.5 * g_ * dt * dt;
VecT new_v = v_ + R_ * (imu.acce_ - ba_) * dt + g_ * dt;
SO3 new_R = R_ * SO3::exp((imu.gyro_ - bg_) * dt);
R_ = new_R;
v_ = new_v;
p_ = new_p;
// 其余状态维度不变
// error state 递推
// 计算运动过程雅可比矩阵 F,见(3.47)
// F实际上是稀疏矩阵,也可以不用矩阵形式进行相乘而是写成散装形式,这里为了教学方便,使用矩阵形式
Mat18T F = Mat18T::Identity(); // 主对角线
F.template block<3, 3>(0, 3) = Mat3T::Identity() * dt; // p 对 v
F.template block<3, 3>(3, 6) = -R_.matrix() * SO3::hat(imu.acce_ - ba_) * dt; // v对theta
F.template block<3, 3>(3, 12) = -R_.matrix() * dt; // v 对 ba
F.template block<3, 3>(3, 15) = Mat3T::Identity() * dt; // v 对 g
F.template block<3, 3>(6, 6) = SO3::exp(-(imu.gyro_ - bg_) * dt).matrix(); // theta 对 theta
F.template block<3, 3>(6, 9) = -Mat3T::Identity() * dt; // theta 对 bg
// mean and cov prediction
dx_ = F * dx_; // 这行其实没必要算,dx_在重置之后应该为零,因此这步可以跳过,但F需要参与Cov部分计算,所以保留
cov_ = F * cov_.eval() * F.transpose() + Q_;
current_time_ = imu.timestamp_;
return true;
}
- 以下是速度量测,主要是H矩阵的构建
cpp
template <typename S>
bool ESKF<S>::ObserveWheelSpeed(const Odom& odom) {
assert(odom.timestamp_ >= current_time_);
// odom 修正以及雅可比
// 使用三维的轮速观测,H为3x18,大部分为零
Eigen::Matrix<S, 3, 18> H = Eigen::Matrix<S, 3, 18>::Zero();
H.template block<3, 3>(0, 3) = Mat3T::Identity();
// 卡尔曼增益
Eigen::Matrix<S, 18, 3> K = cov_ * H.transpose() * (H * cov_ * H.transpose() + odom_noise_).inverse();
// velocity obs
double velo_l = options_.wheel_radius_ * odom.left_pulse_ / options_.circle_pulse_ * 2 * M_PI / options_.odom_span_;
double velo_r = options_.wheel_radius_ * odom.right_pulse_ / options_.circle_pulse_ * 2 * M_PI / options_.odom_span_;
double average_vel = 0.5 * (velo_l + velo_r);
VecT vel_odom(average_vel, 0.0, 0.0);
VecT vel_world = R_ * vel_odom;
dx_ = K * (vel_world - v_);//v_是状态递推后的速度
// update cov
cov_ = (Mat18T::Identity() - K * H) * cov_;
UpdateAndReset();
return true;
}
- 以下是GPS的量测,主要任然是H矩阵的构建
cpp
template <typename S>
bool ESKF<S>::ObserveGps(const GNSS& gnss) {
/// GNSS 观测的修正
assert(gnss.unix_time_ >= current_time_);
if (first_gnss_) {
R_ = gnss.utm_pose_.so3();
p_ = gnss.utm_pose_.translation();
first_gnss_ = false;
current_time_ = gnss.unix_time_;
return true;
}
assert(gnss.heading_valid_);
ObserveSE3(gnss.utm_pose_, options_.gnss_pos_noise_, options_.gnss_ang_noise_);
current_time_ = gnss.unix_time_;
return true;
}
template <typename S>
bool ESKF<S>::ObserveSE3(const SE3& pose, double trans_noise, double ang_noise) {
/// 既有旋转,也有平移
/// 观测状态变量中的p, R,H为6x18,其余为零
Eigen::Matrix<S, 6, 18> H = Eigen::Matrix<S, 6, 18>::Zero();
H.template block<3, 3>(0, 0) = Mat3T::Identity(); // P部分
H.template block<3, 3>(3, 6) = Mat3T::Identity(); // R部分(3.66)
// 卡尔曼增益和更新过程
Vec6d noise_vec;
noise_vec << trans_noise, trans_noise, trans_noise, ang_noise, ang_noise, ang_noise;
Mat6d V = noise_vec.asDiagonal();
Eigen::Matrix<S, 18, 6> K = cov_ * H.transpose() * (H * cov_ * H.transpose() + V).inverse();
// 更新x和cov
Vec6d innov = Vec6d::Zero();
innov.template head<3>() = (pose.translation() - p_); // 平移部分
innov.template tail<3>() = (R_.inverse() * pose.so3()).log(); // 旋转部分(3.67)
dx_ = K * innov;
cov_ = (Mat18T::Identity() - K * H) * cov_;
UpdateAndReset();
return true;
}