Skip to content

Commit

Permalink
Merge f7a4deb into 893a65f
Browse files Browse the repository at this point in the history
  • Loading branch information
fvantienen committed Apr 19, 2024
2 parents 893a65f + f7a4deb commit 8860e25
Show file tree
Hide file tree
Showing 49 changed files with 3,338 additions and 208 deletions.
360 changes: 360 additions & 0 deletions conf/airframes/examples/pixhawk_6x.xml

Large diffs are not rendered by default.

82 changes: 44 additions & 38 deletions conf/airframes/tudelft/rot_wing_25kg.xml
Original file line number Diff line number Diff line change
Expand Up @@ -10,12 +10,10 @@
<description>RotatingWing25Kg</description>

<firmware name="rotorcraft">
<target name="ap" board="cube_orangeplus">
<target name="ap" board="pixhawk_6x">
<configure name="PERIODIC_FREQUENCY" value="500"/> <!-- Configure the main periodic frequency to 500Hz -->

<module name="radio_control" type="sbus">
<configure name="SBUS_PORT" value="UART3"/> <!-- On the TELEM2 port -->
</module>
<module name="radio_control" type="sbus"/>
<module name="sys_mon"/>
<module name="flight_recorder"/>

Expand All @@ -27,23 +25,24 @@
<define name="RADIO_CONTROL_THRUST_X" value="RADIO_AUX4"/>

<!-- EKF2 configure inputs -->
<define name="INS_EKF2_GYRO_ID" value="IMU_CUBE1_ID"/>
<define name="INS_EKF2_ACCEL_ID" value="IMU_CUBE1_ID"/>
<define name="INS_EKF2_MAG_ID" value="MAG_RM3100_SENDER_ID"/>
<define name="INS_EKF2_GYRO_ID" value="IMU_PIXHAWK2_ID"/>
<define name="INS_EKF2_ACCEL_ID" value="IMU_PIXHAWK2_ID"/>
<define name="INS_EKF2_MAG_ID" value="MAG_RM3100_SENDER_ID"/>

<!--Only send gyro and accel that is being used-->
<define name="IMU_GYRO_ABI_SEND_ID" value= "IMU_CUBE1_ID"/>
<define name="IMU_ACCEL_ABI_SEND_ID" value= "IMU_CUBE1_ID"/>
<define name="IMU_GYRO_ABI_SEND_ID" value="IMU_PIXHAWK2_ID"/>
<define name="IMU_ACCEL_ABI_SEND_ID" value="IMU_PIXHAWK2_ID"/>

<!-- Range sensor connected to supercan -->
<module name="range_sensor_uavcan"/>

<!-- Disable current sensing using UAVCAN -->
<define name="UAVCAN_ACTUATORS_USE_CURRENT" value="FALSE"/>
<define name="USE_I2C1"/>
<define name="UAVCAN_ACTUATORS_USE_CURRENT" value="FALSE"/>

<!-- Log in high speed (Remove for outdoor flights) -->
<!-- <define name="IMU_LOG_HIGHSPEED" value="TRUE"/> -->

<define name="SERVO_ROTATION_MECH_IDX" value="0"/> <!-- !!!!!!!!!!!!!!!!!!!!!!!!!!!! FIXMEEE !!!!!!!!!!!!!!!!!!!!!!!!!! -->
</target>

<target name="nps" board="pc">
Expand All @@ -60,16 +59,17 @@

<!-- Herelink datalink -->
<module name="telemetry" type="transparent">
<configure name="MODEM_PORT" value="usb_serial"/>
<configure name="MODEM_BAUD" value="B460800"/>
</module>

<!-- Sensors -->
<module name="mag" type="rm3100">
<configure name="MAG_RM3100_I2C_DEV" value="I2C1"/>
<define name="MODULE_RM3100_UPDATE_AHRS" value="TRUE"/>
<configure name="MAG_RM3100_I2C_DEV" value="I2C2"/>
</module>
<module name="airspeed" type="ms45xx_i2c">
<define name="MS45XX_I2C_DEV" value="i2c1"/>
<configure name="MS45XX_I2C_DEV" value="I2C2"/>
<define name="MS45XX_AIRSPEED_SCALE" value="2.0833"/>
<define name="USE_AIRSPEED_LOWPASS_FILTER" value="TRUE"/>
<define name="MS45XX_LOWPASS_TAU" value="0.15"/>
Expand All @@ -86,7 +86,7 @@
</module>

<!-- IMU / INS -->
<module name="imu" type="cube"/>
<module name="imu" type="pixhawk6x"/>
<module name="ins" type="ekf2">
<!-- The Cube is mounted 25cm backwards of the CG -->
<define name="INS_EKF2_IMU_POS_X" value="-0.25"/>
Expand Down Expand Up @@ -139,36 +139,42 @@

<!-- Can bus 1 actuators -->
<servos driver="Uavcan1">
<servo no="0" name="MOTOR_FRONT" min="-8191" neutral="-5000" max="8191"/>
<servo no="1" name="MOTOR_RIGHT" min="-8191" neutral="-5000" max="8191"/>
<servo no="2" name="MOTOR_BACK" min="-8191" neutral="-5000" max="8191"/>
<servo no="3" name="MOTOR_LEFT" min="-8191" neutral="-5000" max="8191"/>
<servo no="4" name="MOTOR_PUSH" min="-8191" neutral="-8191" max="8191"/>
<servo no="5" name="SERVO_ELEVATOR" min="-3191" neutral="-3191" max="4900"/>
<servo no="6" name="SERVO_RUDDER" min="-6500" neutral="0" max="6500"/>
<servo no="7" name="ROTATION_MECH" min="8191" neutral="0" max="-8191"/>
<servo no="8" name="AIL_RIGHT" min="-8000" neutral="-1000" max="5000"/>
<servo no="0" name="MOTOR_FRONT" min="-3276" neutral="-2437" max="3605"/> <!-- Supercan (1100-1202.56-1940us) -->
<servo no="1" name="MOTOR_RIGHT" min="-3276" neutral="-2437" max="3605"/> <!-- Supercan (1100-1202.56-1940us) -->
<servo no="2" name="MOTOR_BACK" min="-3276" neutral="-2437" max="3605"/> <!-- Supercan (1100-1202.56-1940us) -->
<servo no="3" name="MOTOR_LEFT" min="0" neutral="1000" max="8191"/> <!-- T-Motor ESC is neutral -->
<servo no="4" name="MOTOR_PUSH" min="-3276" neutral="-3276" max="3605"/> <!-- Supercan (1100-1940us) -->
<!--servo no="8" name="AIL_RIGHT" min="-8000" neutral="-1000" max="5000"/>
<servo no="9" name="FLAP_RIGHT" min="-8000" neutral="-1000" max="5000"/>
<servo no="10" name="AIL_LEFT" min="-5000" neutral="1000" max="8000"/>
<servo no="11" name="FLAP_LEFT" min="-5000" neutral="1000" max="8000"/>
<servo no="12" name="PARACHUTE" min="-8191" neutral="0" max="8191"/>
<servo no="12" name="PARACHUTE" min="-8191" neutral="0" max="8191"/-->
</servos>

<!-- CAN BUS 1 command outputs-->
<servos driver="Uavcan1Cmd">
<servo no="5" name="SERVO_ELEVATOR" min="-3250" neutral="0" max="3250"/>
<servo no="6" name="SERVO_RUDDER" min="-3250" neutral="0" max="3250"/>
</servos>

<!-- Can bus 2 actuators -->
<servos driver="Uavcan2">
<servo no="0" name="BMOTOR_FRONT" min="-8191" neutral="-5000" max="8191"/>
<servo no="1" name="BMOTOR_RIGHT" min="-8191" neutral="-5000" max="8191"/>
<servo no="2" name="BMOTOR_BACK" min="-8191" neutral="-5000" max="8191"/>
<servo no="3" name="BMOTOR_LEFT" min="-8191" neutral="-5000" max="8191"/>
<servo no="4" name="BMOTOR_PUSH" min="-8191" neutral="-8191" max="8191"/>
<servo no="5" name="BSERVO_ELEVATOR" min="-3191" neutral="-3191" max="4900"/>
<servo no="6" name="BSERVO_RUDDER" min="-6500" neutral="0" max="6500"/>
<servo no="7" name="BROTATION_MECH" min="8191" neutral="0" max="-8191"/>
<servo no="8" name="BAIL_RIGHT" min="-8000" neutral="-1000" max="5000"/>
<servo no="0" name="BMOTOR_FRONT" min="0" neutral="1000" max="8191"/> <!-- T-Motor ESC -->
<servo no="1" name="BMOTOR_RIGHT" min="0" neutral="1000" max="8191"/> <!-- T-Motor ESC -->
<servo no="2" name="BMOTOR_BACK" min="0" neutral="1000" max="8191"/> <!-- T-Motor ESC -->
<servo no="3" name="BMOTOR_LEFT" min="-3276" neutral="-2437" max="3605"/> <!-- Supercan (1100-1202.56-1940us) -->
<servo no="4" name="BMOTOR_PUSH" min="-3276" neutral="-3276" max="3605"/> <!-- Supercan (1100-1940us) -->
<!--servo no="8" name="BAIL_RIGHT" min="-8000" neutral="-1000" max="5000"/>
<servo no="9" name="BFLAP_RIGHT" min="-8000" neutral="-1000" max="5000"/>
<servo no="10" name="BAIL_LEFT" min="-5000" neutral="1000" max="8000"/>
<servo no="11" name="BFLAP_LEFT" min="-5000" neutral="1000" max="8000"/>
<servo no="12" name="BPARACHUTE" min="-8191" neutral="0" max="8191"/>
<servo no="12" name="BPARACHUTE" min="-8191" neutral="0" max="8191"/-->
</servos>

<!-- CAN BUS 1 command outputs-->
<servos driver="Uavcan2Cmd">
<servo no="5" name="BSERVO_ELEVATOR" min="-3250" neutral="0" max="3250"/>
<servo no="6" name="BSERVO_RUDDER" min="-3250" neutral="0" max="3250"/>
</servos>

<commands>
Expand All @@ -194,12 +200,12 @@
<set servo="MOTOR_PUSH" value="($th_hold? -9600 : actuators_pprz[8])"/>
<set servo="SERVO_ELEVATOR" value="($servo_hold? (RadioControlValues(RADIO_PITCH)/4+7200) : (!autopilot_in_flight()? 0 : actuators_pprz[5]))"/>
<set servo="SERVO_RUDDER" value="($servo_hold? RadioControlValues(RADIO_YAW) : (!autopilot_in_flight()? 0 : actuators_pprz[4]))"/>
<set servo="ROTATION_MECH" value="rotwing_state_skewing.servo_pprz_cmd"/>
<!--set servo="ROTATION_MECH" value="rotwing_state_skewing.servo_pprz_cmd"/>
<set servo="AIL_RIGHT" value="($servo_hold? RadioControlValues(RADIO_ROLL) : actuators_pprz[6])"/>
<set servo="FLAP_RIGHT" value="($servo_hold? RadioControlValues(RADIO_ROLL) : actuators_pprz[7])"/>
<set servo="AIL_LEFT" value="($servo_hold? RadioControlValues(RADIO_ROLL) : actuators_pprz[6])"/>
<set servo="FLAP_LEFT" value="($servo_hold? RadioControlValues(RADIO_ROLL) : actuators_pprz[7])"/>
<set servo="PARACHUTE" value="RadioControlValues(RADIO_AUX6)"/>
<set servo="PARACHUTE" value="RadioControlValues(RADIO_AUX6)"/-->

<!-- Second bus -->
<set servo="BMOTOR_FRONT" value="($hover_off? -9600 : actuators_pprz[0])"/>
Expand All @@ -209,12 +215,12 @@
<set servo="BMOTOR_PUSH" value="($th_hold? -9600 : actuators_pprz[8])"/>
<set servo="BSERVO_ELEVATOR" value="($servo_hold? (RadioControlValues(RADIO_PITCH)/4+7200) : (!autopilot_in_flight()? 0 : actuators_pprz[5]))"/>
<set servo="BSERVO_RUDDER" value="($servo_hold? RadioControlValues(RADIO_YAW) : (!autopilot_in_flight()? 0 : actuators_pprz[4]))"/>
<set servo="BROTATION_MECH" value="rotwing_state_skewing.servo_pprz_cmd"/>
<!--set servo="BROTATION_MECH" value="rotwing_state_skewing.servo_pprz_cmd"/>
<set servo="BAIL_RIGHT" value="($servo_hold? RadioControlValues(RADIO_ROLL) : actuators_pprz[6])"/>
<set servo="BFLAP_RIGHT" value="($servo_hold? RadioControlValues(RADIO_ROLL) : actuators_pprz[7])"/>
<set servo="BAIL_LEFT" value="($servo_hold? RadioControlValues(RADIO_ROLL) : actuators_pprz[6])"/>
<set servo="BFLAP_LEFT" value="($servo_hold? RadioControlValues(RADIO_ROLL) : actuators_pprz[7])"/>
<set servo="BPARACHUTE" value="RadioControlValues(RADIO_AUX6)"/>
<set servo="BPARACHUTE" value="RadioControlValues(RADIO_AUX6)"/-->
</command_laws>


Expand Down
88 changes: 88 additions & 0 deletions conf/boards/pixhawk_6x.makefile
Original file line number Diff line number Diff line change
@@ -0,0 +1,88 @@
# Hey Emacs, this is a -*- makefile -*-
#
# cube_orange.makefile
#
# This is for the main MCU (STM32F767) on the PX4 board
# See https://pixhawk.org/modules/pixhawk for details
#

BOARD=px4fmu
BOARD_VERSION=v6x
BOARD_DIR=$(BOARD)/chibios/$(BOARD_VERSION)
BOARD_CFG=\"arch/chibios/common_board.h\"

ARCH=chibios
$(TARGET).ARCHDIR = $(ARCH)

RTOS=chibios
MCU=cortex-m7

# FPU on F7
USE_FPU=hard
USE_FPU_OPT= -mfpu=fpv5-d16

#USE_LTO=yes

$(TARGET).CFLAGS += -DPPRZLINK_ENABLE_FD

##############################################################################
# Architecture or project specific options
#
# Define project name here (target)
PROJECT = $(TARGET)

# Project specific files and paths (see Makefile.chibios for details)
CHIBIOS_BOARD_PLATFORM = STM32H7xx/platform.mk
CHIBIOS_LINKER_DIR = $(PAPARAZZI_SRC)/sw/airborne/arch/chibios/
CHIBIOS_BOARD_LINKER = STM32H743xI.ld
CHIBIOS_BOARD_STARTUP = startup_stm32h7xx.mk

##############################################################################
# Compiler settings
#

# default flash mode is the PX4 bootloader
# possibilities: DFU, SWD, PX4 bootloader
FLASH_MODE ?= PX4_BOOTLOADER
PX4_TARGET = "ap"
PX4_PROTOTYPE ?= "${PAPARAZZI_HOME}/sw/tools/px4/px4fmu_v6x.prototype"
PX4_BL_PORT ?= "/dev/serial/by-id/*-BL_*,/dev/serial/by-id/*_BL_*"

#
# default LED configuration
#
SDLOG_LED ?= none
RADIO_CONTROL_LED ?= none
BARO_LED ?= none
AHRS_ALIGNER_LED ?= none
GPS_LED ?= none
SYS_TIME_LED ?= 4

#
# default UART configuration (modem, gps, spektrum)
# The TELEM2 port
SBUS_PORT ?= UART6
RADIO_CONTROL_SPEKTRUM_PRIMARY_PORT ?= UART6

# The TELEM1 port (UART5 is TELEM2, UART2 is TELEM3)
MODEM_PORT ?= UART7
MODEM_BAUD ?= B57600

# The GPS1 port (UART1 is GPS2)
GPS_PORT ?= UART8
GPS_BAUD ?= B460800

# InterMCU port connected to the IO processor
#INTERMCU_PORT ?= UART6
#INTERMCU_BAUD ?= B1500000

#
# default actuator configuration
#
# you can use different actuators by adding a configure option to your firmware section
# e.g. <configure name="ACTUATORS" value="actuators_ppm/>
# and by setting the correct "driver" attribute in servo section
# e.g. <servo driver="Ppm">
#
ACTUATORS ?= actuators_pwm

13 changes: 12 additions & 1 deletion conf/conf_tests.xml
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
telemetry="telemetry/highspeed_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_basic_geofence.xml"
settings="settings/rotorcraft_basic.xml"
settings_modules="modules/air_data.xml modules/electrical.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_indi_hybrid.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/imu_heater.xml modules/ins_ekf2.xml modules/logger_sd_chibios.xml modules/nav_hybrid.xml modules/nav_rotorcraft.xml modules/preflight_checks.xml modules/scheduling_indi_simple.xml modules/stabilization_indi_simple.xml"
settings_modules="modules/air_data.xml modules/airspeed_uavcan.xml modules/electrical.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_indi_hybrid.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/imu_heater.xml modules/ins_ekf2.xml modules/logger_sd_chibios.xml modules/nav_hybrid.xml modules/nav_rotorcraft.xml modules/preflight_checks.xml modules/scheduling_indi_simple.xml modules/stabilization_indi_simple.xml"
gui_color="blue"
/>
<aircraft
Expand Down Expand Up @@ -109,4 +109,15 @@
settings_modules="modules/air_data.xml modules/electrical.xml modules/gps.xml modules/guidance_pid_rotorcraft.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_ekf2.xml modules/nav_rotorcraft.xml modules/stabilization_int_quat.xml"
gui_color="red"
/>
<aircraft
name="Pixhawk6X"
ac_id="5"
airframe="airframes/examples/pixhawk_6x.xml"
radio="radios/crossfire_sbus.xml"
telemetry="telemetry/highspeed_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_basic_geofence.xml"
settings="settings/rotorcraft_basic.xml"
settings_modules="modules/air_data.xml modules/airspeed_ms45xx_i2c.xml modules/airspeed_uavcan.xml modules/electrical.xml modules/gps.xml modules/gps_ublox.xml modules/guidance_indi_hybrid.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/imu_heater.xml modules/ins_ekf2.xml modules/logger_sd_chibios.xml modules/nav_hybrid.xml modules/nav_rotorcraft.xml modules/preflight_checks.xml modules/scheduling_indi_simple.xml modules/stabilization_indi_simple.xml"
gui_color="blue"
/>
</conf>
4 changes: 4 additions & 0 deletions conf/modules/airspeed_ms45xx_i2c.xml
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,10 @@
<event fun="ms45xx_i2c_event()"/>

<makefile target="ap">
<configure name="MS45XX_I2C_DEV" default="i2c2" case="lower|upper"/>
<define name="MS45XX_I2C_DEV" value="$(MS45XX_I2C_DEV_LOWER)"/>
<define name="USE_$(MS45XX_I2C_DEV_UPPER)"/>

<file name="airspeed_ms45xx_i2c.c"/>
<test>
<define name="MS45XX_I2C_PERIODIC_PERIOD" value="0.001"/>
Expand Down
20 changes: 16 additions & 4 deletions conf/modules/baro_board.xml
Original file line number Diff line number Diff line change
Expand Up @@ -152,27 +152,39 @@ LIA_BARO ?= BARO_MS5611_SPI

# PX4FMU
else ifeq ($(BOARD),$(filter $(BOARD),px4fmu))
include $(CFG_SHARED)/spi_master.makefile
BARO_BOARD_SRCS += peripherals/ms5611.c
BARO_BOARD_SRCS += peripherals/ms5611_spi.c
BARO_BOARD_SRCS += boards/baro_board_ms5611_spi.c
ifeq ($(BOARD_VERSION), 1.7)
# PX4FMU 1.7
include $(CFG_SHARED)/spi_master.makefile
BARO_BOARD_SRCS += peripherals/ms5611.c
BARO_BOARD_SRCS += peripherals/ms5611_spi.c
BARO_BOARD_SRCS += boards/baro_board_ms5611_spi.c
BARO_BOARD_CFLAGS += -DUSE_SPI1 -DUSE_SPI_SLAVE3
BARO_BOARD_CFLAGS += -DBB_MS5611_SPI_DEV=spi1
BARO_BOARD_CFLAGS += -DBB_MS5611_SLAVE_IDX=SPI_SLAVE3
else ifeq ($(BOARD_VERSION), 2.4)
# PX4FMU 2.4 a.k.a. PIXHAWK
include $(CFG_SHARED)/spi_master.makefile
BARO_BOARD_SRCS += peripherals/ms5611.c
BARO_BOARD_SRCS += peripherals/ms5611_spi.c
BARO_BOARD_SRCS += boards/baro_board_ms5611_spi.c
BARO_BOARD_CFLAGS += -DUSE_SPI1 -DUSE_SPI_SLAVE3
BARO_BOARD_CFLAGS += -DBB_MS5611_SPI_DEV=spi1
BARO_BOARD_CFLAGS += -DBB_MS5611_SLAVE_IDX=SPI_SLAVE3
else ifeq ($(BOARD_VERSION), 4.0)
# PX4FMU 4.0 a.k.a. PX4_PIXRACER
include $(CFG_SHARED)/spi_master.makefile
BARO_BOARD_SRCS += peripherals/ms5611.c
BARO_BOARD_SRCS += peripherals/ms5611_spi.c
BARO_BOARD_SRCS += boards/baro_board_ms5611_spi.c
BARO_BOARD_CFLAGS += -DUSE_SPI2 -DUSE_SPI_SLAVE3
BARO_BOARD_CFLAGS += -DBB_MS5611_SPI_DEV=spi2
BARO_BOARD_CFLAGS += -DBB_MS5611_SLAVE_IDX=SPI_SLAVE3
else ifeq ($(BOARD_VERSION), 5.0)
# PX4FMU 5.0
include $(CFG_SHARED)/spi_master.makefile
BARO_BOARD_SRCS += peripherals/ms5611.c
BARO_BOARD_SRCS += peripherals/ms5611_spi.c
BARO_BOARD_SRCS += boards/baro_board_ms5611_spi.c
BARO_BOARD_CFLAGS += -DUSE_SPI4 -DUSE_SPI_SLAVE4
BARO_BOARD_CFLAGS += -DBB_MS5611_SPI_DEV=spi4
BARO_BOARD_CFLAGS += -DBB_MS5611_SLAVE_IDX=SPI_SLAVE4
Expand Down
25 changes: 25 additions & 0 deletions conf/modules/boards/pixhawk_6x.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
<!DOCTYPE module SYSTEM "../module.dtd">

<module name="pixhawk_v6x" dir="boards">
<doc>
<description>
Specific configuration for Pixhawk V6X with ChibiOS
</description>
</doc>
<dep>
<depends>spi_master,baro_bmp3</depends>
</dep>
<makefile target="!sim|nps|fbw">
<define name="USE_RTC_BACKUP" value="TRUE"/>
<configure name="SDLOG_USE_RTC" value="FALSE"/>
<configure name="SDLOG_SDIO" value="SDCD2"/>

<!-- On FMU board -->
<!--configure name="BMP3_I2C_DEV" value="i2c2"/>
<define name="BMP3_SLAVE_ADDR" value="BMP3_I2C_ADDR"/-->

<!-- On IMU board -->
<configure name="BMP3_I2C_DEV" value="i2c4"/>
<define name="BMP3_SLAVE_ADDR" value="BMP3_I2C_ADDR_ALT"/>
</makefile>
</module>
2 changes: 1 addition & 1 deletion conf/modules/eff_scheduling_rot_wing.xml
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@
<define name="ROT_WING_EFF_SCHED_IYY_WING" value="1"/>
<define name="ROT_WING_EFF_SCHED_M" value="1"/>
<define name="ROT_WING_EFF_SCHED_DM_DPPRZ_HOVER_PITCH" value="1"/>
<define name="ROT_WING_EFF_SCHED_DM_DPPRZ_HOVER_ROLL" value="1"/>
<define name="ROT_WING_EFF_SCHED_DM_DPPRZ_HOVER_ROLL" value="{1,1}"/>
<define name="ROT_WING_EFF_SCHED_HOVER_ROLL_PITCH_COEF" value="{1,1}"/>
<define name="ROT_WING_EFF_SCHED_HOVER_ROLL_ROLL_COEF" value="{1,1}"/>
<define name="ROT_WING_EFF_SCHED_K_ELEVATOR" value="{1,1,1}"/>
Expand Down
2 changes: 1 addition & 1 deletion conf/modules/imu_cube.xml
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@
</description>
</doc>
<dep>
<depends>spi_master,imu_common,intermcu_iomcu,imu_heater</depends>
<depends>spi_master,i2c,imu_common,intermcu_iomcu,imu_heater</depends>
<provides>imu</provides>
</dep>
<header>
Expand Down

0 comments on commit 8860e25

Please sign in to comment.