Throttle control - Jeffem/MP5_QuadCopter GitHub Wiki
Introduction
This document describes the thrust control of a QuadCopter with MatrixPilot Version 5.
Please excuse any lack of clarity due to my English.
Altitude control (Throttle axis)
Multicopter altitude is controlled directly by the throttle. There is no need to increase the incidence to get lift: the automatic altitude control algorithm can be simplified. Apart from the suppression of pitch, the original MP principle stays the same, as described in the document AltitudeHoldSetup.pdf, with the option ALTITUDEHOLD_STABILIZED = AH_FULL.
In manual mode, the throttle is entirely under pilot control.
In auto mode, altitude control is composed of four steps:
-
Desired height ;
-
Thrust computation ;
-
Filter ;
-
Throttle command.
- Desired height
During auto mode with the AH_FULL option, the target altitude is set according to the throttle stick position on the transmitter. This achieves a similar feel to the controls in both manual and stabilized modes.
When the stick is near the idle position, the desired height is a constant Height_Target_Min.
When the stick is in full power position, the desired height is a constant Height_Target_Max.
In the following diagram, servo range value is 800 µs.
[
]
Desired height = Height target min + Height throttle gain * Stick offset position
A dead band (blue rectangle) avoids stick fluctuation when idle is commanded.
The coefficient 1024 in HEIGHTTHROTTLEGAIN is used for software integer multiplication purposes.
We can observe that the desired height depends on height target values, whatever is its unit, here we are using centimeters.
A rate limiter of 2m/s is used to avoid too much command in case of high stick change.
Power computation
Although we try to stick to the MP philosophy, thrust control has to be specific for the multicopter. In contrast to an airplane, the helicopter does not fly. It needs to be sustained by its propellers. Furthermore, its attitude is also insured by its propellers.
Our next figure shows vertical acceleration versus motor throttle.
The neutral command, corresponding to null acceleration, is obtained with a throttle of 370µs (above the trim value of 1100µs).
With a command of 395 µs, the acceleration is 1 m/s² up, while with 310 µs, it is 2 m/s² down.
To obtain acceleration in the range of +/- 5 m/s², the throttle has to be commanded, roughly, from 250 to 600 µs.
These last values will be the saturation threshold for the throttle command in order to leave some room for attitude control.
Taking into account the power variation versus battery voltage, an integral term is added to the corrector.
Power computation follows a linear response to the error between actual altitude Z and the desired height.
ε = Z – DesiredHeight
Throttle = Neutral + Kp * ε + Ki * ∑εdt + Kd*Vz + Ka*γz
The outer loop, running at PID_HZ=40 Hz, compute the proportional and integral terms of the corrector’s law.
Inside the inner loop, running at HEARTBEAT_HZ = 200 Hz, the stabilization terms in speed and acceleration are added.
The output is clamped between [SERVORANGE+Thrust_CLAMP, SERVORANGE-Thrust_Clamp].
As the altitude control frame reference is the absolute frame, the variable are:
-
Estimated height for Z ;
-
IMUvelocityZ for Vz ;
-
AccelEath[2] for γz.
It is very important to use IMUvelocity and not any estimated Vz value coming from the altitude fusion because the phase margin of the corrector is very sensible to the delay of Vz.
Filter
The feedback γz is filtered by a low pass Buterworth 4, with a cut frequency of 30 Hz to avoid too much noise coming from motors and propellers.
Throttle command
In manual mode, throttle is controlled directely by the RC stick.
In auto mode, throttle is the output of the inner throttle loop added with the trim value.
Acceleration feedback justification
On board a multicopter, the vibration level is very high due to the motors and propellers unbalancing. Nothing can eliminates completely these mechanical sources.
The accelerometers, of course, detect these vibrations.
Filtering the accelerometers output is not sufficient to erase the noise.
One can ask the interest of the acceleration feedback in the altitude control loop.
The theoretical study can help to answer.
For the same phase margin of the loop, and with a typical SK450 quadcopter model, the study gives the following result:
Kp | 2 | 0.7 | |
---|---|---|---|
Kd | 1 | 0.5 | |
Ka | 0.05 | 0 |