Add target OMNIBUSF4V6

I add target of Airbot Omnibus F4 V6, it is tested and functional at 100%

Update target OmnibusF4V6 to Fireworks variant

Update target.h

Update target.c

Update target.c

Fix motor output resources for Typhoon32 V2

Revert motor changes

Enable SCL and SDA pins

I have enabled the resources I2C2_SCL and I2C2_SDA, in Omnibus F4 V6 they are independent, they do not share with UART3TX / UART3RX

Requested changes

I have reviewed the requested changes, default gyro first and swapping of gyro1 and 2

Removing two linefeed

Add I2C Definitions and Timers

Added definitions and timers for I2C1 device(Baro, Mag)

Update target.c target.h

Some requested changes

Remove I2C Timers

Waiting to find compatible timers for SCL and SDA(I2C)

Update USABLE_TIMER_CHANNEL_COUNT
This commit is contained in:
Asizon 2018-11-25 09:39:40 +01:00
parent e24a4fe4de
commit 31db76b856
4 changed files with 58 additions and 17 deletions

View File

@ -0,0 +1 @@
#OMNIBUSF4V6

View File

@ -32,8 +32,12 @@
#include "config_helper.h" #include "config_helper.h"
static targetSerialPortFunction_t targetSerialPortFunction[] = { static targetSerialPortFunction_t targetSerialPortFunction[] = {
#ifdef OMNIBUSF4V6
{ SERIAL_PORT_USART6, FUNCTION_RX_SERIAL },
#else
{ SERIAL_PORT_USART1, FUNCTION_RX_SERIAL }, { SERIAL_PORT_USART1, FUNCTION_RX_SERIAL },
{ SERIAL_PORT_UART4, FUNCTION_ESC_SENSOR }, { SERIAL_PORT_UART4, FUNCTION_ESC_SENSOR },
#endif
}; };
void targetConfiguration(void) void targetConfiguration(void)

View File

@ -32,22 +32,29 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), // D(1,7) U(1,2) DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), // D(1,7) U(1,2)
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), // D(1,2) U(1,2) DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), // D(1,2) U(1,2)
DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR, 0, 1), // D(1,6) U(1,7) DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR, 0, 1), // D(1,6) U(1,7)
#if defined(OMNIBUSF4FW) #if defined(OMNIBUSF4FW1)
DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR, 0, 0), // D(1,5) U(1,2)
#elif defined(OMNIBUSF4FW1)
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, 0, 0), DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, 0, 0),
#else
DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR, 0, 0), // D(1,5) U(1,2)
#endif #endif
// Additional motors/servos
DEF_TIM(TIM8, CH3, PC8, TIM_USE_NONE, 0, 0), // SJ1/M5
DEF_TIM(TIM8, CH4, PC9, TIM_USE_NONE, 0, 0), // SJ2/M6
// Other functions // Other functions
DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED, 0, 0), // D(1,0) DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED, 0, 0), // D(1,0)
DEF_TIM(TIM10, CH1, PB8, TIM_USE_PPM, 0, 0), // PPM DEF_TIM(TIM10, CH1, PB8, TIM_USE_PPM, 0, 0), // PPM Collision with I2C2_SCL
#if defined(OMNIBUSF4V6)
DEF_TIM(TIM11, CH1, PB7, TIM_USE_CAMERA_CONTROL, 0, 0), // CAM_CTL,timer collision with I2C1_SDA
#else
DEF_TIM(TIM11, CH1, PB9, TIM_USE_CAMERA_CONTROL, 0, 0), // CAM_CTL DEF_TIM(TIM11, CH1, PB9, TIM_USE_CAMERA_CONTROL, 0, 0), // CAM_CTL
#endif
// Spare pins and backdoor timer // Spare pins and backdoor timer
DEF_TIM(TIM8, CH1, PC6, TIM_USE_NONE, 0, 0), // UART6_TX DEF_TIM(TIM8, CH1, PC6, TIM_USE_NONE, 0, 0), // UART6_TX
DEF_TIM(TIM8, CH2, PC7, TIM_USE_NONE, 0, 0), // UART6_RX DEF_TIM(TIM8, CH2, PC7, TIM_USE_NONE, 0, 0), // UART6_RX
DEF_TIM(TIM8, CH3, PC8, TIM_USE_NONE, 0, 0), // SJ1
DEF_TIM(TIM8, CH4, PC9, TIM_USE_NONE, 0, 0), // SJ2
// Backdoor timers on UARTs // Backdoor timers on UARTs
DEF_TIM(TIM1, CH2, PA9, TIM_USE_NONE, 0, 0), // UART1_TX DEF_TIM(TIM1, CH2, PA9, TIM_USE_NONE, 0, 0), // UART1_TX

View File

@ -25,19 +25,28 @@
// OMNIBUSF4FW for Version 2 // OMNIBUSF4FW for Version 2
// OMNIBUSF4FW1/OFW1 for Public Test Version // OMNIBUSF4FW1/OFW1 for Public Test Version
// (Not a valid target, .mk file must be supplied by a user) // (Not a valid target, .mk file must be supplied by a user)
// OMNIBUSF4V6
#if defined(OMNIBUSF4FW) #if defined(OMNIBUSF4V6)
#define TARGET_BOARD_IDENTIFIER "OBFW" #define TARGET_BOARD_IDENTIFIER "OBV6"
#define USBD_PRODUCT_STRING "OmnibusF4 Fireworks"
#elif defined(OMNIBUSF4FW1) #elif defined(OMNIBUSF4FW1)
#define TARGET_BOARD_IDENTIFIER "OFW1" #define TARGET_BOARD_IDENTIFIER "OFW1"
#define USBD_PRODUCT_STRING "OmnibusF4 FWProto1" #else
#define TARGET_BOARD_IDENTIFIER "OBFW"
#endif #endif
#if defined(OMNIBUSF4FW) #if defined(OMNIBUSF4FW1)
#define LED0_PIN PA8 #define USBD_PRODUCT_STRING "OmnibusF4 FWProto1"
#elif defined(OMNIBUSF4FW1) #elif defined(OMNIBUSF4V6)
#define USBD_PRODUCT_STRING "OmnibusF4 V6"
#else
#define USBD_PRODUCT_STRING "OmnibusF4 Fireworks"
#endif
#if defined(OMNIBUSF4FW1)
#define LED0_PIN PB5 #define LED0_PIN PB5
#else
#define LED0_PIN PA8
#endif #endif
#define USE_BEEPER #define USE_BEEPER
@ -54,15 +63,28 @@
#define USE_DUAL_GYRO #define USE_DUAL_GYRO
#if defined(OMNIBUSF4V6)
#define GYRO_1_CS_PIN PA4 // Onboard IMU
#define GYRO_1_SPI_INSTANCE SPI1
#define GYRO_2_CS_PIN PC14 // External IMU
#define GYRO_2_SPI_INSTANCE SPI1
#else
#define GYRO_1_CS_PIN PD2 #define GYRO_1_CS_PIN PD2
#define GYRO_1_SPI_INSTANCE SPI3 #define GYRO_1_SPI_INSTANCE SPI3
#define GYRO_2_CS_PIN PA4 #define GYRO_2_CS_PIN PA4
#define GYRO_2_SPI_INSTANCE SPI1 #define GYRO_2_SPI_INSTANCE SPI1
#endif
#define GYRO_1_ALIGN CW180_DEG #define GYRO_1_ALIGN CW180_DEG
#define ACC_1_ALIGN CW180_DEG #define ACC_1_ALIGN CW180_DEG
#if defined(OMNIBUSF4V6)
#define GYRO_2_ALIGN CW180_DEG
#define ACC_2_ALIGN CW180_DEG
#else
#define GYRO_2_ALIGN CW0_DEG_FLIP #define GYRO_2_ALIGN CW0_DEG_FLIP
#define ACC_2_ALIGN CW0_DEG_FLIP #define ACC_2_ALIGN CW0_DEG_FLIP
#endif
#define GYRO_CONFIG_USE_GYRO_DEFAULT GYRO_CONFIG_USE_GYRO_1 #define GYRO_CONFIG_USE_GYRO_DEFAULT GYRO_CONFIG_USE_GYRO_1
@ -74,11 +96,13 @@
#define USE_MPU_DATA_READY_SIGNAL #define USE_MPU_DATA_READY_SIGNAL
#define USE_MAG #define USE_MAG
#define MAG_I2C_INSTANCE (I2CDEV_1)
#define USE_MAG_HMC5883 #define USE_MAG_HMC5883
#define USE_MAG_LIS3MDL #define USE_MAG_LIS3MDL
#define MAG_HMC5883_ALIGN CW90_DEG #define MAG_HMC5883_ALIGN CW90_DEG
#define USE_BARO #define USE_BARO
#define BARO_I2C_INSTANCE (I2CDEV_1)
#define USE_BARO_SPI_BMP280 #define USE_BARO_SPI_BMP280
#define BMP280_SPI_INSTANCE SPI3 #define BMP280_SPI_INSTANCE SPI3
#define BMP280_CS_PIN PB3 #define BMP280_CS_PIN PB3
@ -147,11 +171,19 @@
#define SPI3_MISO_PIN PC11 #define SPI3_MISO_PIN PC11
#define SPI3_MOSI_PIN PC12 #define SPI3_MOSI_PIN PC12
#if defined(OMNIBUSF4V6)
#define USE_I2C
#define USE_I2C_DEVICE_1
#define I2C1_SCL PB8 // SCL PIN,alt MST8
#define I2C1_SDA PB9 // SDA PIN,alt MST7
#define I2C_DEVICE (I2CDEV_1)
#else
#define USE_I2C #define USE_I2C
#define USE_I2C_DEVICE_2 #define USE_I2C_DEVICE_2
#define I2C2_SCL NONE // PB10, shared with UART3TX #define I2C2_SCL NONE // PB10, shared with UART3TX
#define I2C2_SDA NONE // PB11, shared with UART3RX #define I2C2_SDA NONE // PB11, shared with UART3RX
#define I2C_DEVICE (I2CDEV_2) #define I2C_DEVICE (I2CDEV_2)
#endif
#define USE_ADC #define USE_ADC
#define ADC_INSTANCE ADC2 #define ADC_INSTANCE ADC2
@ -181,9 +213,6 @@
#define TARGET_IO_PORTC (0xffff & ~(BIT(15))) #define TARGET_IO_PORTC (0xffff & ~(BIT(15)))
#define TARGET_IO_PORTD BIT(2) #define TARGET_IO_PORTD BIT(2)
#if defined(OMNIBUSF4FW) || defined(OMNIBUSF4FW1)
#define USABLE_TIMER_CHANNEL_COUNT 15 #define USABLE_TIMER_CHANNEL_COUNT 15
#else
#define USABLE_TIMER_CHANNEL_COUNT 14
#endif
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(8) | TIM_N(9) | TIM_N(10) | TIM_N(11)) #define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(8) | TIM_N(9) | TIM_N(10) | TIM_N(11))