GCS_MAVLink: correct send_scaled_imu gyro-count check

This commit is contained in:
Peter Barker 2021-11-28 08:13:56 +11:00 committed by Peter Barker
parent 40d75302c2
commit ba63e9a17b
1 changed files with 1 additions and 1 deletions

View File

@ -1789,7 +1789,7 @@ void GCS_MAVLINK::send_scaled_imu(uint8_t instance, void (*send_fn)(mavlink_chan
have_data = true;
}
Vector3f gyro{};
if (ins.get_accel_count() > instance) {
if (ins.get_gyro_count() > instance) {
gyro = ins.get_gyro(instance);
have_data = true;
}