mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2025-02-20 10:54:14 +01:00
Stabilization: Small patch so that by default the integral is zeroed while
throttle is low (good for quads) but can be disabled (good for planes and also testing helis).
This commit is contained in:
parent
12ae607a22
commit
ab288e95ab
@ -84,6 +84,7 @@ uint8_t max_axis_lock = 0;
|
||||
uint8_t max_axislock_rate = 0;
|
||||
float weak_leveling_kp = 0;
|
||||
uint8_t weak_leveling_max = 0;
|
||||
bool lowThrottleZeroIntegral;
|
||||
|
||||
pid_type pids[PID_MAX];
|
||||
|
||||
@ -329,6 +330,7 @@ static void stabilizationTask(void* parameters)
|
||||
}
|
||||
|
||||
if(flightStatus.Armed != FLIGHTSTATUS_ARMED_ARMED ||
|
||||
(lowThrottleZeroIntegral && stabDesired.Throttle < 0) ||
|
||||
!shouldUpdate)
|
||||
{
|
||||
ZeroPids();
|
||||
@ -427,6 +429,9 @@ static void SettingsUpdatedCb(UAVObjEvent * ev)
|
||||
weak_leveling_kp = settings.WeakLevelingKp;
|
||||
weak_leveling_max = settings.MaxWeakLevelingRate;
|
||||
|
||||
// Whether to zero the PID integrals while throttle is low
|
||||
lowThrottleZeroIntegral = settings.LowThrottleZeroIntegral == STABILIZATIONSETTINGS_LOWTHROTTLEZEROINTEGRAL_TRUE;
|
||||
|
||||
// The dT has some jitter iteration to iteration that we don't want to
|
||||
// make thie result unpredictable. Still, it's nicer to specify the constant
|
||||
// based on a time (in ms) rather than a fixed multiplier. The error between
|
||||
|
@ -22,6 +22,8 @@
|
||||
<field name="WeakLevelingKp" units="(deg/s)/deg" type="float" elements="1" defaultvalue="0.1"/>
|
||||
<field name="MaxWeakLevelingRate" units="deg/s" type="uint8" elements="1" defaultvalue="5"/>
|
||||
|
||||
<field name="LowThrottleZeroIntegral" units="" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="TRUE"/>
|
||||
|
||||
<access gcs="readwrite" flight="readwrite"/>
|
||||
<telemetrygcs acked="true" updatemode="onchange" period="0"/>
|
||||
<telemetryflight acked="true" updatemode="onchange" period="0"/>
|
||||
|
Loading…
x
Reference in New Issue
Block a user