Difference between revisions of "Working with INDI"

From PaparazziUAV
Jump to navigation Jump to search
m
Line 65: Line 65:
Actuators don't react instantly. Motors need time to spin up, and servos can only move so many degrees per second. This means that if the input is suddenly changed, the angular acceleration is not immediately expected to change. If there is actuator feedback available, we know exactly how much the actuator has moved and at what moment how much angular acceleration we should expect. If actuator feedback is not available, an estimate of the actuator position has to be made.
Actuators don't react instantly. Motors need time to spin up, and servos can only move so many degrees per second. This means that if the input is suddenly changed, the angular acceleration is not immediately expected to change. If there is actuator feedback available, we know exactly how much the actuator has moved and at what moment how much angular acceleration we should expect. If actuator feedback is not available, an estimate of the actuator position has to be made.


For electric motors, a first order system can be an accurate model. This can be written as: act(i+1) = act(i) + alpha*(input - act(i)), where alpha is the value that can be specified in the airframe file. There are a few vehicles for which this value has been determined, such as the ARDrone, Bebop and AscTec Hummingbird. It can be obtained with a step response of the motors, using for instance a logic analyzer and a light sensor to record the spinup profile.
For electric motors, a first order system can be an accurate model. This can be written as: act(i+1) = act(i) + alpha*(input - act(i)), where alpha is the value that can be specified in the airframe file. Note that the value of alpha depends on the frequency that this model runs! There are a few vehicles for which this value has been determined, such as the ARDrone, Bebop and AscTec Hummingbird. It can be obtained with a step response of the motors, using for instance a logic analyzer and a light sensor to record the spinup profile.


== Adaptive INDI ==
== Adaptive INDI ==

Revision as of 08:27, 10 August 2017

Example Airframe Section

To use INDI for your drone, you have to specify:

   <module name="stabilization" type="indi_simple"/>

or

   <module name="stabilization" type="rate_indi"/>

if you want to fly manual rate control.

Below you can see an example of how INDI can be configured in the airframe file:

File: conf/airframes/myplane.xml
  <section name="STABILIZATION_ATTITUDE_INDI" prefix="STABILIZATION_INDI_">
    <!-- control effectiveness -->
    <define name="G1_P" value="0.0639"/>
    <define name="G1_Q" value="0.0361"/>
    <define name="G1_R" value="0.0022"/>
    <define name="G2_R" value="0.1450"/>

    <!-- reference acceleration for attitude control -->
    <define name="REF_ERR_P" value="600.0"/>
    <define name="REF_ERR_Q" value="600.0"/>
    <define name="REF_ERR_R" value="600.0"/>
    <define name="REF_RATE_P" value="28.0"/>
    <define name="REF_RATE_Q" value="28.0"/>
    <define name="REF_RATE_R" value="28.0"/>

    <!--Maxium yaw rate, to avoid instability-->
    <define name="MAX_R" value="120.0" unit="deg/s"/>

    <!-- second order filter parameters -->
    <define name="FILT_CUTOFF" value="8.0"/>
    <define name="ESTIMATION_FILT_CUTOFF" value="8.0"/>

    <!-- first order actuator dynamics -->
    <define name="ACT_DYN_P" value="0.1"/>
    <define name="ACT_DYN_Q" value="0.1"/>
    <define name="ACT_DYN_R" value="0.1"/>

    <!-- Adaptive Learning Rate -->
    <define name="USE_ADAPTIVE" value="FALSE"/>
    <define name="ADAPTIVE_MU" value="0.0001"/>
  </section>

Make sure that in your configuration (in paparazzi center) the settings for different controllers, that are not used, are removed. The variables in these settings are not declared, so they will cause errors.

Control Effectiveness

The control effectiveness (G1) is what relates inputs to the actuators to angular accelerations. These values are not meant to be tuned. They can be obtained from flight logs, or by using the adaptive algorithm. Note that if you change the inertia of the drone, by adding weight, the control effectiveness is probably different than before. This is also the case when you add or remove bumpers/a flight hull.

Also note that for quadrotors, a G2 value is introduced, which is there to account for the inertia of the rotors. When the rotors have a certain RPM, they have a certain drag, which is why they provide a yawing moment. More RPM, more drag, more moment. But to change the RPM of the rotors, the motors need to apply a moment to accelerate the rotors. This moment is applied to the drone as well (action = -reaction). To obtain best performance, we have to account for this effect in the controller. That is why there is a control effectiveness value for it.

Attitude Control

The INDI controller itself controls angular accelerations. This means that if we want to command angular rates or attitude angles, we need to come up with a angular acceleration reference (or virtual control) that will result in the desired rate/attitude. This can be done with a simple PD controller. Since the control effectiveness (which includes the inertia of the vehicle) is accounted for by INDI, the P and D gains do not depend on the size of the drone. Instead, they only depend on the actuator dynamics.

Maximum Yaw Rate

The yaw control is usually least effective on a quadrotor. Therefore, the yaw command can easily saturate. To avoid yaw overshoot because of this, you can specify a maximum yaw rate.

Filtering

The angular acceleration is derived from the angular rate. In taking the derivative, noise is amplified. Therefore, the angular acceleration signal can be quite noisy, and filtering is practically always needed. For this purpose a second order filter is used. Such a filter adds a bit of delay to the signal. More filtering will give more delay. This delay will cause disturbances to be measured slightly later and hence be compensated later. If you are not logging the flight data and able to inspect what level of filtering is necessary, it is best not to change this.

Actuator Dynamics

Actuators don't react instantly. Motors need time to spin up, and servos can only move so many degrees per second. This means that if the input is suddenly changed, the angular acceleration is not immediately expected to change. If there is actuator feedback available, we know exactly how much the actuator has moved and at what moment how much angular acceleration we should expect. If actuator feedback is not available, an estimate of the actuator position has to be made.

For electric motors, a first order system can be an accurate model. This can be written as: act(i+1) = act(i) + alpha*(input - act(i)), where alpha is the value that can be specified in the airframe file. Note that the value of alpha depends on the frequency that this model runs! There are a few vehicles for which this value has been determined, such as the ARDrone, Bebop and AscTec Hummingbird. It can be obtained with a step response of the motors, using for instance a logic analyzer and a light sensor to record the spinup profile.

Adaptive INDI

Always use caution with Adaptive INDI

If you enable adaptive INDI, a Least Mean Squares (LMS) algorithm will estimate the control effectiveness values online. It does this by taking the current estimate of the control effectiveness multiplied with the most recent change in input. This is the expected change in angular acceleration. This is then compared to the actual angular acceleration, and the control effectiveness is changed proportional to the error. The parameter ADAPTIVE_MU is the learning rate of the algorithm. A high value will adapt quicker, but can also respond more to disturbances and noise.

Note that this assumes that all angular accelerations are caused by the inputs. This assumption usually holds indoors, but outside the wind can cause part of the angular acceleration. This can result in faulty adaptation. Also, when taking off with adaptation enabled, faulty learning can occur. This is because while on the ground, inputs will not result in angular accelerations. The algorithm may then estimate a very low control effectiveness. Lastly, if you have no actuator feedback/a bad estimate of the actuator dynamics, the learning may deteriorate.

One approach is to only use the adaptation for estimation of the control effectiveness after airframe changes. Start flying the drone, and activate the learning while flying through the INDI settings. More importantly, de-activate the learning before landing, or kill the drone before touching the ground. Again, interaction with the ground may result in faulty learning. Save the control effectiveness values.

My drone is oscillating

If your drone is oscillating or unstable, make sure you check the following (in this order):

Changed inertia

If you were flying before, but added something to the drone and now it is oscillating, you probably just need a different control effectiveness. You can try the online adaptation. Make sure that things are not loosely attached to the drone, as this will introduce extra dynamics. Rigid connections are preferred.

The Actuator dynamics

If you do not have actuator feedback, it is important to have an accurate actuator model. If you are unsure about your actuator model, it can be worthwhile to try to determine it.

INDI loop vs PD controller

Check if the oscillation comes from the INDI loop (control of angular acceleration) or from the PD controller that commands the reference angular acceleration. It can be that the angular acceleration reference is just too demanding.

Do this by reducing both the P and D gains. If this does not resolve the issue, you can try holding the drone in your hand (if this can be done safe!) and reducing both P and D gains to zero. The drone will now try to keep zero angular acceleration. If the drone is still oscillating, probably the control effectiveness is wrong (see step 1). Else, try to find P and D values that give a fast response without oscillation.