mirror of https://github.com/ArduPilot/ardupilot
Sub: Set GND_EXT_BUS to 1 by default
This commit is contained in:
parent
ee07a06fa2
commit
279b11e392
|
@ -961,6 +961,7 @@ void Sub::load_parameters(void)
|
|||
convert_old_parameters();
|
||||
|
||||
AP_Param::set_default_by_name("BRD_SAFETYENABLE", 0);
|
||||
AP_Param::set_default_by_name("GND_EXT_BUS", 1);
|
||||
}
|
||||
|
||||
void Sub::convert_old_parameters(void)
|
||||
|
|
Loading…
Reference in New Issue