Difference between revisions of "Subsystem/stabilization"

From PaparazziUAV
Jump to navigation Jump to search
Line 103: Line 103:


=== INDI ===
=== INDI ===
Attitude controller based on an Incremental Nonlinear Dynamic Inversion inner loop. It controls the angular acceleration in an incremental way. More detailed information will follow after publication of the paper 'Adaptive Incremental Nonlinear Dynamic Inversion for Micro Aerial Vehicles'.
Attitude controller based on an Incremental Nonlinear Dynamic Inversion inner loop. It controls the angular acceleration in an incremental way. Detailed information can be found in the paper 'Adaptive Incremental Nonlinear Dynamic Inversion for Micro Aerial Vehicles' (http://arc.aiaa.org/doi/abs/10.2514/1.G001490).


Early adopters can take a look at the ardrone2_indi airframe file. Important settings are located in the STABILIZATION_ATTITUDE_INDI section.  
The idea is that any moment on the drone, results in an angular acceleration. With the onboard gyroscope, we measure the angular rate. This means that if we take the derivative of the angular rate, we have a measure of all moments on the drone through the angular acceleration. This includes the moment caused by the inputs. We know what the angular acceleration is with the inputs that we are giving, so to change the angular acceleration to a desired value, we just need to increment these inputs. How much we should increment the inputs to get a certain increment in angular acceleration is determined by the ''control effectiveness''.


The control effectiveness 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.  
The benefit of using INDI over PID is that the disturbance rejection is a lot faster. This means that an external moment on the drone due to wind or something else is counteracted as fast as the drone can measure it and the actuators can move. Compare this to the integrator gain of a PID controller, that only slowly removes steady state offsets.


The reference acceleration gains are kinematic gains that provide a reference to the angular acceleration controller. These gains depend on the actuator dynamics, but they can also be tuned.
More practical information can be found on [[working with INDI]]
 
The filter parameters are the omega and zeta of a second order filter on the gyroscope. Use a higher omega to get faster disturbance rejection, or a lower omega to filter more noise. I have used omega=50 for well-damped frames and omega=20 for badly damped frames.
 
First order actuator dynamics are assumed, written as: act(i+1) = act(i) + alpha*(input - act(i)), where alpha is the value that can be specified in the airframe file. 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.
 
It is advised to start out with ADAPTIVE_INDI FALSE. Eventually this feature can be very helpful, but it is a bit tricky. Problems can occur when:
 
- You don't take off right away, but keep in contact with the ground. A wrong effectiveness is estimated. The estimation goes quite fast, so if the drone doesn't rotate because it is still on the ground, the actuators are estimated to be very ineffective and large commands will be sent to the motors. So interaction with anything other than air is not advised.
 
- You have a hard mounted IMU with a lot of noise, this might affect the adaptation.


== Rate Control ==
== Rate Control ==

Revision as of 02:18, 8 June 2016

Stabilization subsystem

The stabilization subsystem provides the attitude controller for rotorcrafts.

Currently possible attitude stabilization subsystem types are

Attitude Control Implementations

There are several different attitude control algorithm implementations.

They use the same STABILIZATION_ATTITUDE xml configuration section:

File: conf/airframes/myplane.xml
  <section name="STABILIZATION_ATTITUDE" prefix="STABILIZATION_ATTITUDE_">
    <!-- setpoints -->
    <define name="SP_MAX_PHI"     value="45." unit="deg"/>
    <define name="SP_MAX_THETA"   value="45." unit="deg"/>
    <define name="SP_MAX_R"       value="90." unit="deg/s"/>
    <define name="DEADBAND_A"     value="0"/>
    <define name="DEADBAND_E"     value="0"/>
    <define name="DEADBAND_R"     value="250"/>

    <!-- reference -->
    <define name="REF_OMEGA_P"  value="800" unit="deg/s"/>
    <define name="REF_ZETA_P"   value="0.85"/>
    <define name="REF_MAX_P"    value="400." unit="deg/s"/>
    <define name="REF_MAX_PDOT" value="RadOfDeg(8000.)"/>

    <define name="REF_OMEGA_Q"  value="800" unit="deg/s"/>
    <define name="REF_ZETA_Q"   value="0.85"/>
    <define name="REF_MAX_Q"    value="400." unit="deg/s"/>
    <define name="REF_MAX_QDOT" value="RadOfDeg(8000.)"/>

    <define name="REF_OMEGA_R"  value="500" unit="deg/s"/>
    <define name="REF_ZETA_R"   value="0.85"/>
    <define name="REF_MAX_R"    value="180." unit="deg/s"/>
    <define name="REF_MAX_RDOT" value="RadOfDeg(1800.)"/>

    <!-- feedback -->
    <define name="PHI_PGAIN"  value="1000"/>
    <define name="PHI_DGAIN"  value="400"/>
    <define name="PHI_IGAIN"  value="200"/>

    <define name="THETA_PGAIN"  value="1000"/>
    <define name="THETA_DGAIN"  value="400"/>
    <define name="THETA_IGAIN"  value="200"/>

    <define name="PSI_PGAIN"  value="500"/>
    <define name="PSI_DGAIN"  value="300"/>
    <define name="PSI_IGAIN"  value="10"/>

    <!-- feedforward -->
    <define name="PHI_DDGAIN"   value="300"/>
    <define name="THETA_DDGAIN" value="300"/>
    <define name="PSI_DDGAIN"   value="300"/>
  </section>


SP_MAX_*
maximum PHI/THETA (roll/pitch) angles and maximum angular velocity R around yaw axis
DEADBAND_*
RC stick deadband around the center for A,E,R (roll,pitch,yaw)
REF_*
parameters for the reference generator
REF_OMEGA_*
second order model natural frequency for respective axis
REF_ZETA_*
second order model damping factor for respective axis
REF_MAX_x
bound on ref model angular speed
REF_MAX_xDOT
bound on ref model angular acceleration
[PHI|THETA|PSI]_[PID]GAIN
gains for the feedback control of the respective axis
[PHI|THETA|PSI]_DDGAIN
feedforward gains for the respective axis

Quaternion

Attitude controllers using quaternions (no gimbal lock). There is a fixed point implementation (recommended) and a floating point implementation for reference and testing.

  • fixed point:
    <subsystem name="stabilization" type="int_quat"/>
    
  • floating point:
    <subsystem name="stabilization" type="float_quat"/>
    
File: conf/airframes/myplane.xml
  <firmware name="rotorcraft">
     ...
    <subsystem name="stabilization" type="int_quat"/>
  </firmware>

You also need the STABILIZATION_ATTITUDE xml configuration section as described above.

Euler

Attitude controller using Euler Angles. Due to the inherent singularities (e.g. 90deg pitch) of the euler angles representation you can't use this controller if you want to fly in regimes close or at these singularities (e.g. acrobatics or transitioning vehicles). See Control_Loops#Attitude_loop for diagrams of the control loop.

File: conf/airframes/myplane.xml
  <firmware name="rotorcraft">
     ...
    <subsystem name="stabilization" type="int_euler"/>
  </firmware>

You also need the STABILIZATION_ATTITUDE xml configuration section as described above.

INDI

Attitude controller based on an Incremental Nonlinear Dynamic Inversion inner loop. It controls the angular acceleration in an incremental way. Detailed information can be found in the paper 'Adaptive Incremental Nonlinear Dynamic Inversion for Micro Aerial Vehicles' (http://arc.aiaa.org/doi/abs/10.2514/1.G001490).

The idea is that any moment on the drone, results in an angular acceleration. With the onboard gyroscope, we measure the angular rate. This means that if we take the derivative of the angular rate, we have a measure of all moments on the drone through the angular acceleration. This includes the moment caused by the inputs. We know what the angular acceleration is with the inputs that we are giving, so to change the angular acceleration to a desired value, we just need to increment these inputs. How much we should increment the inputs to get a certain increment in angular acceleration is determined by the control effectiveness.

The benefit of using INDI over PID is that the disturbance rejection is a lot faster. This means that an external moment on the drone due to wind or something else is counteracted as fast as the drone can measure it and the actuators can move. Compare this to the integrator gain of a PID controller, that only slowly removes steady state offsets.

More practical information can be found on working with INDI

Rate Control

There is only one rate control implementation (which is included in the rotorcraft firmware by default). It allows you to fly a rotorcraft like a helicopter by controlling the angular rate directly instead of having (self-leveling) attitude control. See Control_Loops#Rate_loop for diagrams of the control loop.

File: conf/airframes/myplane.xml
  <firmware name="rotorcraft">
     ...
  </firmware>

  <section name="STABILIZATION_RATE" prefix="STABILIZATION_RATE_">
    <!-- setpoints -->
    <define name="SP_MAX_P" value="10000"/>
    <define name="SP_MAX_Q" value="10000"/>
    <define name="SP_MAX_R" value="10000"/>
    <define name="DEADBAND_P" value="20"/>
    <define name="DEADBAND_Q" value="20"/>
    <define name="DEADBAND_R" value="200"/>
    <define name="REF_TAU" value="4"/>

    <!-- feedback -->
    <define name="GAIN_P" value="400"/>
    <define name="GAIN_Q" value="400"/>
    <define name="GAIN_R" value="350"/>

    <define name="IGAIN_P" value="75"/>
    <define name="IGAIN_Q" value="75"/>
    <define name="IGAIN_R" value="50"/>

    <!-- feedforward -->
    <define name="DDGAIN_P" value="300"/>
    <define name="DDGAIN_Q" value="300"/>
    <define name="DDGAIN_R" value="300"/>
  </section>