Subsystem/ahrs

From PaparazziUAV
Revision as of 06:51, 6 January 2012 by Flixr (talk | contribs) (added link to ahrs issue)
Jump to navigation Jump to search

AHRS subsystem

The AHRS subsystem specifies which attitude estimation filter you are using.

Currently possible AHRS subsystems are

  • int_cmpl_quat
  • int_cmpl_euler
  • float_cmpl_rmat
  • float_dcm

e.g. for the latest complementary filter:

File: conf/airframes/myplane.xml
  <firmware name="fixedwing or rotorcraft">
     ...
    <subsystem name="ahrs" type="int_cmpl_quat"/>
  </firmware>

Implementations

There is a test program ( sw/airborne/test/ahrs/compare_ahrs.py ) to compare different AHRS implementations on simple test cases.

Please also see issue 93 about proper handling of BODY_TO_IMU in all AHRS algorithms.

Complementary Euler (fixed point)

Not recommended for fixedwings, as this filter doesn't compensate for centrifugal force when flying turns.

File: conf/airframes/myplane.xml
  <firmware name="fixedwing or rotorcraft">
     ...
    <subsystem name="ahrs" type="int_cmpl_euler"/>
  </firmware>

  <section name="MISC">
    <define name="FACE_REINJ_1" value="1024"/> <!-- optional, defaults to 1024 -->
  </section>

Complementary Quaternion (fixed point)

If you are NOT using the dev branch, this is currently not recommended for fixedwings, as this filter doesn't compensate for centrifugal force when flying turns. In the dev branch this is fixed (but untested) and the needed AHRS_GRAVITY_UPDATE_COORDINATED_TURN already set by default for a fixedwing firmware.

Other flags of interest are:

  • AHRS_PROPAGATE_LOW_PASS_RATES : apply a low pass filter on rotational velocity
  • AHRS_MAG_UPDATE_YAW_ONLY : use mag to update yaw only


For the latest integer complementary quaternion filter (int_cmpl_quat):

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

  <section name="AHRS" prefix="AHRS_">
    <define name="H_X" value=" 0.51562740288882"/>
    <define name="H_Y" value="-0.05707735220832"/>
    <define name="H_Z" value=" 0.85490967783446"/>
  </section>

Also see the Local Magnetic Field section.

Complementary Rotation Matrix (floating point)

If you are NOT using the dev branch, this is currently not recommended for fixedwings, as this filter doesn't compensate for centrifugal force when flying turns. In the dev branch this is fixed (but untested) and the needed AHRS_GRAVITY_UPDATE_COORDINATED_TURN already set by default for a fixedwing firmware.

Other flags of interest are:

  • AHRS_PROPAGATE_LOW_PASS_RATES : apply a low pass filter on rotational velocity
  • AHRS_MAG_UPDATE_YAW_ONLY : use mag to update yaw only


File: conf/airframes/myplane.xml
  <firmware name="rotorcraft or fixedwing">
     ...
    <subsystem name="ahrs" type="float_cmpl_rmat">
      <define name="AHRS_PROPAGATE_RMAT"/>
    </subsystem>
  </firmware>

  <section name="AHRS" prefix="AHRS_">
    <define name="H_X" value=" 0.51562740288882"/>
    <define name="H_Y" value="-0.05707735220832"/>
    <define name="H_Z" value=" 0.85490967783446"/>
  </section>

Also see the Local Magnetic Field section.

DCM (floating point)

Similar in principle to the float_cmpl_rmat filter (but less cleanly written).

The main aspects are:

  1. using the centrifugal force in z direction for calculating the attitude (you can fly circles for long time without any problems). Careful, it doesn't handle all BODYY_TO_IMU rotations (mounting positions) correctly!
  2. Correcting the matrix elements of the direct cosine matrix for every calculation step (typ. every 25ms) to archive the orthogonality of the matrix (small errors of the integration and calculations are not accumulated, the algorithm gives almost exact results).

The algorithms was developed by William Premerlani and Paul Bizard. The theory can be found here: DCMDraft2.pdf The algorithm is also used in the AHS systems of the AdruIMU and SparkFun Razor 6DOF IMU.

Other flags of interest are:

  • USE_MAGNETOMETER : use magnetometer to update yaw (untested ? The magnetometer code has to be improved, since ferromagnetic materials affect the magnetic field. This is currently not implemented.)


File: conf/airframes/myplane.xml
  <firmware name="rotorcraft or fixedwing">
     ...
    <subsystem name="ahrs" type="float_dcm"/>
  </firmware>

Infrared

Local Magnetic Field

To calculate the normalised local magnetic field insert the relevant location coordinates hereand calculate.


Screenshot of noaa page. Noaa mag data.png


Copy the north(x),east(y),vertical(z) component values into scilab and execute "X/norm(X)".


Screenshot of scilab page. Normalised mag fields.png