mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-28 10:43:58 -04:00
Plane: Add fwd. throttle cutoff voltage parameter
Updated the forward throttle battery voltage compensation feature to disable the throttle entirely when the sag-compensated voltage drops below the new parameter FWD_THR_CUTOFF_V. Key changes: - Added new parameter FWD_THR_CUTOFF_V to control the voltage threshold for this feature. The default value of 0 matches the original behavior of never cutting the throttle due to low voltage. - Modified forward throttle battery voltage compensation logic in the servos code to cut off the throttle in auto-throttle modes if the resting voltage estimate of the FWD_BAT_IDX battery is under FWD_THR_CUTOFF_V.
This commit is contained in:
parent
25f7eebce5
commit
a1a0fc4a70
@ -1309,7 +1309,16 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("RNGFND_LND_ORNT", 36, ParametersG2, rangefinder_land_orient, ROTATION_PITCH_270),
|
||||
#endif
|
||||
|
||||
|
||||
// @Param: FWD_BAT_THR_CUT
|
||||
// @DisplayName: Forward throttle cutoff battery voltage
|
||||
// @Description: The estimated battery resting voltage below which the throttle is cut in auto-throttle modes. Measured on the battery used for forward throttle compensation (FWD_BAT_IDX). If set to zero, the throttle will not be cut due to low voltage, allowing the motor(s) to continue running until the battery is depleted. This should be set to the minimum operating voltage of you motor(s) or to a voltage level where minimal thrust is produced, to conserve the remaining battery power for the electronics and actuators.
|
||||
// @Range: 0 35
|
||||
// @Units: V
|
||||
// @Increment: 0.1
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("FWD_BAT_THR_CUT", 37, ParametersG2, fwd_batt_cmp.batt_voltage_throttle_cutoff, 0.0f),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
@ -556,6 +556,7 @@ public:
|
||||
|
||||
AP_Float batt_voltage_max;
|
||||
AP_Float batt_voltage_min;
|
||||
AP_Float batt_voltage_throttle_cutoff;
|
||||
AP_Int8 batt_idx;
|
||||
|
||||
private:
|
||||
|
@ -440,6 +440,19 @@ void ParametersG2::FWD_BATT_CMP::update()
|
||||
// Apply throttle scale to min and max limits
|
||||
void ParametersG2::FWD_BATT_CMP::apply_min_max(int8_t &min_throttle, int8_t &max_throttle) const
|
||||
{
|
||||
// Cut off throttle if FWD_BAT_IDX battery resting voltage is below
|
||||
// FWD_THR_CUTOFF_V (if set), to preserve battery life for the electronics
|
||||
// and actuators. Only applies when the battery monitor is working and the
|
||||
// current mode does auto-throttle.
|
||||
if (is_positive(batt_voltage_throttle_cutoff) &&
|
||||
plane.control_mode->does_auto_throttle() && AP::battery().healthy(batt_idx) &&
|
||||
(AP::battery().voltage_resting_estimate(batt_idx) < batt_voltage_throttle_cutoff)) {
|
||||
min_throttle = 0;
|
||||
max_throttle = 0;
|
||||
|
||||
return;
|
||||
}
|
||||
|
||||
// return if not enabled
|
||||
if (!enabled) {
|
||||
return;
|
||||
|
Loading…
Reference in New Issue
Block a user