mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-24 01:28:29 -04:00
GCS_MAVLink: correct send_scaled_imu gyro-count check
This commit is contained in:
parent
40d75302c2
commit
ba63e9a17b
@ -1789,7 +1789,7 @@ void GCS_MAVLINK::send_scaled_imu(uint8_t instance, void (*send_fn)(mavlink_chan
|
|||||||
have_data = true;
|
have_data = true;
|
||||||
}
|
}
|
||||||
Vector3f gyro{};
|
Vector3f gyro{};
|
||||||
if (ins.get_accel_count() > instance) {
|
if (ins.get_gyro_count() > instance) {
|
||||||
gyro = ins.get_gyro(instance);
|
gyro = ins.get_gyro(instance);
|
||||||
have_data = true;
|
have_data = true;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user