mirror of https://github.com/ArduPilot/ardupilot
GCS_Common: Fix issue #19599 Failed to build Pixhawk1 with O3
This commit is contained in:
parent
f80a9ba3ce
commit
20b3add9fb
|
@ -1769,11 +1769,13 @@ void GCS_MAVLINK::send_scaled_imu(uint8_t instance, void (*send_fn)(mavlink_chan
|
||||||
#if HAL_INS_ENABLED
|
#if HAL_INS_ENABLED
|
||||||
const AP_InertialSensor &ins = AP::ins();
|
const AP_InertialSensor &ins = AP::ins();
|
||||||
const Compass &compass = AP::compass();
|
const Compass &compass = AP::compass();
|
||||||
|
int16_t _temperature = 0;
|
||||||
|
|
||||||
bool have_data = false;
|
bool have_data = false;
|
||||||
Vector3f accel{};
|
Vector3f accel{};
|
||||||
if (ins.get_accel_count() > instance) {
|
if (ins.get_accel_count() > instance) {
|
||||||
accel = ins.get_accel(instance);
|
accel = ins.get_accel(instance);
|
||||||
|
_temperature = ins.get_temperature(instance)*100;
|
||||||
have_data = true;
|
have_data = true;
|
||||||
}
|
}
|
||||||
Vector3f gyro{};
|
Vector3f gyro{};
|
||||||
|
@ -1801,7 +1803,7 @@ void GCS_MAVLINK::send_scaled_imu(uint8_t instance, void (*send_fn)(mavlink_chan
|
||||||
mag.x,
|
mag.x,
|
||||||
mag.y,
|
mag.y,
|
||||||
mag.z,
|
mag.z,
|
||||||
int16_t(ins.get_temperature(instance)*100));
|
_temperature);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue