Subsystem/ahrs
Jump to navigation
Jump to search
AHRS subsystem
The AHRS subsystem specifies which attitude estimation filter you are using.
e.g. for the complementary filter:
File: conf/airframes/myplane.xml |
<firmware name="fixedwing or rotorcraft"> ... <subsystem name="ahrs" type="int_cmpl_euler"/> </firmware> |
There is a test program ( sw/airborne/test/ahrs/compare_ahrs.py ) to compare different AHRS implementations on simple test cases.
Complementary Euler (fixed point)
Complementary Quaternion (fixed point)
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="PROPAGATE_FREQUENCY" value="512"/> <define name="H_X" value=" 0.51562740288882"/> <define name="H_Y" value="-0.05707735220832"/> <define name="H_Z" value=" 0.85490967783446"/> </section> |
H is the normalised local magnetic field which can be derived by following instructions on the IMU calibration page here.
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