Propagation is done in quaternion representation. Estimates the gyro bias. By default uses magnetometer for heading for rotorcrafts. For fixedwing firmware AHRS_GRAVITY_UPDATE_COORDINATED_TURN is enabled by default.
Add to your firmware section: This example contains all possible configuration options, not all of them are mandatory!
<module name="ahrs_float_cmpl_quat">
b'<define name="AHRS_MAG_UPDATE_ALL_AXES" value="FALSE|TRUE" />\n '
b'<define name="AHRS_USE_GPS_HEADING" value="FALSE|TRUE" />\n '
b'<define name="AHRS_GRAVITY_UPDATE_COORDINATED_TURN" value="FALSE|TRUE" />\n '
b'<define name="AHRS_GPS_SPEED_IN_NEGATIVE_Z_DIRECTION" value="FALSE|TRUE" />\n\n '
b'<define name="AHRS_PROPAGATE_LOW_PASS_RATES" />\n '
b'<define name="AHRS_GRAVITY_HEURISTIC_FACTOR" value="30" />\n '
b'<define name="AHRS_FC_IMU_ID" value="ABI_BROADCAST" />\n '
b'<define name="AHRS_FC_MAG_ID" value="ABI_BROADCAST" />\n '
b'<define name="AHRS_FC_GPS_ID" value="GPS_MULTI_ID" />\n '
b'<configure name="AHRS_FC_TYPE" value="AHRS_PRIMARY|AHRS_SECONDARY" />\n '
b'<configure name="USE_MAGNETOMETER" value="TRUE" />\n '
b'<configure name="AHRS_ALIGNER_LED" value="1" />\n '
</module>
These initialization functions are called once on startup.
<!DOCTYPE module SYSTEM "module.dtd">
<module name="ahrs_float_cmpl_quat" dir="ahrs" task="estimation">
<doc>
<description>
AHRS using complementary filter in floating point.
Propagation is done in quaternion representation.
Estimates the gyro bias.
By default uses magnetometer for heading for rotorcrafts.
For fixedwing firmware AHRS_GRAVITY_UPDATE_COORDINATED_TURN is enabled by default.
</description>
<configure name="AHRS_FC_TYPE" value="AHRS_PRIMARY|AHRS_SECONDARY" description="set if the AHRS is the primary source (default) or one of the secondary sources"/>
<configure name="USE_MAGNETOMETER" value="TRUE" description="set to FALSE to disable magnetometer"/>
<configure name="AHRS_ALIGNER_LED" value="1" description="LED number to indicate AHRS alignment, none to disable (default is board dependent)"/>
<define name="AHRS_MAG_UPDATE_ALL_AXES" value="FALSE|TRUE" description="Use magnetometer to update all axes and not only yaw"/>
<define name="AHRS_USE_GPS_HEADING" value="FALSE|TRUE" description="Use GPS course to update heading"/>
<define name="AHRS_GRAVITY_UPDATE_COORDINATED_TURN" value="FALSE|TRUE" description="Compensation of centrifugal force via GPS speed (to fly in circles with a fixedwing)"/>
<define name="AHRS_GPS_SPEED_IN_NEGATIVE_Z_DIRECTION" value="FALSE|TRUE" description="AHRS_GRAVITY_UPDATE_COORDINATED_TURN assumes the GPS speed is in the X axis direction. Quadshot, DelftaCopter and other hybrids can have the GPS speed in the negative Z direction"/>
<define name="AHRS_PROPAGATE_LOW_PASS_RATES" description="apply a low pass filter on rotational velocity"/>
<define name="AHRS_GRAVITY_HEURISTIC_FACTOR" value="30" description="Default is 30. Reduce accelerometer cut-off frequency when the vehicle is accelerating: norm(ax,ay,az) ~ 9,81 m/s2. WARNING: when the IMU is not well damped, the norm of accelerometers never equals to 9,81 m/s2. As a result, the GRAVITY_HEURISTIC_FACTOR will reduce the accelerometer bandwith even if the vehicle is not accelerating. Set to 0 in case of vibrations"/>
<define name="AHRS_FC_IMU_ID" value="ABI_BROADCAST" description="ABI sender id of IMU to use"/>
<define name="AHRS_FC_MAG_ID" value="ABI_BROADCAST" description="ABI sender id of magnetometer to use"/>
<define name="AHRS_FC_GPS_ID" value="GPS_MULTI_ID" description="ABI sender id of GPS to use"/>
</doc>
<settings>
<dl_settings>
<dl_settings NAME="AHRS FC">
<dl_setting var="ahrs_fc_enable" min="0" step="1" max="1" module="modules/ahrs/ahrs_float_cmpl_wrapper" values="DISABLE|ENABLE" handler="enable"/>
<dl_setting var="ahrs_fc.gravity_heuristic_factor" min="0" step="1" max="50" module="modules/ahrs/ahrs_float_cmpl" shortname="g_heuristic" param="AHRS_GRAVITY_HEURISTIC_FACTOR" type="uint8" persistent="true"/>
<dl_setting var="ahrs_fc.accel_omega" min="0.02" step="0.02" max="0.2" module="modules/ahrs/ahrs_float_cmpl" shortname="acc_omega" param="AHRS_ACCEL_OMEGA" unit="rad/s" type="float" persistent="true"/>
<dl_setting var="ahrs_fc.accel_zeta" min="0.7" step="0.05" max="1.5" module="modules/ahrs/ahrs_float_cmpl" shortname="acc_zeta" param="AHRS_ACCEL_ZETA" type="float" persistent="true"/>
<dl_setting var="ahrs_fc.mag_omega" min="0.02" step="0.01" max="0.1" module="modules/ahrs/ahrs_float_cmpl" shortname="mag_omega" param="AHRS_MAG_OMEGA" unit="rad/s" type="float" persistent="true"/>
<dl_setting var="ahrs_fc.mag_zeta" min="0.7" step="0.05" max="1.5" module="modules/ahrs/ahrs_float_cmpl" shortname="mag_zeta" param="AHRS_MAG_ZETA" type="float" persistent="true"/>
</dl_settings>
</dl_settings>
</settings>
<dep>
<depends>ahrs_common,@imu,@gps|@mag</depends>
<provides>ahrs</provides>
</dep>
<header>
<file name="ahrs_float_cmpl_wrapper.h"/>
</header>
<init fun="ahrs_fc_wrapper_init()"/>
<makefile target="!sim|fbw" firmware="fixedwing">
<configure name="USE_MAGNETOMETER" default="0"/>
<define name="AHRS_USE_GPS_HEADING" cond="ifneq (,$(findstring $(USE_MAGNETOMETER),0 FALSE))"/>
<define name="AHRS_GRAVITY_UPDATE_COORDINATED_TURN"/>
</makefile>
<makefile target="!sim|fbw">
<configure name="AHRS_FC_TYPE" default="AHRS_PRIMARY"/>
<define name="AHRS_FC_TYPE" value="$(AHRS_FC_TYPE)"/>
<configure name="USE_MAGNETOMETER" default="1"/>
<define name="USE_MAGNETOMETER" cond="ifeq (,$(findstring $(USE_MAGNETOMETER),0 FALSE))"/>
<define name="AHRS_PROPAGATE_QUAT"/>
<file name="ahrs_float_cmpl.c"/>
<file name="ahrs_float_cmpl_wrapper.c"/>
<test>
<define name="AHRS_FC_TYPE" value="AHRS_PRIMARY"/>
<define name="AHRS_PROPAGATE_QUAT"/>
</test>
</makefile>
</module>