mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 05:58:30 -04:00
SITL: update for compass API change
This commit is contained in:
parent
baa4ecc2ea
commit
dfe3af0b30
@ -40,9 +40,7 @@ void SITL_State::_update_compass(float rollDeg, float pitchDeg, float yawDeg)
|
||||
}
|
||||
_compass->setHIL(radians(rollDeg), radians(pitchDeg), radians(yawDeg));
|
||||
Vector3f noise = _rand_vec3f() * _sitl->mag_noise;
|
||||
_compass->mag_x += noise.x;
|
||||
_compass->mag_y += noise.y;
|
||||
_compass->mag_z += noise.z;
|
||||
_compass->set_field(_compass->get_field() + noise);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
Loading…
Reference in New Issue
Block a user