AP_Arming: make expected magnetic field strength available to subclasses
This commit is contained in:
parent
8159c4b747
commit
1f37366c5b
@ -21,6 +21,7 @@
|
||||
// this can also be overridden for specific boards in the HAL
|
||||
#define AP_ARMING_COMPASS_OFFSETS_MAX 600
|
||||
#endif
|
||||
#define AP_ARMING_COMPASS_MAGFIELD_EXPECTED 530
|
||||
#define AP_ARMING_COMPASS_MAGFIELD_MIN 185 // 0.35 * 530 milligauss
|
||||
#define AP_ARMING_COMPASS_MAGFIELD_MAX 875 // 1.65 * 530 milligauss
|
||||
#define AP_ARMING_BOARD_VOLTAGE_MIN 4.3f
|
||||
@ -88,6 +89,11 @@ AP_Arming::AP_Arming(const AP_AHRS &ahrs_ref, const AP_Baro &baro, Compass &comp
|
||||
memset(last_gyro_pass_ms, 0, sizeof(last_gyro_pass_ms));
|
||||
}
|
||||
|
||||
uint16_t AP_Arming::compass_magfield_expected() const
|
||||
{
|
||||
return AP_ARMING_COMPASS_MAGFIELD_EXPECTED;
|
||||
}
|
||||
|
||||
bool AP_Arming::is_armed()
|
||||
{
|
||||
return require == NONE || armed;
|
||||
|
@ -65,6 +65,8 @@ public:
|
||||
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
uint16_t compass_magfield_expected() const;
|
||||
|
||||
protected:
|
||||
// Parameters
|
||||
AP_Int8 require;
|
||||
@ -96,7 +98,7 @@ protected:
|
||||
|
||||
virtual bool ins_checks(bool report);
|
||||
|
||||
bool compass_checks(bool report);
|
||||
virtual bool compass_checks(bool report);
|
||||
|
||||
bool gps_checks(bool report);
|
||||
|
||||
@ -109,4 +111,5 @@ protected:
|
||||
bool manual_transmitter_checks(bool report);
|
||||
|
||||
virtual enum HomeState home_status() const = 0;
|
||||
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user