Copter: CompassMot current calibration

Was using a hardcoded (330) value instead of COMPASS_MAGFIELD_EXPECTED define
This commit is contained in:
Olivier-ADLER 2013-06-27 00:29:01 +02:00 committed by rmackay9
parent 1a3ed2d80b
commit eaa0e36954
1 changed files with 1 additions and 1 deletions

View File

@ -357,7 +357,7 @@ setup_compassmot(uint8_t argc, const Menu::arg *argv)
interference_pct = motor_compensation.length() / (float)COMPASS_MAGFIELD_EXPECTED * 100.0f;
}else{
// interference is impact/amp * (max current seen / max throttle seen) / mag field * 100
interference_pct = motor_compensation.length() * (current_amps_max/throttle_pct_max) / 330.0f * 100.0f;
interference_pct = motor_compensation.length() * (current_amps_max/throttle_pct_max) / (float)COMPASS_MAGFIELD_EXPECTED * 100.0f;
}
cliSerial->printf_P(PSTR("\nInterference at full throttle is %d%% of mag field\n\n"),(int)interference_pct);
}else{