Browse Source

Copter: CompassMot current calibration

Was using a hardcoded (330) value instead of COMPASS_MAGFIELD_EXPECTED define
mission-4.1.18
Olivier-ADLER 12 years ago committed by rmackay9
parent
commit
eaa0e36954
  1. 2
      ArduCopter/setup.pde

2
ArduCopter/setup.pde

@ -357,7 +357,7 @@ setup_compassmot(uint8_t argc, const Menu::arg *argv) @@ -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{

Loading…
Cancel
Save