Difference between revisions of "Subsystem/stabilization"

From PaparazziUAV
Jump to navigation Jump to search
(fix names of types)
m
 
(6 intermediate revisions by 2 users not shown)
Line 8: Line 8:
* ''[[Subsystem/stabilization#Euler|int_euler]]''
* ''[[Subsystem/stabilization#Euler|int_euler]]''
* ''[[Subsystem/stabilization#Euler|float_euler]]''
* ''[[Subsystem/stabilization#Euler|float_euler]]''
* ''[[Subsystem/stabilization#INDI|indi]]''


== Attitude Control Implementations ==
== Attitude Control Implementations ==
Line 65: Line 66:
; ''DEADBAND_*'': RC stick deadband around the center for ''A'',''E'',''R'' (roll,pitch,yaw)
; ''DEADBAND_*'': RC stick deadband around the center for ''A'',''E'',''R'' (roll,pitch,yaw)
; ''REF_*'': parameters for the [[Control_Loops#Reference_generators_2|reference generator]]
; ''REF_*'': parameters for the [[Control_Loops#Reference_generators_2|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]_[PID]GAIN'': gains for the feedback control of the respective axis
; ''[PHI|THETA|PSI]_DDGAIN'': feedforward gains for the respective axis
; ''[PHI|THETA|PSI]_DDGAIN'': feedforward gains for the respective axis
Line 96: Line 101:
}}
}}
You also need the ''STABILIZATION_ATTITUDE'' xml configuration section as described above.
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 ==
== 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.
You can also control the rotation rates of the vehicle with the RC, instead of using full (self-leveling) attitude control.
For the control method, it is possible to choose a PI controller, by specifying <code>type="rate"</code>, or INDI control, by specifying <code>type="rate_indi"</code>, like in the example below.
See [[Control_Loops#Rate_loop]] for diagrams of the control loop.
See [[Control_Loops#Rate_loop]] for diagrams of the control loop.
{{Box Code|conf/airframes/myplane.xml|
{{Box Code|conf/airframes/myplane.xml|
Line 104: Line 119:
   <firmware name="rotorcraft">
   <firmware name="rotorcraft">
     ...
     ...
    <module name="stabilization" type="rate"/>
   </firmware>
   </firmware>



Latest revision as of 01:54, 28 November 2017

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

You can also control the rotation rates of the vehicle with the RC, instead of using full (self-leveling) attitude control. For the control method, it is possible to choose a PI controller, by specifying type="rate", or INDI control, by specifying type="rate_indi", like in the example below. See Control_Loops#Rate_loop for diagrams of the control loop.

File: conf/airframes/myplane.xml
  <firmware name="rotorcraft">
     ...
     <module name="stabilization" type="rate"/>
  </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>