mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 14:08:45 -04:00
AP_Arming: use singletons in AP_Arming
This commit is contained in:
parent
051c811bfb
commit
598f82a2fe
@ -78,11 +78,7 @@ const AP_Param::GroupInfo AP_Arming::var_info[] = {
|
|||||||
|
|
||||||
//The function point is particularly hacky, hacky, tacky
|
//The function point is particularly hacky, hacky, tacky
|
||||||
//but I don't want to reimplement messaging to GCS at the moment:
|
//but I don't want to reimplement messaging to GCS at the moment:
|
||||||
AP_Arming::AP_Arming(const AP_AHRS &ahrs_ref, Compass &compass,
|
AP_Arming::AP_Arming() :
|
||||||
const AP_BattMonitor &battery) :
|
|
||||||
ahrs(ahrs_ref),
|
|
||||||
_compass(compass),
|
|
||||||
_battery(battery),
|
|
||||||
arming_method(NONE)
|
arming_method(NONE)
|
||||||
{
|
{
|
||||||
AP_Param::setup_object_defaults(this, var_info);
|
AP_Param::setup_object_defaults(this, var_info);
|
||||||
@ -154,7 +150,7 @@ bool AP_Arming::airspeed_checks(bool report)
|
|||||||
{
|
{
|
||||||
if ((checks_to_perform & ARMING_CHECK_ALL) ||
|
if ((checks_to_perform & ARMING_CHECK_ALL) ||
|
||||||
(checks_to_perform & ARMING_CHECK_AIRSPEED)) {
|
(checks_to_perform & ARMING_CHECK_AIRSPEED)) {
|
||||||
const AP_Airspeed *airspeed = ahrs.get_airspeed();
|
const AP_Airspeed *airspeed = AP_Airspeed::get_singleton();
|
||||||
if (airspeed == nullptr) {
|
if (airspeed == nullptr) {
|
||||||
// not an airspeed capable vehicle
|
// not an airspeed capable vehicle
|
||||||
return true;
|
return true;
|
||||||
@ -305,6 +301,8 @@ bool AP_Arming::compass_checks(bool report)
|
|||||||
if ((checks_to_perform) & ARMING_CHECK_ALL ||
|
if ((checks_to_perform) & ARMING_CHECK_ALL ||
|
||||||
(checks_to_perform) & ARMING_CHECK_COMPASS) {
|
(checks_to_perform) & ARMING_CHECK_COMPASS) {
|
||||||
|
|
||||||
|
Compass &_compass = AP::compass();
|
||||||
|
|
||||||
// avoid Compass::use_for_yaw(void) as it implicitly calls healthy() which can
|
// avoid Compass::use_for_yaw(void) as it implicitly calls healthy() which can
|
||||||
// incorrectly skip the remaining checks, pass the primary instance directly
|
// incorrectly skip the remaining checks, pass the primary instance directly
|
||||||
if (!_compass.use_for_yaw(_compass.get_primary())) {
|
if (!_compass.use_for_yaw(_compass.get_primary())) {
|
||||||
@ -391,7 +389,7 @@ bool AP_Arming::gps_checks(bool report)
|
|||||||
// check AHRS and GPS are within 10m of each other
|
// check AHRS and GPS are within 10m of each other
|
||||||
Location gps_loc = gps.location();
|
Location gps_loc = gps.location();
|
||||||
Location ahrs_loc;
|
Location ahrs_loc;
|
||||||
if (ahrs.get_position(ahrs_loc)) {
|
if (AP::ahrs().get_position(ahrs_loc)) {
|
||||||
const float distance = location_diff(gps_loc, ahrs_loc).length();
|
const float distance = location_diff(gps_loc, ahrs_loc).length();
|
||||||
if (distance > AP_ARMING_AHRS_GPS_ERROR_MAX) {
|
if (distance > AP_ARMING_AHRS_GPS_ERROR_MAX) {
|
||||||
if (report) {
|
if (report) {
|
||||||
@ -423,6 +421,8 @@ bool AP_Arming::battery_checks(bool report)
|
|||||||
if ((checks_to_perform & ARMING_CHECK_ALL) ||
|
if ((checks_to_perform & ARMING_CHECK_ALL) ||
|
||||||
(checks_to_perform & ARMING_CHECK_BATTERY)) {
|
(checks_to_perform & ARMING_CHECK_BATTERY)) {
|
||||||
|
|
||||||
|
const AP_BattMonitor &_battery = AP::battery();
|
||||||
|
|
||||||
if (AP_Notify::flags.failsafe_battery) {
|
if (AP_Notify::flags.failsafe_battery) {
|
||||||
check_failed(ARMING_CHECK_BATTERY, report, "Battery failsafe on");
|
check_failed(ARMING_CHECK_BATTERY, report, "Battery failsafe on");
|
||||||
return false;
|
return false;
|
||||||
|
@ -9,6 +9,13 @@
|
|||||||
|
|
||||||
class AP_Arming {
|
class AP_Arming {
|
||||||
public:
|
public:
|
||||||
|
|
||||||
|
AP_Arming();
|
||||||
|
|
||||||
|
/* Do not allow copies */
|
||||||
|
AP_Arming(const AP_Arming &other) = delete;
|
||||||
|
AP_Arming &operator=(const AP_Arming&) = delete;
|
||||||
|
|
||||||
enum ArmingChecks {
|
enum ArmingChecks {
|
||||||
ARMING_CHECK_NONE = 0x0000,
|
ARMING_CHECK_NONE = 0x0000,
|
||||||
ARMING_CHECK_ALL = 0x0001,
|
ARMING_CHECK_ALL = 0x0001,
|
||||||
@ -62,8 +69,6 @@ public:
|
|||||||
static const struct AP_Param::GroupInfo var_info[];
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
AP_Arming(const AP_AHRS &ahrs_ref, Compass &compass,
|
|
||||||
const AP_BattMonitor &battery);
|
|
||||||
|
|
||||||
// Parameters
|
// Parameters
|
||||||
AP_Int8 require;
|
AP_Int8 require;
|
||||||
@ -71,11 +76,6 @@ protected:
|
|||||||
AP_Float accel_error_threshold;
|
AP_Float accel_error_threshold;
|
||||||
AP_Float _min_voltage[AP_BATT_MONITOR_MAX_INSTANCES];
|
AP_Float _min_voltage[AP_BATT_MONITOR_MAX_INSTANCES];
|
||||||
|
|
||||||
// references
|
|
||||||
const AP_AHRS &ahrs;
|
|
||||||
Compass &_compass;
|
|
||||||
const AP_BattMonitor &_battery;
|
|
||||||
|
|
||||||
// internal members
|
// internal members
|
||||||
bool armed:1;
|
bool armed:1;
|
||||||
bool logging_available:1;
|
bool logging_available:1;
|
||||||
|
Loading…
Reference in New Issue
Block a user