mirror of https://github.com/ArduPilot/ardupilot
Copter: relax pre-arm checks for mag field
previously it was 50% ~ 150% of expected mag field but now expanded to 35% ~ 165%.
This commit is contained in:
parent
8c49ed78a5
commit
ed3bf2c1e7
|
@ -249,7 +249,7 @@ static void pre_arm_checks(bool display_failure)
|
|||
|
||||
// check for unreasonable mag field length
|
||||
float mag_field = pythagorous3(compass.mag_x, compass.mag_y, compass.mag_z);
|
||||
if (mag_field > COMPASS_MAGFIELD_EXPECTED*1.5 || mag_field < COMPASS_MAGFIELD_EXPECTED*0.5) {
|
||||
if (mag_field > COMPASS_MAGFIELD_EXPECTED*1.65 || mag_field < COMPASS_MAGFIELD_EXPECTED*0.35) {
|
||||
if (display_failure) {
|
||||
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: Check mag field"));
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue