AP_Compass: revert AP_Math class change

This commit is contained in:
Andrew Tridgell 2015-05-05 12:35:20 +10:00
parent d2167633f0
commit 015fce5183
3 changed files with 4 additions and 4 deletions

View File

@ -284,7 +284,7 @@ bool AP_Compass_AK8963_MPU9250::read_raw()
_mag_y = (float) int16_val(rx, 2);
_mag_z = (float) int16_val(rx, 3);
if (AP_Math::is_zero(_mag_x) && AP_Math::is_zero(_mag_y) && AP_Math::is_zero(_mag_z)) {
if (is_zero(_mag_x) && is_zero(_mag_y) && is_zero(_mag_z)) {
return false;
}

View File

@ -60,7 +60,7 @@ void AP_Compass_Backend::apply_corrections(Vector3f &mag, uint8_t i)
being applied so it can be logged correctly
*/
mag += offsets;
if(_compass._motor_comp_type != AP_COMPASS_MOT_COMP_DISABLED && !AP_Math::is_zero(_compass._thr_or_curr)) {
if(_compass._motor_comp_type != AP_COMPASS_MOT_COMP_DISABLED && !is_zero(_compass._thr_or_curr)) {
state.motor_offset = mot * _compass._thr_or_curr;
mag += state.motor_offset;
} else {

View File

@ -533,7 +533,7 @@ bool Compass::configured(uint8_t i)
}
// exit immediately if all offsets are zero
if (AP_Math::is_zero(get_offsets(i).length())) {
if (is_zero(get_offsets(i).length())) {
return false;
}
@ -575,7 +575,7 @@ void Compass::setHIL(float roll, float pitch, float yaw)
// create a rotation matrix for the given attitude
R.from_euler(roll, pitch, yaw);
if (!AP_Math::is_equal(_hil.last_declination,get_declination())) {
if (!is_equal(_hil.last_declination,get_declination())) {
_setup_earth_field();
_hil.last_declination = get_declination();
}