mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_HAL_SITL: float to double promotion via cos instead of cosf
This commit is contained in:
parent
4f1dd2c8a4
commit
7b95241306
@ -103,7 +103,7 @@ uint16_t SITL_State::_ground_sonar(void)
|
|||||||
if (fabsf(_sitl->state.rollDeg) < 90 &&
|
if (fabsf(_sitl->state.rollDeg) < 90 &&
|
||||||
fabsf(_sitl->state.pitchDeg) < 90) {
|
fabsf(_sitl->state.pitchDeg) < 90) {
|
||||||
// adjust for apparent altitude with roll
|
// adjust for apparent altitude with roll
|
||||||
altitude /= cos(radians(_sitl->state.rollDeg)) * cos(radians(_sitl->state.pitchDeg));
|
altitude /= cosf(radians(_sitl->state.rollDeg)) * cosf(radians(_sitl->state.pitchDeg));
|
||||||
|
|
||||||
altitude += _sitl->sonar_noise * _rand_float();
|
altitude += _sitl->sonar_noise * _rand_float();
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user