1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071 |
- # hw definition file for processing by chibios_hwdef.py
- # for The CUBE Black and the Cube Purple hardware
- # this is based on fmuv3, but with vendor specific USB IDs
- include ../fmuv3/hwdef.dat
- define HAL_CHIBIOS_ARCH_CUBEBLACK 1
- env OPTIMIZE -O2
- # USB setup
- USB_VENDOR 0x2DAE # ONLY FOR USE BY HEX! NOBODY ELSE
- USB_PRODUCT 0x1011
- USB_STRING_MANUFACTURER "Hex/ProfiCNC"
- USB_STRING_PRODUCT "CubeBlack"
- USB_STRING_SERIAL "%SERIAL%"
- # remap PB0/1 as ADC's
- undef PB0
- undef PB1
- PB0 PB0_ADC ADC1 SCALE(1)
- PB1 PB1_ADC ADC1 SCALE(1)
- SPIDEV icm20948_ext SPI4 DEVID1 MPU_EXT_CS MODE3 4*MHZ 8*MHZ
- SPIDEV icm20602_ext SPI4 DEVID3 GYRO_EXT_CS MODE3 4*MHZ 8*MHZ
- # three IMUs, but allow for different varients. First two IMUs are
- # isolated, 3rd isn't
- IMU Invensense SPI:mpu9250_ext ROTATION_PITCH_180
- # the 3 rotations for the LSM9DS0 driver are for the accel, the gyro
- # and the H varient of the gyro
- IMU LSM9DS0 SPI:lsm9ds0_ext_g SPI:lsm9ds0_ext_am ROTATION_ROLL_180_YAW_270 ROTATION_ROLL_180_YAW_90 ROTATION_ROLL_180_YAW_90
- # 3rd non-isolated IMU
- IMU Invensense SPI:mpu9250 ROTATION_YAW_270
- # alternative IMU set for newer cubes
- IMU Invensense SPI:icm20602_ext ROTATION_ROLL_180_YAW_270
- IMU Invensensev2 SPI:icm20948_ext ROTATION_PITCH_180
- IMU Invensensev2 SPI:icm20948 ROTATION_YAW_270
- define HAL_DEFAULT_INS_FAST_SAMPLE 5
- # two baros
- BARO MS56XX SPI:ms5611_ext
- BARO MS56XX SPI:ms5611
- # two compasses. First is in the LSM303D
- COMPASS LSM303D SPI:lsm9ds0_ext_am ROTATION_YAW_270
- # 2nd compass is part of the 2nd invensense IMU
- COMPASS AK8963:probe_mpu9250 1 ROTATION_YAW_270
- # compass as part of ICM20948 on newer cubes
- COMPASS AK09916:probe_ICM20948 0 ROTATION_ROLL_180_YAW_90
- # also probe for external compasses
- define HAL_PROBE_EXTERNAL_I2C_COMPASSES
- # This defines an output pin which will default to output HIGH. It is
- # a pin that enables peripheral power on this board. It starts in the
- # off state, then is pulled low to enable peripherals in
- # peripheral_power_enable()
- undef PA8
- PA8 nVDD_5V_PERIPH_EN OUTPUT HIGH
- # This is the pin to enable the sensors rail. It can be used to power
- # cycle sensors to recover them in case there are problems with power on
- # timing affecting sensor stability. We pull it LOW on startup, which
- # means sensors off, then it is pulled HIGH in peripheral_power_enable()
- undef PE3
- PE3 VDD_3V3_SENSORS_EN OUTPUT LOW
|