Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Plane: Add fwd. throttle cutoff voltage parameter #29080

Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
11 changes: 10 additions & 1 deletion ArduPlane/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
};

Expand Down
1 change: 1 addition & 0 deletions ArduPlane/Parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -556,6 +556,7 @@ class ParametersG2 {

AP_Float batt_voltage_max;
AP_Float batt_voltage_min;
AP_Float batt_voltage_throttle_cutoff;
AP_Int8 batt_idx;

private:
Expand Down
13 changes: 13 additions & 0 deletions ArduPlane/servos.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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) &&
rubenp02 marked this conversation as resolved.
Show resolved Hide resolved
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;
Expand Down
Loading