mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-03 14:38:44 -04:00
Sub: Remove unnecessary checks from default pre-arm checks
This commit is contained in:
parent
8bb55af0fb
commit
35c03717fc
@ -801,13 +801,9 @@ void Sub::load_parameters(void)
|
|||||||
AP_Param::set_default_by_name("BRD_SAFETYENABLE", 0);
|
AP_Param::set_default_by_name("BRD_SAFETYENABLE", 0);
|
||||||
AP_Param::set_default_by_name("GND_EXT_BUS", 1);
|
AP_Param::set_default_by_name("GND_EXT_BUS", 1);
|
||||||
AP_Param::set_default_by_name("ARMING_CHECK",
|
AP_Param::set_default_by_name("ARMING_CHECK",
|
||||||
AP_Arming::ARMING_CHECK_BARO |
|
|
||||||
AP_Arming::ARMING_CHECK_COMPASS |
|
|
||||||
AP_Arming::ARMING_CHECK_INS |
|
|
||||||
AP_Arming::ARMING_CHECK_RC |
|
AP_Arming::ARMING_CHECK_RC |
|
||||||
AP_Arming::ARMING_CHECK_VOLTAGE |
|
AP_Arming::ARMING_CHECK_VOLTAGE |
|
||||||
AP_Arming::ARMING_CHECK_BATTERY |
|
AP_Arming::ARMING_CHECK_BATTERY);
|
||||||
AP_Arming::ARMING_CHECK_LOGGING);
|
|
||||||
AP_Param::set_default_by_name("CIRCLE_RATE", 2.0f);
|
AP_Param::set_default_by_name("CIRCLE_RATE", 2.0f);
|
||||||
AP_Param::set_default_by_name("ATC_ACCEL_Y_MAX", 110000.0f);
|
AP_Param::set_default_by_name("ATC_ACCEL_Y_MAX", 110000.0f);
|
||||||
AP_Param::set_default_by_name("RC3_TRIM", 1100);
|
AP_Param::set_default_by_name("RC3_TRIM", 1100);
|
||||||
|
Loading…
Reference in New Issue
Block a user