Subsystem/ahrs
AHRS subsystem
The AHRS subsystem specifies which attitude estimation filter you are using.
Currently possible AHRS subsystems are
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.
- Magnetometer is always only used for heading (yaw).
- Does not handle the accel and mag updates correctly if BODY_TO_IMU is used for more than just adjustment by a few degrees.
- In general, rather use int_cmpl_quat
Optional flags/defines are:
- FACE_REINJ_1 : defaults to 1024
- IMU_MAG_OFFSET : offset to subtract from the heading calculated by the magnetometer
- USE_NOISE_FILTER : apply a simple filter on the rate and accel inputs
- USE_NOISE_CUT : cut rate input at 1 rad/s and accel input at 20m/s²
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)
- Estimates the gyro bias.
- The version on the master branch is currently not recommended for fixedwings, as this filter doesn't compensate for centrifugal force when flying turns.
- In the dev branch:
- Compensation of centrifugal force (via AHRS_GRAVITY_UPDATE_COORDINATED_TURN which is set by default for a fixedwing firmware).
- GPS based heading estimation: https://github.com/paparazzi/paparazzi/issues/130
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 (recommended in most cases, already default in dev branch)
File: conf/airframes/myplane.xml |
<firmware name="fixedwing or rotorcraft"> ... <subsystem name="ahrs" type="int_cmpl_quat"> <define name="AHRS_MAG_UPDATE_YAW_ONLY"/> </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.
Complementary Quaternion/Rotation Matrix (floating point)
- Estimates the gyro bias.
- You need to define either AHRS_PROPAGATE_RMAT or AHRS_PROPAGATE_QUAT (select if the propagation is done in rotation matrix or quaternion representation).
- The version on the master branch is currently not recommended for fixedwings, as this filter doesn't compensate for centrifugal force when flying turns.
- In the dev branch:
- Compensation of centrifugal force (via AHRS_GRAVITY_UPDATE_COORDINATED_TURN which is set by default for a fixedwing firmware).
- GPS based heading estimation: https://github.com/paparazzi/paparazzi/issues/130
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 (recommended in most cases, already default in dev branch)
- AHRS_GRAVITY_UPDATE_NORM_HEURISTIC: lower the gain of the gravity update based on a acceleration norm heuristic (e.g. good for bungee takeoff)
File: conf/airframes/myplane.xml |
<firmware name="rotorcraft or fixedwing"> ... <subsystem name="ahrs" type="float_cmpl_rmat"> <define name="AHRS_PROPAGATE_RMAT"/> <define name="AHRS_MAG_UPDATE_YAW_ONLY"/> </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)
- No direct gyro bias estimation.
- Similar in principle to the float_cmpl_rmat filter (but less cleanly written).
The main aspects are:
- using the centrifugal force by a rotation with the center in the z axis for calculating the attitude (you can fly circles for long time without any problems). Careful, it doesn't handle all BODY_TO_IMU rotations (mounting positions) correctly! If you like to help out improving this part of the sourcecode contact the paparazzi developers via the mailinglist.
- Correcting the matrix elements of the direction 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 algorithm 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.
Copy the north(x),east(y),vertical(z) component values into scilab and execute "X/norm(X)".