SITL: update for compass API change

This commit is contained in:
Andrew Tridgell 2013-12-09 14:11:03 +11:00
parent baa4ecc2ea
commit dfe3af0b30

View File

@ -40,9 +40,7 @@ void SITL_State::_update_compass(float rollDeg, float pitchDeg, float yawDeg)
} }
_compass->setHIL(radians(rollDeg), radians(pitchDeg), radians(yawDeg)); _compass->setHIL(radians(rollDeg), radians(pitchDeg), radians(yawDeg));
Vector3f noise = _rand_vec3f() * _sitl->mag_noise; Vector3f noise = _rand_vec3f() * _sitl->mag_noise;
_compass->mag_x += noise.x; _compass->set_field(_compass->get_field() + noise);
_compass->mag_y += noise.y;
_compass->mag_z += noise.z;
} }
#endif #endif