mirror of https://github.com/ArduPilot/ardupilot
Copter: use compass_checks from AP_Arming
User-visible changes: - checks will fail if calibration is in progress - PX4FMU_V1 will now have COMPASS_OFFSETS_MAX of 600, not 500 - if the primary compass is not set to be used then compass checks will always pass
This commit is contained in:
parent
f3a31b988a
commit
ac980fdd47
|
@ -129,62 +129,20 @@ bool AP_Arming_Copter::barometer_checks(bool display_failure)
|
|||
|
||||
bool AP_Arming_Copter::compass_checks(bool display_failure)
|
||||
{
|
||||
// check Compass
|
||||
Compass &compass = _compass; // avoid code churn
|
||||
bool ret = AP_Arming::compass_checks(display_failure);
|
||||
|
||||
if ((checks_to_perform == ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_COMPASS)) {
|
||||
//check if compass has calibrated and requires reboot
|
||||
if (compass.compass_cal_requires_reboot()) {
|
||||
if (display_failure) {
|
||||
gcs_send_text(MAV_SEVERITY_CRITICAL, "PreArm: Compass calibrated requires reboot");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
// check the primary compass is healthy
|
||||
if (!compass.healthy()) {
|
||||
if (display_failure) {
|
||||
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Compass not healthy");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
// check compass learning is on or offsets have been set
|
||||
if (!compass.configured()) {
|
||||
// check compass offsets have been set. AP_Arming only checks
|
||||
// this if learning is off; Copter *always* checks.
|
||||
if (!_compass.configured()) {
|
||||
if (display_failure) {
|
||||
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Compass not calibrated");
|
||||
}
|
||||
return false;
|
||||
ret = false;
|
||||
}
|
||||
|
||||
// check for unreasonable compass offsets
|
||||
Vector3f offsets = compass.get_offsets();
|
||||
if (offsets.length() > COMPASS_OFFSETS_MAX) {
|
||||
if (display_failure) {
|
||||
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Compass offsets too high");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
// check for unreasonable mag field length
|
||||
float mag_field = compass.get_field().length();
|
||||
if (mag_field > COMPASS_MAGFIELD_EXPECTED*1.65f || mag_field < COMPASS_MAGFIELD_EXPECTED*0.35f) {
|
||||
if (display_failure) {
|
||||
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Check mag field");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
// check all compasses point in roughly same direction
|
||||
if (!compass.consistent()) {
|
||||
if (display_failure) {
|
||||
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: inconsistent compasses");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
return true;
|
||||
return ret;
|
||||
}
|
||||
|
||||
bool AP_Arming_Copter::gps_checks(bool display_failure)
|
||||
|
|
|
@ -30,11 +30,11 @@ protected:
|
|||
|
||||
// NOTE! the following check functions *DO* call into AP_Arming:
|
||||
bool ins_checks(bool display_failure) override;
|
||||
bool compass_checks(bool display_failure) override;
|
||||
|
||||
// NOTE! the following check functions *DO NOT* call into AP_Arming!
|
||||
bool gps_checks(bool display_failure);
|
||||
bool fence_checks(bool display_failure);
|
||||
bool compass_checks(bool display_failure);
|
||||
bool board_voltage_checks(bool display_failure);
|
||||
bool parameter_checks(bool display_failure);
|
||||
bool pilot_throttle_checks(bool display_failure);
|
||||
|
|
|
@ -210,12 +210,12 @@ MAV_RESULT Copter::mavlink_compassmot(mavlink_channel_t chan)
|
|||
if (comp_type == AP_COMPASS_MOT_COMP_THROTTLE) {
|
||||
for (uint8_t i=0; i<compass.get_count(); i++) {
|
||||
// interference is impact@fullthrottle / mag field * 100
|
||||
interference_pct[i] = motor_compensation[i].length() / (float)COMPASS_MAGFIELD_EXPECTED * 100.0f;
|
||||
interference_pct[i] = motor_compensation[i].length() / (float)arming.compass_magfield_expected() * 100.0f;
|
||||
}
|
||||
}else{
|
||||
for (uint8_t i=0; i<compass.get_count(); i++) {
|
||||
// interference is impact/amp * (max current seen / max throttle seen) / mag field * 100
|
||||
interference_pct[i] = motor_compensation[i].length() * (current_amps_max/throttle_pct_max) / (float)COMPASS_MAGFIELD_EXPECTED * 100.0f;
|
||||
interference_pct[i] = motor_compensation[i].length() * (current_amps_max/throttle_pct_max) / (float)arming.compass_magfield_expected() * 100.0f;
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -207,22 +207,6 @@
|
|||
# define MAGNETOMETER ENABLED
|
||||
#endif
|
||||
|
||||
// expected magnetic field strength. pre-arm checks will fail if 50% higher or lower than this value
|
||||
#ifndef COMPASS_MAGFIELD_EXPECTED
|
||||
#define COMPASS_MAGFIELD_EXPECTED 530 // pre arm will fail if mag field > 874 or < 185
|
||||
#endif
|
||||
|
||||
// max compass offset length (i.e. sqrt(offs_x^2+offs_y^2+offs_Z^2))
|
||||
#ifndef CONFIG_ARCH_BOARD_PX4FMU_V1
|
||||
#ifndef COMPASS_OFFSETS_MAX
|
||||
# define COMPASS_OFFSETS_MAX 600 // PX4 onboard compass has high offsets
|
||||
#endif
|
||||
#else // SITL, etc
|
||||
#ifndef COMPASS_OFFSETS_MAX
|
||||
# define COMPASS_OFFSETS_MAX 500
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifndef COMPASS_CAL_STICK_GESTURE_TIME
|
||||
#define COMPASS_CAL_STICK_GESTURE_TIME 2.0f // 2 seconds
|
||||
#endif
|
||||
|
|
Loading…
Reference in New Issue