ardupilot/libraries/AP_HAL_ChibiOS/hwdef/Pix32v5/hwdef.dat

19 lines
545 B
Plaintext
Raw Normal View History

2020-06-11 19:50:56 -03:00
# hw definition file for processing by chibios_hwdef.py
# for Holybro Pix32v5 hardware.
include ../fmuv5/hwdef.dat
USB_VENDOR 0x3162 # ONLY FOR USE BY Holybro
USB_PRODUCT 0x004E
USB_STRING_MANUFACTURER "Holybro"
2021-05-30 21:26:17 -03:00
# this board has a heater, set default target as 45
define HAL_HAVE_IMU_HEATER 1
define HAL_IMU_TEMP_DEFAULT 45
define HAL_IMUHEAT_P_DEFAULT 50
define HAL_IMUHEAT_I_DEFAULT 0.07
# offset the internal compass for EM impact of the IMU heater
# this is in sensor frame mGauss
define HAL_IST8310_I2C_HEATER_OFFSET Vector3f(-3,14,-6)