mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
AP_InertialSensor: fixed build warnings
This commit is contained in:
parent
ac3fc2f373
commit
6a2c585632
@ -443,8 +443,8 @@ bool AP_InertialSensor::_calculate_trim(const Vector3f &accel_sample, float& tri
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
hal.console->printf_P(PSTR("Trim OK: roll=%.2f pitch=%.2f\n"),
|
hal.console->printf_P(PSTR("Trim OK: roll=%.2f pitch=%.2f\n"),
|
||||||
degrees(trim_roll),
|
(double)degrees(trim_roll),
|
||||||
degrees(trim_pitch));
|
(double)degrees(trim_pitch));
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user