mavlink: streams SCALED_IMU fix gyro dt

This commit is contained in:
Daniel Agar 2023-01-13 17:00:16 -05:00
parent 5942194c66
commit c97381c97f
3 changed files with 3 additions and 3 deletions

View File

@ -88,7 +88,7 @@ private:
msg.zacc = (int16_t)accel(2);
// Gyroscope in mrad/s
const float gyro_dt_inv = 1.e6f / (float)imu.delta_velocity_dt;
const float gyro_dt_inv = 1.e6f / (float)imu.delta_angle_dt;
const Vector3f gyro = Vector3f{imu.delta_angle} * gyro_dt_inv * 1000.0f;
msg.xgyro = gyro(0);
msg.ygyro = gyro(1);

View File

@ -88,7 +88,7 @@ private:
msg.zacc = (int16_t)accel(2);
// Gyroscope in mrad/s
const float gyro_dt_inv = 1.e6f / (float)imu.delta_velocity_dt;
const float gyro_dt_inv = 1.e6f / (float)imu.delta_angle_dt;
const Vector3f gyro = Vector3f{imu.delta_angle} * gyro_dt_inv * 1000.0f;
msg.xgyro = gyro(0);
msg.ygyro = gyro(1);

View File

@ -88,7 +88,7 @@ private:
msg.zacc = (int16_t)accel(2);
// Gyroscope in mrad/s
const float gyro_dt_inv = 1.e6f / (float)imu.delta_velocity_dt;
const float gyro_dt_inv = 1.e6f / (float)imu.delta_angle_dt;
const Vector3f gyro = Vector3f{imu.delta_angle} * gyro_dt_inv * 1000.0f;
msg.xgyro = gyro(0);
msg.ygyro = gyro(1);