mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 17:53:59 -04:00
Sub: set defaults for navigator
This commit is contained in:
parent
a7bb57c319
commit
f8af741255
@ -732,6 +732,13 @@ void Sub::load_parameters()
|
||||
AP_Param::set_by_name("MNT_RC_IN_TILT", 8);
|
||||
// We should ignore this parameter since ROVs are neutral buoyancy
|
||||
AP_Param::set_by_name("MOT_THST_HOVER", 0.5);
|
||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIGATOR
|
||||
AP_Param::set_default_by_name("BARO_PROBE_EXT", 0);
|
||||
AP_Param::set_default_by_name("SR0_EXTRA1", 10);
|
||||
AP_Param::set_default_by_name("BATT_MONITOR", 4);
|
||||
AP_Param::set_default_by_name("BATT_CAPACITY", 0);
|
||||
AP_Param::set_default_by_name("LEAK1_PIN", 27);
|
||||
#endif
|
||||
}
|
||||
|
||||
void Sub::convert_old_parameters()
|
||||
|
Loading…
Reference in New Issue
Block a user