CRITICAL Copter 3.6.10 Throttle Limit Issue

Hello,
Testing the end off battery, I had throttle limit issue starting at log line 225000, instead motor was not at 100% (1920pwm max esc calibrated) but at 1800pwm (also output is not linear so 10% remaining represent 20% of thrust……) .

So drone slowly fall down, until I released the load. (servo controled).
Also I check Mot thr max param was set to 1.

I Don’t understand this behavior, can you explain to me wich parameters allow to adjust this behavior ?

You will find attached log of this flight.

thank you for your help.

Hi @kuspower,
I think you might find more information here.
HTH,
Gal

So, I found that is in correlation with MOT_BAT_VOLT_MIN….

I set 38V and as soon as voltage drop below Trottle limit occurs until voltage returns to above 38V !!!

in the reality my 12S lipo can drop to 36V.

So It need to be mentionned as critical parameter, because can lead to crash if it badly set.

You can check another flight made today without overload, and the same thing occurs!!!
check attached

Your log is missing from the first post.
MOT_BAT_VOLT_MIN has nothing to do with throttle limiting, But MOT_BAT_CURR_MAX can do it.

Hello eosbandy, if i push this issue is because im sure what im telling on this post.

For me as for you mot bat volt min dont must to act with throttle limit.

Im experiencing Ac since 3.2…

Now i dont know since witch version this issue appear.

In the log you can check the parameters used in flight.

There is dev that can check code to find explanations ?

As I said it is current limiting. Since your current limit and minimum voltage is enabled, the current limiter tries to keep voltage above MOT_BATT_VOLT_MIN. See line below starts with “_float bat_current_max = MIN(…” If the actual voltage drops below voltage min, then the current limit become the actual current.

So it is a perfectly normal behavior. Either disable MOT_BATT_CURR_MAX or lower MOT_BATT_VOLT_MIN.

(anyway if you need curr_max then your drivetrain is underpowered)

// return current_limit as a number from 0 ~ 1 in the range throttle_min to throttle_max
float AP_MotorsMulticopter::get_current_limit_max_throttle()
{
    AP_BattMonitor &battery = AP::battery();

    if (_batt_current_max <= 0 || // return maximum if current limiting is disabled
        !_flags.armed || // remove throttle limit if disarmed
        !battery.has_current(_batt_idx)) { // no current monitoring is available
        _throttle_limit = 1.0f;
        return 1.0f;
    }

    float _batt_resistance = battery.get_resistance(_batt_idx);

    if (is_zero(_batt_resistance)) {
        _throttle_limit = 1.0f;
        return 1.0f;
    }

    float _batt_current = battery.current_amps(_batt_idx);

    // calculate the maximum current to prevent voltage sag below _batt_voltage_min
    float batt_current_max = MIN(_batt_current_max, _batt_current + (battery.voltage(_batt_idx)-_batt_voltage_min)/_batt_resistance);

    float batt_current_ratio = _batt_current/batt_current_max;

    float loop_interval = 1.0f/_loop_rate;
    _throttle_limit += (loop_interval/(loop_interval+_batt_current_time_constant))*(1.0f - batt_current_ratio);

    // throttle limit drops to 20% between hover and full throttle
    _throttle_limit = constrain_float(_throttle_limit, 0.2f, 1.0f);

    // limit max throttle
    return get_throttle_hover() + ((1.0-get_throttle_hover())*_throttle_limit);
}

Okey! Thank you so much for this explanation!

I set curr max to 125a and now i understand that when we activate current limiting if we not reach the curr max but we pass lower than mot bat volt min, ap takes actual current as limit!

Okey now its clear.

I think that instead of mark in copter user guide that good value for start mot bat volt min is failsafe voltage, it need to mark good voltage to start is the lowest voltage that your battery can handle without damage. So for lipo 3v x cell and for liion 2,8v /cell.

If not user like me that read it can set this value to voltage failsafe and if like me it set curr max, as soon as the uav drop below failsafe it crash…

AKA Setting this to the battery failsafe voltage is a good start

Yes, the doco does actually mention something similar, although it’s clearly worded for Lipo batteries:
http://ardupilot.org/copter/docs/parameters.html#mot-bat-volt-min-battery-voltage-compensation-minimum-voltage
And also best to set the max too.
You might set the maximum current to what ever is the weakest link in your battery/sensor/ESC/motor drive train. For example you might only have a 100A current sensor - some can go over their maximum reading and some cant. Or maybe your battery will only safely do 100A…
http://ardupilot.org/copter/docs/parameters.html#mot-bat-curr-max-motor-current-max

The poor documentation here is my fault.

When you have current limiting value set it will limit the throttle to a point that will prevent the battery voltage being pulled below your minimum voltage set in the MOT parameters. Appart form prolonging the battery lifetime, it lets you maximise flight time by limiting the power draw when the battery is getting low and causing a battery failsafe.

Notice in the code that it does not pull the maximum throttle below the hover throttle. The lowest value it can pull maximum throttle is: Hover + (1-Hover)*0.2

Now the problem. This should never reduce the maximum throttle below the hover throttle. It should simply limit your maximum lean angle and ability to climb quickly. So it should never cause the aircraft to descend unless the parameters have been set badly. In particular if your hover throttle is set too low.

So we have good news and bad news… And great news…

The good news is you have not set the parameters badly.
The bad news is we have a bug.
The great news is I found it :slight_smile:

So the problem is we are not accounting for the increase in hover throttle caused by the battery voltage scaling correction. Because your maximum thrust has dropped by 20% at this point in the flight, when you get the reduction it goes lower than it should.

Thanks for your log and I am sorry for my mistake. I am glad you did not damage your aircraft!

I have reopened the Issue.

3 Likes

Hello,

I’m happy that this experiance can help to improve Arducopter.

Thank you so much.

2 Likes