mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 00:58:37 -04:00
AP_NavEKF2: Get IMU accelerometer body position offset data
This commit is contained in:
parent
397033b7c3
commit
064a106808
@ -276,8 +276,10 @@ void NavEKF2_core::readIMUData()
|
||||
// use the nominated imu or primary if not available
|
||||
if (ins.use_accel(imu_index)) {
|
||||
readDeltaVelocity(imu_index, imuDataNew.delVel, imuDataNew.delVelDT);
|
||||
accelPosOffset = ins.get_imu_pos_offset(imu_index);
|
||||
} else {
|
||||
readDeltaVelocity(ins.get_primary_accel(), imuDataNew.delVel, imuDataNew.delVelDT);
|
||||
accelPosOffset = ins.get_imu_pos_offset(ins.get_primary_accel());
|
||||
}
|
||||
|
||||
// Get delta angle data from primary gyro or primary if not available
|
||||
|
@ -908,6 +908,8 @@ private:
|
||||
bool gndOffsetValid; // true when the ground offset state can still be considered valid
|
||||
Vector3f delAngBodyOF; // bias corrected delta angle of the vehicle IMU measured summed across the time since the last OF measurement
|
||||
float delTimeOF; // time that delAngBodyOF is summed across
|
||||
Vector3f accelPosOffset; // position of IMU accelerometer unit in body frame (m)
|
||||
|
||||
|
||||
// Range finder
|
||||
float baroHgtOffset; // offset applied when when switching to use of Baro height
|
||||
|
Loading…
Reference in New Issue
Block a user