Difference between revisions of "Subsystem/ahrs"
(added wolfram alpha link for computing local mag field and made it clearer where to put the resulting values in the airframe file) |
|||
Line 138: | Line 138: | ||
== Local Magnetic Field == | == Local Magnetic Field == | ||
If you are using a magnetometer, calculate the normalised local magnetic field by inserting your location coordinates [http://www.ngdc.noaa.gov/geomag-web/#igrfwmm here]and clicking calculate. | |||
<gallery widths=200px heigths=300px> | <gallery widths=200px heigths=300px> | ||
Line 145: | Line 145: | ||
</gallery> | </gallery> | ||
Copy the north(x),east(y),vertical(z) component values into scilab and execute "X/norm(X)" or run this in ipython: | Copy the north(x), east(y), and vertical(z) component values into scilab and execute "X/norm(X)" or run this in ipython: | ||
<source lang=python> | <source lang=python> | ||
Line 154: | Line 154: | ||
</source> | </source> | ||
or enter this into [http://wolframalpha.com Wolfram Alpha]: | |||
<source lang=python> | |||
{20875.1, 8480.2, -51279.8}/Norm[{20875.1, 8480.2, -51279.8}] | |||
</source> | |||
[[Category:User_Documentation]] [[Category:Subsystems]] | [[Category:User_Documentation]] [[Category:Subsystems]] | ||
Lastly, enter the results into your airframe file as H_X, H_Y, and H_Z: | |||
{{Box Code|conf/airframes/myplane.xml| | |||
<source lang="xml"> | |||
<section name="AHRS" prefix="AHRS_"> | |||
<define name="H_X" value="0.372692"/> | |||
<define name="H_Y" value="0.151401"/> | |||
<define name="H_Z" value="-0.915521"/> | |||
</section> | |||
</source> | |||
}} |
Revision as of 23:26, 1 July 2013
AHRS subsystem
The Attitude and Heading Reference System subsystem specifies which attitude estimation filter you are using.
Currently possible AHRS subsystem types 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 Quaternion (fixed point)
- Estimates the gyro bias.
- By default uses magnetometer for heading.
- In v3.9 and later:
- Compensation of centrifugal force via GPS speed (to fly in circles with a fixedwing).
Enabled with 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
- Compensation of centrifugal force via GPS speed (to fly in circles with a fixedwing).
Other flags of interest are:
- AHRS_PROPAGATE_LOW_PASS_RATES : apply a low pass filter on rotational velocity
- AHRS_MAG_UPDATE_ALL_AXES : available since v3.9 use mag to also update roll/pitch and not only yaw (not recommended in most cases)
- AHRS_MAG_UPDATE_YAW_ONLY : removed in v3.9, default behaviour since only update the yaw instead of all axes
File: conf/airframes/myplane.xml |
<firmware name="fixedwing or 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 Quaternion/Rotation Matrix (floating point)
- Estimates the gyro bias.
- By default uses magnetometer for heading.
- You need to define either AHRS_PROPAGATE_RMAT or AHRS_PROPAGATE_QUAT (select if the propagation is done in rotation matrix or quaternion representation).
- In v3.9 and later:
- Compensation of centrifugal force via GPS speed (to fly in circles with a fixedwing).
Enabled with 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
- Compensation of centrifugal force via GPS speed (to fly in circles with a fixedwing).
Other flags of interest are:
- AHRS_PROPAGATE_LOW_PASS_RATES : apply a low pass filter on rotational velocity
- AHRS_MAG_UPDATE_ALL_AXES : use mag to also update roll/pitch and not only yaw (not recommended in most cases)
- 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_QUAT"/>
</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, but also compensates for attitude drift.
- Uses GPS speed for heading.
- Compensation of centrifugal force via GPS speed (to fly in circles with a fixedwing).
- Careful, it doesn't handle all BODY_TO_IMU rotations (mounting positions) correctly!
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 AHRS systems of the AdruIMU. The name DCM for the algorithm is really a misnomer, as that just means that the orientation is represented as a DirectionCosineMatrix (rotation matrix). But since people already know it under that name, we kept it.
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>
|
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>
|
Infrared
For use with infrared sensors that detect aircraft attitude and the infrared module.
Local Magnetic Field
If you are using a magnetometer, calculate the normalised local magnetic field by inserting your location coordinates hereand clicking calculate.
Copy the north(x), east(y), and vertical(z) component values into scilab and execute "X/norm(X)" or run this in ipython:
from scipy import *
from numpy.linalg import norm
x = array([20875.1, 8480.2, -51279.8])
x/norm(x)
or enter this into Wolfram Alpha:
{20875.1, 8480.2, -51279.8}/Norm[{20875.1, 8480.2, -51279.8}]
Lastly, enter the results into your airframe file as H_X, H_Y, and H_Z:
File: conf/airframes/myplane.xml |
<section name="AHRS" prefix="AHRS_">
<define name="H_X" value="0.372692"/>
<define name="H_Y" value="0.151401"/>
<define name="H_Z" value="-0.915521"/>
</section>
|