Propagation is done in rotation matrix representation.
Add to your firmware section: This example contains all possible configuration options, not all of them are mandatory!
The following modules are automatically loaded (just as if you had added them in the airframe file)
<!DOCTYPE module SYSTEM "module.dtd">
<module name="ahrs_flat_cmpl_rmat" dir="ahrs">
<doc>
<description>
AHRS using complementary filter in floating point.
Propagation is done in rotation matrix representation.
</description>
<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_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">
<dl_setting var="ahrs_fc.gravity_heuristic_factor" min="0" step="1" max="50" module="subsystems/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="subsystems/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="subsystems/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="subsystems/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="subsystems/ahrs/ahrs_float_cmpl" shortname="mag_zeta" param="AHRS_MAG_ZETA" type="float" persistent="true"/>
</dl_settings>
</dl_settings>
</settings>
<autoload name="ahrs_sim"/>
<header>
<file name="ahrs.h" dir="subsystems"/>
</header>
<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="USE_MAGNETOMETER" default="1"/>
<define name="USE_MAGNETOMETER" cond="ifeq (,$(findstring $(USE_MAGNETOMETER),0 FALSE))"/>
<define name="AHRS_ALIGNER_LED" value="$(AHRS_ALIGNER_LED)" cond="ifneq ($(AHRS_ALIGNER_LED),none)"/>
<define name="USE_AHRS"/>
<define name="USE_AHRS_ALIGNER"/>
<define name="AHRS_PROPAGATE_RMAT"/>
<file name="ahrs.c" dir="subsystems"/>
<file name="ahrs_aligner.c" dir="subsystems/ahrs"/>
<file name="ahrs_float_cmpl.c" dir="subsystems/ahrs"/>
<file name="ahrs_float_cmpl_wrapper.c" dir="subsystems/ahrs"/>
<raw>
ifdef SECONDARY_AHRS
ifneq (,$(findstring $(SECONDARY_AHRS), fcr float_cmpl_rmat))
# this is the secondary AHRS
$(TARGET).CFLAGS += -DAHRS_SECONDARY_TYPE_H=\"subsystems/ahrs/ahrs_float_cmpl_wrapper.h\"
$(TARGET).CFLAGS += -DSECONDARY_AHRS=ahrs_fc
else
# this is the primary AHRS
$(TARGET).CFLAGS += -DAHRS_TYPE_H=\"subsystems/ahrs/ahrs_float_cmpl_wrapper.h\"
$(TARGET).CFLAGS += -DPRIMARY_AHRS=ahrs_fc
endif
else
# plain old single AHRS usage
$(TARGET).CFLAGS += -DAHRS_TYPE_H=\"subsystems/ahrs/ahrs_float_cmpl_wrapper.h\"
endif
</raw>
</makefile>
</module>