mirror of https://github.com/ArduPilot/ardupilot
AP_Arming: rename _MIN_VOLT to _VOLT_MIN
Also _MIN_VOLT2 to _VOLT2_MIN
This commit is contained in:
parent
1405801595
commit
159906762f
|
@ -53,21 +53,21 @@ const AP_Param::GroupInfo AP_Arming::var_info[] = {
|
|||
// @User: Advanced
|
||||
AP_GROUPINFO("ACCTHRESH", 3, AP_Arming, accel_error_threshold, AP_ARMING_ACCEL_ERROR_THRESHOLD),
|
||||
|
||||
// @Param: MIN_VOLT
|
||||
// @DisplayName: Minimum arming voltage on the first battery
|
||||
// @Param: VOLT_MIN
|
||||
// @DisplayName: Arming voltage minimum on the first battery
|
||||
// @Description: The minimum voltage on the first battery to arm, 0 disables the check
|
||||
// @Units: V
|
||||
// @Increment: 0.1
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("MIN_VOLT", 4, AP_Arming, _min_voltage[0], 0),
|
||||
AP_GROUPINFO("VOLT_MIN", 4, AP_Arming, _min_voltage[0], 0),
|
||||
|
||||
// @Param: MIN_VOLT2
|
||||
// @DisplayName: Minimum arming voltage on the second battery
|
||||
// @Param: VOLT2_MIN
|
||||
// @DisplayName: Arming voltage minimum on the second battery
|
||||
// @Description: The minimum voltage on the first battery to arm, 0 disables the check
|
||||
// @Units: V
|
||||
// @Increment: 0.1
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("MIN_VOLT2", 5, AP_Arming, _min_voltage[1], 0),
|
||||
AP_GROUPINFO("VOLT2_MIN", 5, AP_Arming, _min_voltage[1], 0),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue