diff --git a/libraries/AP_HAL/board/f4light.h b/libraries/AP_HAL/board/f4light.h index fa9905c4b8..d0a33c928d 100644 --- a/libraries/AP_HAL/board/f4light.h +++ b/libraries/AP_HAL/board/f4light.h @@ -1,5 +1,6 @@ #include #include +#include #define HAL_NEEDS_PARAM_HELPER diff --git a/libraries/AP_HAL_F4Light/HAL_F4Light_Class.cpp b/libraries/AP_HAL_F4Light/HAL_F4Light_Class.cpp index 349241d9d2..ab80ca22dc 100644 --- a/libraries/AP_HAL_F4Light/HAL_F4Light_Class.cpp +++ b/libraries/AP_HAL_F4Light/HAL_F4Light_Class.cpp @@ -46,8 +46,10 @@ static F4Light::I2CDeviceManager i2c_mgr_instance; // XXX make sure these are assigned correctly static USBDriver USB_Driver(1); // ACM static UARTDriver uart1Driver(_USART1); // main port -static UARTDriver uart6Driver(_USART6); // pin 7&8(REVO)/5&6(RevoMini) of input port +#if defined(BOARD_USART6_RX_PIN) && defined(BOARD_USART6_TX_PIN) +static UARTDriver uart6Driver(_USART6); // pin 7&8(REVO)/5&6(RevoMini) of input port +#endif #ifdef BOARD_HAS_UART3 @@ -68,6 +70,10 @@ static UARTDriver uart6Driver(_USART6); // pin 7&8(REVO)/5&6(RevoMini) of input static UARTDriver uart4Driver(_UART4); // pin 5&6 of servo port #endif +#if defined(BOARD_USART5_RX_PIN) && defined( BOARD_USART5_TX_PIN) + static UARTDriver uart5Driver(_UART5); +#endif + static UART_PPM uartPPM2(1); // PPM2 input static UART_PPM uartPPM1(0); // PPM1 input @@ -132,47 +138,59 @@ AP_SerialManager.cpp line 159 HAL_F4Light::HAL_F4Light() : AP_HAL::HAL( &USB_Driver, // uartA - USB console - Serial0 - &uart6Driver, // uartB - pin 7&8(REVO)/5&6(RevoMini) of input port - for GPS - Serial3 - &uart1Driver, // uartC - main port - for telemetry - Serial1 #if BOARD_UARTS_LAYOUT == 1 // Revolution + &uart6Driver, // uartB - pin 7&8(REVO)/5&6(RevoMini) of input port - for GPS - Serial3 + &uart1Driver, // uartC - main port - for telemetry - Serial1 &uart3Driver, // uartD - flexi port - Serial2 &uart4Driver, // uartE - PWM pins 5&6 - Serial4 &softDriver, // uartF - soft UART on pins 7&8 - Serial5 #elif BOARD_UARTS_LAYOUT == 2 // Airbot + &uart6Driver, // uartB - pin 7&8(REVO)/5&6(RevoMini) of input port - for GPS - Serial3 + &uart1Driver, // uartC - main port - for telemetry - Serial1 &uart4Driver, // uartD - PWM pins 5&6 - Serial2 &uartPPM2, // uartE - input data from PPM2 pin - Serial4 &uartPPM1, // uartF - input data from PPM1 pin - Serial5 #elif BOARD_UARTS_LAYOUT == 3 // AirbotV2 + &uart6Driver, // uartB - pin 7&8(REVO)/5&6(RevoMini) of input port - for GPS - Serial3 + &uart1Driver, // uartC - main port - for telemetry - Serial1 &uartOSDdriver, // uartD - OSD emulated UART - Serial2 &uart4Driver, // uartE - PWM pins 5&6 - Serial4 &uartPPM2, // uartF - input data from PPM2 pin - Serial5 #elif BOARD_UARTS_LAYOUT == 4 // MiniOSD + &uart6Driver, // uartB - pin 7&8(REVO)/5&6(RevoMini) of input port - for GPS - Serial3 + &uart1Driver, // uartC - main port - for telemetry - Serial1 NULL, NULL, NULL, #elif BOARD_UARTS_LAYOUT == 5 // MicroOSD + &uart6Driver, // uartB - pin 7&8(REVO)/5&6(RevoMini) of input port - for GPS - Serial3 + &uart1Driver, // uartC - main port - for telemetry - Serial1 NULL, NULL, NULL, -#elif BOARD_UARTS_LAYOUT == 6 // MatekF405_OSD +#elif BOARD_UARTS_LAYOUT == 6 // MatekF405_CTR - NULL, - NULL, - NULL, + &uart4Driver, // uartB - UART4 for GPS - Serial3 + &uart1Driver, // uartC - UART1 for telemetry - Serial1 + &uartOSDdriver, // uartD - OSD emulated UART - Serial2 + &uart3Driver, // uartE - UART3 - Serial4 + &uart5Driver, // uartF - UART5 - Serial5 #elif BOARD_UARTS_LAYOUT == 7 // Cl_Racing F4 + &uart6Driver, // uartB - pin 7&8(REVO)/5&6(RevoMini) of input port - for GPS - Serial3 + &uart1Driver, // uartC - main port - for telemetry - Serial1 &uartOSDdriver, // uartD - OSD emulated UART - Serial2 &uartPPM1, // uartE - input data from PPM1 pin - Serial4 NULL, // no uartF diff --git a/libraries/AP_HAL_F4Light/I2CDevice.cpp b/libraries/AP_HAL_F4Light/I2CDevice.cpp index 5ee432edae..713ab6dafd 100644 --- a/libraries/AP_HAL_F4Light/I2CDevice.cpp +++ b/libraries/AP_HAL_F4Light/I2CDevice.cpp @@ -95,7 +95,7 @@ void I2CDevice::init(){ switch(_bus) { case 0: // this is always internal bus -#ifndef BOARD_I2C1_DISABLE +#if defined(I2C1_SDA) && defined(I2C1_SCL) && !defined(BOARD_I2C1_DISABLE) _offs =0; #if defined(BOARD_I2C_BUS_SLOW) && BOARD_I2C_BUS_SLOW==0 _slow=true; @@ -103,9 +103,11 @@ void I2CDevice::init(){ #if defined(BOARD_SOFT_I2C) || defined(BOARD_SOFT_I2C1) if(s_i2c==NULL) s_i2c = new Soft_I2C; + const stm32_pin_info &p_sda = PIN_MAP[_I2C1->sda_pin]; + const stm32_pin_info &p_scl = PIN_MAP[_I2C1->scl_pin]; s_i2c->init_hw( - _I2C1->gpio_port, _I2C1->scl_pin, - _I2C1->gpio_port, _I2C1->sda_pin, + p_scl.gpio_device, p_scl.gpio_bit, + p_sda.gpio_device, p_sda.gpio_bit, _timers[_bus] ); #else @@ -117,7 +119,7 @@ void I2CDevice::init(){ #endif case 1: // flexi port - I2C2 -#if !defined( BOARD_I2C2_DISABLE) && !defined(BOARD_HAS_UART3) // in this case I2C on FlexiPort will be bus 2 +#if defined(I2C2_SDA) && defined(I2C2_SCL) && !defined( BOARD_I2C2_DISABLE) && !defined(BOARD_HAS_UART3) // in this case I2C on FlexiPort will be bus 2 _offs = 2; #if defined(BOARD_I2C_BUS_SLOW) && BOARD_I2C_BUS_SLOW==1 @@ -126,9 +128,11 @@ void I2CDevice::init(){ #if defined(BOARD_SOFT_I2C) || defined(BOARD_SOFT_I2C2) if(s_i2c==NULL) s_i2c = new Soft_I2C; + const stm32_pin_info &p_sda = PIN_MAP[_I2C2->sda_pin]; + const stm32_pin_info &p_scl = PIN_MAP[_I2C2->scl_pin]; s_i2c->init_hw( - _I2C2->gpio_port, _I2C2->scl_pin, - _I2C2->gpio_port, _I2C2->sda_pin, + p_scl.gpio_device, p_scl.gpio_bit, + p_sda.gpio_device, p_sda.gpio_bit, _timers[_bus] ); #else @@ -148,9 +152,11 @@ void I2CDevice::init(){ if(hal_param_helper->_flexi_i2c){ // move external I2C to flexi port #if defined(BOARD_SOFT_I2C) || defined(BOARD_SOFT_I2C3) if(s_i2c==NULL) s_i2c = new Soft_I2C; + const stm32_pin_info &p_sda = PIN_MAP[_I2C2->sda_pin]; + const stm32_pin_info &p_scl = PIN_MAP[_I2C2->scl_pin]; s_i2c->init_hw( - _I2C2->gpio_port, _I2C2->scl_pin, - _I2C2->gpio_port, _I2C2->sda_pin, + p_scl.gpio_device, p_scl.gpio_bit, + p_sda.gpio_device, p_sda.gpio_bit, _timers[_bus] ); #else @@ -170,6 +176,10 @@ void I2CDevice::init(){ } break; +// TODO +#if defined(I2C3_SDA) && defined(I2C3_SCL) +#endif + default: return; } diff --git a/libraries/AP_HAL_F4Light/RC_DSM_parser.cpp b/libraries/AP_HAL_F4Light/RC_DSM_parser.cpp index d98f5b8f24..510f716dc2 100644 --- a/libraries/AP_HAL_F4Light/RC_DSM_parser.cpp +++ b/libraries/AP_HAL_F4Light/RC_DSM_parser.cpp @@ -27,8 +27,6 @@ extern const AP_HAL::HAL& hal; #if defined(BOARD_DSM_USART) UARTDriver DSM_parser::uartSDriver(BOARD_DSM_USART); // UART connected to DSM pin -#elif defined(BOARD_USART5_RX_PIN) && defined(BOARD_USART5_TX_PIN) -UARTDriver DSM_parser::uartSDriver(_UART5); #endif diff --git a/libraries/AP_HAL_F4Light/Scheduler.cpp b/libraries/AP_HAL_F4Light/Scheduler.cpp index bf239fccff..c5c0dd7b0f 100644 --- a/libraries/AP_HAL_F4Light/Scheduler.cpp +++ b/libraries/AP_HAL_F4Light/Scheduler.cpp @@ -584,7 +584,7 @@ void Scheduler::_print_stats(){ if(is_zero(shed_eff)) shed_eff = eff; else shed_eff = shed_eff*(1 - 1/Kf) + eff*(1/Kf); - printf("\nSched stats:\n %% of full time: %5.2f Efficiency %5.3f max loop time %ld\n", (task_time/10.0)/t /* in percent*/ , shed_eff, max_loop_time); + printf("\nSched stats: uptime %lds\n %% of full time: %5.2f Efficiency %5.3f max loop time %ld\n", t/1000, (task_time/10.0)/t /* in percent*/ , shed_eff, max_loop_time); printf("delay times: in main %5.2f including in timer %5.2f", (delay_time/10.0)/t, (delay_int_time/10.0)/t); max_loop_time=0; @@ -1279,9 +1279,9 @@ void SVC_Handler(){ : "=rm" (svc_args) ); Scheduler::SVC_Handler(svc_args); - } + // svc executes on same priority as Timer7 ISR so there is no need to prevent interrupts void Scheduler::SVC_Handler(uint32_t * svc_args){ // * Stack contains: * r0, r1, r2, r3, r12, r14, the return address and xPSR diff --git a/libraries/AP_HAL_F4Light/boards/f4light_Airbot/board.h b/libraries/AP_HAL_F4Light/boards/f4light_Airbot/board.h index ee46235271..59fa68c609 100644 --- a/libraries/AP_HAL_F4Light/boards/f4light_Airbot/board.h +++ b/libraries/AP_HAL_F4Light/boards/f4light_Airbot/board.h @@ -95,6 +95,12 @@ #define BOARD_NR_GPIO_PINS 109 +#define I2C1_SDA PB9 +#define I2C1_SCL PB8 + +#define I2C2_SDA PB11 +#define I2C2_SCL PB10 + // use soft I2C driver instead hardware //#define BOARD_SOFT_I2C2 //#define BOARD_I2C_BUS_INT 1 // hardware internal I2C @@ -166,6 +172,8 @@ #define SERVO_PIN_5 48 // PA1 #define SERVO_PIN_6 22 // PA8 +#define MOTOR_LAYOUT_DEFAULT 0 + #define HAL_CONSOLE USB_Driver // console on USB //#define HAL_CONSOLE uart1Driver // console on radio #define HAL_CONSOLE_PORT 0 diff --git a/libraries/AP_HAL_F4Light/boards/f4light_AirbotV2/board.h b/libraries/AP_HAL_F4Light/boards/f4light_AirbotV2/board.h index 2a04eef1bb..efa3eb8248 100644 --- a/libraries/AP_HAL_F4Light/boards/f4light_AirbotV2/board.h +++ b/libraries/AP_HAL_F4Light/boards/f4light_AirbotV2/board.h @@ -167,6 +167,8 @@ #define SERVO_PIN_5 48 // PA1 #define SERVO_PIN_6 22 // PA8 +#define MOTOR_LAYOUT_DEFAULT 0 + #if 1 #define HAL_CONSOLE USB_Driver // console on USB #define HAL_CONSOLE_PORT 0 diff --git a/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_CTR/1_read_me.md b/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_CTR/1_read_me.md new file mode 100644 index 0000000000..f46661c9cf --- /dev/null +++ b/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_CTR/1_read_me.md @@ -0,0 +1,38 @@ +this is for Matek F405-CTR board + +# Board connection + +Just see board's documentation. + + +## Default connection +| Function | Serial | +| ------ | ------ | +| USB | Serial0 in MP | +| Telemetry | UART1 (Serial1) | +| GPS | UART6 (Serial3) | +| Built-in OSD | Serial2 | +| UART2 | Serial4 | +| UART5 | Serial5 | + +This board REQUIRES external Compass via I2C bus. + +## OSD +Built-in OSD can be configured via files in root directory of SD card: +- eeprom.osd is configuration, exported from Configuration Tool. +- font.mcm is font (select one of https://github.com/night-ghost/minimosd-extra/tree/master/Released/FW_%2B_Char). This file will be deleted after flashing. + +Firmware supports connection to built-in OSD with CT from my MinimOSD (https://github.com/night-ghost/minimosd-extra). To do this: +- set BRD_CONNECT_COM parameter to OSD's Serial (usually 2), then reboot / power cycle +- USB will be connected to OSD after reboot, supported load/store/fonts in MAVLink mode + +## Voltage and current reading + +How to get voltage/current reading(tested on omnibus, should work on other targets to): +- BAT_MONITOR 4 +- BAT_VOLT_PIN 8 +- BAT_CURR_PIN 7 +- BAT_VOLT_MULT 11.0 (or 10.1 for apm power module) +- BAT_AMP_PERVOLT 38.0 (or 17 for apm power module) + +Don't try to configure Curr/Vol reading from Initial setup page of MP, because VOL/CURR variables will be reset. diff --git a/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_OSD/board.cpp b/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_CTR/board.cpp similarity index 74% rename from libraries/AP_HAL_F4Light/boards/f4light_MatekF405_OSD/board.cpp rename to libraries/AP_HAL_F4Light/boards/f4light_MatekF405_CTR/board.cpp index 40906695c9..f058d92f71 100644 --- a/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_OSD/board.cpp +++ b/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_CTR/board.cpp @@ -7,6 +7,17 @@ using namespace F4Light; +/* + LQFP64 + + PA0-15 + PB0-15 + PC0-12 + PD2 + + +*/ + extern const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS] __FLASH__ = { /* Top header */ @@ -19,35 +30,35 @@ extern const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS] __FLASH__ = { uint8_t adc_channel; < Pin ADC channel, or nADC if none. */ - {&gpiob, NULL, NULL, 10, NO_CH, nADC}, /* D0/PB10 0 USART3_TX/I2C2-SCL */ - {&gpiob, NULL, NULL, 2, NO_CH, nADC}, /* D1/PB2 1*/ + {&gpiob, NULL, NULL, 10, NO_CH, nADC}, /* D0/PB10 0 MAX7456_SPI_CS_PIN */ + {&gpiob, NULL, NULL, 2, NO_CH, nADC}, /* D1/PB2 1 (BOOT1) */ {&gpiob, NULL, NULL, 12, NO_CH, nADC}, /* D2/PB12 2 SDCARD CS pin */ {&gpiob, NULL, NULL, 13, NO_CH, nADC}, /* D3/PB13 3 SPI2_SCK */ {&gpiob,&timer12,NULL, 14, TIMER_CH1, nADC}, /* D4/PB14 4 SPI2_MOSI */ {&gpiob,&timer12,NULL, 15, TIMER_CH2, nADC}, /* D5/PB15 5 SPI2_MISO */ - {&gpioc, NULL,&_adc1, 0, NO_CH, 10}, /* D6/PC0 6 NC */ - {&gpioc, NULL,&_adc1, 1, NO_CH, 11}, /* D7/PC1 7 AMP */ - {&gpioc, NULL,&_adc1, 2, NO_CH, 12}, /* D8/PC2 8 VOLT */ - {&gpioc, NULL,&_adc1, 3, NO_CH, 13}, /* D9/PC3 9 freq sense - resistor to VCC, used asd MAX7456 VSYNC */ - {&gpioc, NULL,&_adc1, 4, NO_CH, 14}, /* D10/PC4 10 EXTI_MPU6000 */ - {&gpioc, NULL,&_adc1, 5, NO_CH, 15}, /* D11/PC5 1 Vbat */ - {&gpioc, &timer8,NULL, 6, TIMER_CH1, nADC}, /* D12/PC6 2 CH3_IN / UART6_TX */ - {&gpioc, &timer8,NULL, 7, TIMER_CH2, nADC}, /* D13/PC7 3 CH4_IN / UART6_RX */ - {&gpioc, &timer8,NULL, 8, TIMER_CH3, nADC}, /* D14/PC8 4 CH5_IN / S_scl */ - {&gpioc, &timer8,NULL, 9, TIMER_CH4, nADC}, /* D15/PC9 5 CH6_IN / S_sda */ - {&gpioc, NULL, NULL, 10, NO_CH, nADC}, /* D16/PC10 6 */ - {&gpioc, NULL, NULL, 11, NO_CH, nADC}, /* D17/PC11 7 */ - {&gpioc, NULL, NULL, 12, NO_CH, nADC}, /* D18/PC12 8 */ - {&gpioc, NULL, NULL, 13, NO_CH, nADC}, /* D19/PC13 9 */ - {&gpioc, NULL, NULL, 14, NO_CH, nADC}, /* D20/PC14 20 */ - {&gpioc, NULL, NULL, 15, NO_CH, nADC}, /* D21/PC15 1 */ - {&gpioa, &timer1,NULL, 8, TIMER_CH1, nADC}, /* D22/PA8 2 SERVO6 */ + {&gpioc, NULL,&_adc1, 0, NO_CH, 10}, /* D6/PC0 6 */ + {&gpioc, NULL,&_adc1, 1, NO_CH, 11}, /* D7/PC1 7 SD CS */ + {&gpioc, NULL,&_adc1, 2, NO_CH, 12}, /* D8/PC2 8 CS_MPU6000 */ + {&gpioc, NULL,&_adc1, 3, NO_CH, 13}, /* D9/PC3 9 EXTI_MPU6000 */ + {&gpioc, NULL,&_adc1, 4, NO_CH, 14}, /* D10/PC4 10 Current */ + {&gpioc, NULL,&_adc1, 5, NO_CH, 15}, /* D11/PC5 1 Vbat */ + {&gpioc, &timer8,NULL, 6, TIMER_CH1, nADC}, /* D12/PC6 2 SERVO_1 */ + {&gpioc, &timer8,NULL, 7, TIMER_CH2, nADC}, /* D13/PC7 3 SERVO_2 */ + {&gpioc, &timer8,NULL, 8, TIMER_CH3, nADC}, /* D14/PC8 4 SERVO_3 */ + {&gpioc, &timer8,NULL, 9, TIMER_CH4, nADC}, /* D15/PC9 5 SERVO_4 */ + {&gpioc, NULL, NULL, 10, NO_CH, nADC}, /* D16/PC10 6 UART3 RX */ + {&gpioc, NULL, NULL, 11, NO_CH, nADC}, /* D17/PC11 7 UART3 TX */ + {&gpioc, NULL, NULL, 12, NO_CH, nADC}, /* D18/PC12 8 UART5_TX */ + {&gpioc, NULL, NULL, 13, NO_CH, nADC}, /* D19/PC13 9 Buzzer */ + {&gpioc, NULL, NULL, 14, NO_CH, nADC}, /* D20/PC14 20 n/a */ + {&gpioc, NULL, NULL, 15, NO_CH, nADC}, /* D21/PC15 1 n/a */ + {&gpioa, &timer1,NULL, 8, TIMER_CH1, nADC}, /* D22/PA8 2 SERVO_6 */ {&gpioa, &timer1,NULL, 9, TIMER_CH2, nADC}, /* D23/PA9 3 USART1_TX */ {&gpioa, &timer1,NULL, 10, TIMER_CH3, nADC}, /* D24/PA10 4 USART1_RX */ {&gpiob, &timer4,NULL, 9, TIMER_CH4, nADC}, /* D25/PB9 5 LED */ - {&gpiod, NULL, NULL, 2, NO_CH, nADC}, /* D26/PD2 6 EXTI_RFM22B / UART5_RX */ - {&gpiod, NULL, NULL, 3, NO_CH, nADC}, /* D27/PD3 7*/ - {&gpiod, NULL, NULL, 6, NO_CH, nADC}, /* D28/PD6 8*/ + {&gpiod, NULL, NULL, 2, NO_CH, nADC}, /* D26/PD2 6 UART5_RX */ + {&gpiod, NULL, NULL, 3, NO_CH, nADC}, /* D27/PD3 7 n/a */ + {&gpiod, NULL, NULL, 6, NO_CH, nADC}, /* D28/PD6 8 n/a */ {&gpiog, NULL, NULL, 11, NO_CH, nADC}, /* D29/PG11 9*/ {&gpiog, NULL, NULL, 12, NO_CH, nADC}, /* D30/PG12 30*/ {&gpiog, NULL, NULL, 13, NO_CH, nADC}, /* D31/PG13 1*/ @@ -55,25 +66,25 @@ extern const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS] __FLASH__ = { {&gpiog, NULL, NULL, 8, NO_CH, nADC}, /* D33/PG8 3*/ {&gpiog, NULL, NULL, 7, NO_CH, nADC}, /* D34/PG7 4*/ {&gpiog, NULL, NULL, 6, NO_CH, nADC}, /* D35/PG6 5*/ - {&gpiob, &timer3,NULL, 5, TIMER_CH2, nADC}, /* D36/PB5 6 */ - {&gpiob, &timer4,NULL, 6, TIMER_CH1, nADC}, /* D37/PB6 7 RCD_CS on SPI_3*/ - {&gpiob, &timer4,NULL, 7, TIMER_CH2, nADC}, /* D38/PB7 8 SD_DET */ + {&gpiob, &timer3,NULL, 5, TIMER_CH2, nADC}, /* D36/PB5 6 SPI3 MOSI */ + {&gpiob, &timer4,NULL, 6, TIMER_CH1, nADC}, /* D37/PB6 7 SCL pad */ + {&gpiob, &timer4,NULL, 7, TIMER_CH2, nADC}, /* D38/PB7 8 SDA pad */ {&gpiof, NULL,&_adc3, 6, NO_CH, 4}, /* D39/PF6 9*/ {&gpiof, NULL,&_adc3, 7, NO_CH, 5}, /* D40/PF7 40*/ {&gpiof, NULL,&_adc3, 8, NO_CH, 6}, /* D41/PF8 1*/ {&gpiof, NULL,&_adc3, 9, NO_CH, 7}, /* D42/PF9 2*/ {&gpiof, NULL,&_adc3,10, NO_CH, 8}, /* D43/PF10 3*/ {&gpiof, NULL, NULL, 11, NO_CH, nADC}, /* D44/PF11 4*/ - {&gpiob, &timer3,&_adc1,1, TIMER_CH4, 9}, /* D45/PB1 5 SERVO2 */ - {&gpiob, &timer3,&_adc1,0, TIMER_CH3, 8}, /* D46/PB0 6 SERVO1 */ - {&gpioa, &timer2,&_adc1,0, TIMER_CH1, 0}, /* D47/PA0 7 RSSI input */ - {&gpioa, &timer2,&_adc1,1, TIMER_CH2, 1}, /* D48/PA1 8 SERVO5 / UART4_RX */ - {&gpioa, &timer2,&_adc1,2, TIMER_CH3, 2}, /* D49/PA2 9 SERVO4 */ - {&gpioa, &timer2,&_adc1,3, TIMER_CH4, 3}, /* D50/PA3 50 SERVO3 */ - {&gpioa, NULL, &_adc1,4, NO_CH, 4}, /* D51/PA4 1 CS_MPU6000 */ - {&gpioa, NULL, &_adc1,5, NO_CH, 5}, /* D52/PA5 2 SPI1_CLK */ - {&gpioa, &timer3,&_adc1,6, TIMER_CH1, 6}, /* D53/PA6 3 SPI1_MISO */ - {&gpioa, &timer3,&_adc1,7, TIMER_CH2, 7}, /* D54/PA7 4 SPI1_MOSI */ + {&gpiob, &timer3,&_adc1,1, TIMER_CH4, 9}, /* D45/PB1 5 RSSI */ + {&gpiob, &timer3,&_adc1,0, TIMER_CH3, 8}, /* D46/PB0 6 */ + {&gpioa, &timer2,&_adc1,0, TIMER_CH1, 0}, /* D47/PA0 7 UART4 TX (wkup)*/ + {&gpioa, &timer2,&_adc1,1, TIMER_CH2, 1}, /* D48/PA1 8 UART4_RX */ + {&gpioa, &timer2,&_adc1,2, TIMER_CH3, 2}, /* D49/PA2 9 PPM_IN 2 */ + {&gpioa, &timer2,&_adc1,3, TIMER_CH4, 3}, /* D50/PA3 50 PPM_IN 1 */ + {&gpioa, NULL, &_adc1,4, NO_CH, 4}, /* D51/PA4 1 */ + {&gpioa, NULL, &_adc1,5, NO_CH, 5}, /* D52/PA5 2 SPI1_CLK */ + {&gpioa, &timer3,&_adc1,6, TIMER_CH1, 6}, /* D53/PA6 3 SPI1_MISO */ + {&gpioa, &timer3,&_adc1,7, TIMER_CH2, 7}, /* D54/PA7 4 SPI1_MOSI */ {&gpiof, NULL, NULL, 0, NO_CH, nADC}, /* D55/PF0 5*/ {&gpiod, NULL, NULL, 11, NO_CH, nADC}, /* D56/PD11 6*/ {&gpiod, &timer4,NULL, 14, TIMER_CH3, nADC}, /* D57/PD14 7*/ @@ -119,14 +130,14 @@ extern const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS] __FLASH__ = { {&gpiod, NULL, NULL, 9, NO_CH, nADC}, /* D97/PD9 7*/ {&gpiog, NULL, NULL, 5, NO_CH, nADC}, /* D98/PG5 8*/ {&gpiod, NULL, NULL, 10, NO_CH, nADC}, /* D99/PD10 9*/ - {&gpiob, NULL, NULL, 11, NO_CH, nADC}, /* D100/PB11 100 USART3_RX/I2C2-SDA */ - {&gpiob, &timer4,NULL, 8, TIMER_CH3, nADC}, /* D101/PB8 I2C1_SCL PPM_IN */ + {&gpiob, NULL, NULL, 11, NO_CH, nADC}, /* D100/PB11 100 */ + {&gpiob, &timer4,NULL, 8, TIMER_CH3, nADC}, /* D101/PB8 */ {&gpioe, NULL, NULL, 2, NO_CH, nADC}, /* D102/PE2 */ - {&gpioa, NULL, NULL, 15, NO_CH, nADC}, /* D103/PA15 */ - {&gpiob, NULL, NULL, 3, NO_CH, nADC}, /* D104/PB3 */ - {&gpiob, NULL, NULL, 4, NO_CH, nADC}, /* D105/PB4 */ + {&gpioa, &timer2,NULL, 15, TIMER_CH1, nADC}, /* D103/PA15 SERVO_5 */ + {&gpiob, NULL, NULL, 3, NO_CH, nADC}, /* D104/PB3 SPI3 SCK */ + {&gpiob, NULL, NULL, 4, NO_CH, nADC}, /* D105/PB4 SPI3 MISO */ {&gpioa, NULL, NULL, 13, NO_CH, nADC}, /* D106/PA13 SWDIO */ - {&gpioa, NULL, NULL, 14, NO_CH, nADC}, /* D107/PA14 SWCLK */ + {&gpioa, NULL, NULL, 14, NO_CH, nADC}, /* D107/PA14 SWCLK LED */ {&gpioa, NULL, NULL, 11, NO_CH, nADC}, /* D108/PA11 - USB D- */ }; @@ -135,22 +146,22 @@ extern const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS] __FLASH__ = { extern const struct TIM_Channel PWM_Channels[] __FLASH__ = { //CH1 and CH2 also for PPMSUM / SBUS / DSM { // 0 RC_IN1 - .pin = 50, + .pin = PA3, // UART2 RX }, { // 1 RC_IN2 - .pin = 37, + .pin = PA2, // UART2 TX }, { // 2 RC_IN3 - .pin = -1, + .pin = (uint8_t)-1, }, { // 3 RC_IN4 - .pin = -1, + .pin = (uint8_t)-1, }, { // 4 RC_IN5 - .pin = -1, + .pin = (uint8_t)-1, }, { // 5 RC_IN6 - .pin = -1, + .pin = (uint8_t)-1, }, }; @@ -166,9 +177,9 @@ extern const struct TIM_Channel PWM_Channels[] __FLASH__ = { extern const SPIDesc spi_device_table[] = { // different SPI tables per board subtype // name device bus mode cs_pin speed_low speed_high dma priority { BOARD_INS_MPU60x0_NAME, _SPI1, 1, SPI_MODE_0, BOARD_MPU6000_CS_PIN, SPI_1_125MHZ, SPI_9MHZ, SPI_TRANSFER_DMA, DMA_Priority_VeryHigh, 1, 5 }, - { BOARD_SDCARD_NAME, _SPI3, 2, SPI_MODE_0, 255, SPI_1_125MHZ, SPI_18MHZ, SPI_TRANSFER_DMA, DMA_Priority_Medium, 0, 0 }, - { HAL_BARO_BMP280_NAME, _SPI3, 3, SPI_MODE_3, BOARD_BMP280_CS_PIN, SPI_1_125MHZ, SPI_9MHZ, SPI_TRANSFER_DMA, DMA_Priority_High, 1, 1 }, - { BOARD_OSD_NAME, _SPI2, 3, SPI_MODE_0, BOARD_OSD_CS_PIN, SPI_1_125MHZ, SPI_4_5MHZ, SPI_TRANSFER_DMA, DMA_Priority_Low, 2, 2 }, + { BOARD_SDCARD_NAME, _SPI3, 3, SPI_MODE_3, 255, SPI_1_125MHZ, SPI_18MHZ, SPI_TRANSFER_DMA, DMA_Priority_Medium, 0, 0 }, + { BOARD_OSD_NAME, _SPI2, 2, SPI_MODE_0, BOARD_OSD_CS_PIN, SPI_1_125MHZ, SPI_4_5MHZ, SPI_TRANSFER_DMA, DMA_Priority_Low, 2, 2 }, +// { BOARD_DATAFLASH_NAME, _SPI3, 3, SPI_MODE_3, 255/*device controls CS*/,SPI_1_125MHZ, SPI_18MHZ, SPI_TRANSFER_DMA, DMA_Priority_High, 1, 1 }, }; extern const uint8_t F4Light_SPI_DEVICE_NUM_DEVICES = ARRAY_SIZE(spi_device_table); diff --git a/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_CTR/board.h b/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_CTR/board.h new file mode 100644 index 0000000000..6c6499bca1 --- /dev/null +++ b/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_CTR/board.h @@ -0,0 +1,208 @@ +#ifndef _BOARD_STM32V1F4_H_ +#define _BOARD_STM32V1F4_H_ + + +/** + * @brief Configuration of the Cortex-M4 Processor and Core Peripherals + */ +#define __CM4_REV 0x0001 /*!< Core revision r0p1 */ +#define __MPU_PRESENT 1 /*!< STM32F4XX provides an MPU */ +#define __NVIC_PRIO_BITS 4 /*!< STM32F4XX uses 4 Bits for the Priority Levels */ +#define __Vendor_SysTickConfig 0 /*!< Set to 1 if different SysTick Config is used */ +#define __FPU_PRESENT 1 /*!< FPU present */ + +#define HSE_VALUE (8000000) + +#define CYCLES_PER_MICROSECOND (SystemCoreClock / 1000000) +#define SYSTICK_RELOAD_VAL (CYCLES_PER_MICROSECOND*1000-1) + +#undef STM32_PCLK1 +#undef STM32_PCLK2 +#define STM32_PCLK1 (CYCLES_PER_MICROSECOND*1000000/4) +#define STM32_PCLK2 (CYCLES_PER_MICROSECOND*1000000/2) + +#define BOARD_BUTTON_PIN 254 + +#ifndef LOW +# define LOW 0 +#endif +#ifndef HIGH +# define HIGH 1 +#endif + +#define BOARD_BUZZER_PIN PC13 +#define HAL_BUZZER_ON 0 +#define HAL_BUZZER_OFF 1 + +#define BOARD_NR_USARTS 4 + + +#define BOARD_USART1_TX_PIN PA10 +#define BOARD_USART1_RX_PIN PA9 + +//#define BOARD_USART2_TX_PIN PA2 +//#define BOARD_USART2_RX_PIN PA3 - used for PPM + +#define BOARD_USART3_TX_PIN PC11 +#define BOARD_USART3_RX_PIN PC10 + +#define BOARD_USART4_TX_PIN PA0 +#define BOARD_USART4_RX_PIN PA1 + +#define BOARD_USART5_RX_PIN PD2 +#define BOARD_USART5_TX_PIN PC12 + +//#define BOARD_USART6_TX_PIN 255 +//#define BOARD_USART6_RX_PIN 255 + +#define BOARD_HAS_UART3 +#define BOARD_DSM_USART _UART5 + +// no inverter +//#define BOARD_SBUS_INVERTER +//#define BOARD_SBUS_UART 1 // can use some UART as hardware inverted input + + +#define BOARD_NR_SPI 3 +#define BOARD_SPI1_SCK_PIN PA5 +#define BOARD_SPI1_MISO_PIN PA6 +#define BOARD_SPI1_MOSI_PIN PA7 +#define BOARD_SPI2_SCK_PIN PB13 +#define BOARD_SPI2_MISO_PIN PB14 +#define BOARD_SPI2_MOSI_PIN PB15 +#define BOARD_SPI3_SCK_PIN PB3 +#define BOARD_SPI3_MISO_PIN PB4 +#define BOARD_SPI3_MOSI_PIN PB5 + + +#define BOARD_MPU6000_CS_PIN PC2 +#define BOARD_MPU6000_DRDY_PIN PC3 + +#define BOARD_USB_SENSE PB12 + +#define I2C1_SDA PB7 +#define I2C1_SCL PB6 + +// bus 2 (soft) pins +//#define BOARD_SOFT_SCL 14 +//#define BOARD_SOFT_SDA 15 + +// SoftSerial pins +//#define BOARD_SOFTSERIAL_TX 14 +//#define BOARD_SOFTSERIAL_RX 15 + + +#define BOARD_BLUE_LED_PIN PB9 +#define BOARD_GREEN_LED_PIN PA14 + +#define HAL_GPIO_A_LED_PIN BOARD_BLUE_LED_PIN +#define HAL_GPIO_B_LED_PIN BOARD_GREEN_LED_PIN + +# define BOARD_LED_ON LOW +# define BOARD_LED_OFF HIGH +# define HAL_GPIO_LED_ON LOW +# define HAL_GPIO_LED_OFF HIGH + + +#define BOARD_NR_GPIO_PINS 109 + +//#define BOARD_I2C_BUS_INT 1 // hardware internal I2C +#define BOARD_I2C_BUS_EXT 0 // external I2C +#define BOARD_I2C_BUS_SLOW 0 // slow down bus with this number + +#define BOARD_BARO_DEFAULT HAL_BARO_BMP280_I2C +#define HAL_BARO_BMP280_BUS BOARD_I2C_BUS_EXT +#define HAL_BARO_BMP280_I2C_ADDR (0x76) + +#define BOARD_COMPASS_DEFAULT HAL_COMPASS_HMC5843 +#define BOARD_COMPASS_HMC5843_I2C_ADDR 0x1E +#define BOARD_COMPASS_HMC5843_ROTATION ROTATION_NONE + +#define HAL_COMPASS_HMC5843_I2C_BUS BOARD_I2C_BUS_EXT +#define HAL_COMPASS_HMC5843_I2C_ADDR BOARD_COMPASS_HMC5843_I2C_ADDR +#define HAL_COMPASS_HMC5843_ROTATION BOARD_COMPASS_HMC5843_ROTATION + +#define BOARD_INS_DEFAULT HAL_INS_MPU60XX_SPI +#define BOARD_INS_ROTATION ROTATION_YAW_180 +#define BOARD_INS_MPU60x0_NAME "mpu6000" + +#define BOARD_STORAGE_SIZE 8192 // 4096 // EEPROM size + +#define BOARD_SDCARD_NAME "sdcard" +#define BOARD_SDCARD_CS_PIN PC1 +//#define BOARD_SDCARD_DET_PIN 38 // PB7 + +#define BOARD_HAS_SDIO +#define HAL_BOARD_LOG_DIRECTORY "0:/APM/LOGS" +#define HAL_BOARD_TERRAIN_DIRECTORY "0:/APM/TERRAIN" +//#define HAL_PARAM_DEFAULTS_PATH "0:/APM/defaults.parm" +#define USB_MASSSTORAGE + +#define BOARD_OSD_NAME "osd" +#define BOARD_OSD_CS_PIN PB10 +//#define BOARD_OSD_VSYNC_PIN 9 +//#define BOARD_OSD_RESET_PIN 6 + + +/* +#define DATAFLASH_CS_PIN PC0 +#define BOARD_DATAFLASH_NAME "dataflash" +#define BOARD_DATAFLASH_PAGES 0x10000 +#define BOARD_DATAFLASH_ERASE_SIZE (4096)// in bytes +*/ + +#define BOARD_OWN_NAME "MatekF4_CTR" + +# define BOARD_PUSHBUTTON_PIN 254 // no button +# define BOARD_USB_MUX_PIN -1 // no mux +# define BOARD_BATTERY_VOLT_PIN PC5 // Battery voltage +# define BOARD_BATTERY_CURR_PIN PC4 // Battery current +# define BOARD_SONAR_SOURCE_ANALOG_PIN PB1 // rssi PB1 + +#define BOARD_USB_DMINUS 108 + + +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#define BOARD_UARTS_LAYOUT 6 + +#define SERVO_PIN_1 12 // PC6 S1 +#define SERVO_PIN_2 13 // PC7 S2 +#define SERVO_PIN_3 14 // PC8 S3 +#define SERVO_PIN_4 15 // PC9 S4 +#define SERVO_PIN_5 103 // PA15 S5 +#define SERVO_PIN_6 22 // PA8 S6 + +#define MOTOR_LAYOUT_DEFAULT 3 // Cleanflight + +#define HAL_CONSOLE USB_Driver // console on USB +#define HAL_CONSOLE_PORT 0 + +/* + + // @Param: USB_STORAGE + // @DisplayName: allows access to SD card at next reboot + // @Description: Allows to read/write internal SD card via USB mass-storage protocol. Auto-reset. + // @Values: 0:normal, 1:work as USB flash drive + // @User: Advanced + AP_GROUPINFO("USB_STORAGE", 8, AP_Param_Helper, _usb_storage, 0), \ + + // @Param: SD_REFORMAT + // @DisplayName: Allows to re-format SD card in case of errors in FS + // @Description: Any FS errors that cause failure of logging will be corrected by SD card formatting + // @Values: 0: not allow, 1:allow + // @User: Advanced + AP_GROUPINFO("SD_REFORMAT", 7, AP_Param_Helper, _sd_format, 0), +*/ + +#define BOARD_HAL_VARINFO \ + AP_GROUPINFO("USB_STORAGE", 30, AP_Param_Helper, _usb_storage, 0), \ + AP_GROUPINFO("SD_REFORMAT", 31, AP_Param_Helper, _sd_format, 0), + +// parameters +#define BOARD_HAL_PARAMS \ + AP_Int8 _usb_storage; \ + AP_Int8 _sd_format; +#endif + + diff --git a/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_OSD/ld/flash-10000.ld b/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_CTR/ld/flash-10000.ld similarity index 100% rename from libraries/AP_HAL_F4Light/boards/f4light_MatekF405_OSD/ld/flash-10000.ld rename to libraries/AP_HAL_F4Light/boards/f4light_MatekF405_CTR/ld/flash-10000.ld diff --git a/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_OSD/ld/flash.ld b/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_CTR/ld/flash.ld similarity index 100% rename from libraries/AP_HAL_F4Light/boards/f4light_MatekF405_OSD/ld/flash.ld rename to libraries/AP_HAL_F4Light/boards/f4light_MatekF405_CTR/ld/flash.ld diff --git a/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_OSD/ld/flash_8000000.ld b/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_CTR/ld/flash_8000000.ld similarity index 100% rename from libraries/AP_HAL_F4Light/boards/f4light_MatekF405_OSD/ld/flash_8000000.ld rename to libraries/AP_HAL_F4Light/boards/f4light_MatekF405_CTR/ld/flash_8000000.ld diff --git a/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_OSD/rules.mk b/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_CTR/rules.mk similarity index 100% rename from libraries/AP_HAL_F4Light/boards/f4light_MatekF405_OSD/rules.mk rename to libraries/AP_HAL_F4Light/boards/f4light_MatekF405_CTR/rules.mk diff --git a/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_OSD/stm32f4xx_conf.h b/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_CTR/stm32f4xx_conf.h similarity index 100% rename from libraries/AP_HAL_F4Light/boards/f4light_MatekF405_OSD/stm32f4xx_conf.h rename to libraries/AP_HAL_F4Light/boards/f4light_MatekF405_CTR/stm32f4xx_conf.h diff --git a/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_OSD/support/DEBUG-STLINK.sh b/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_CTR/support/DEBUG-STLINK.sh similarity index 100% rename from libraries/AP_HAL_F4Light/boards/f4light_MatekF405_OSD/support/DEBUG-STLINK.sh rename to libraries/AP_HAL_F4Light/boards/f4light_MatekF405_CTR/support/DEBUG-STLINK.sh diff --git a/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_OSD/support/UPLOAD-plane-STLINK.sh b/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_CTR/support/DOWNLOAD-STLINK.sh similarity index 56% rename from libraries/AP_HAL_F4Light/boards/f4light_MatekF405_OSD/support/UPLOAD-plane-STLINK.sh rename to libraries/AP_HAL_F4Light/boards/f4light_MatekF405_CTR/support/DOWNLOAD-STLINK.sh index de739a79c9..08d8e8f15b 100755 --- a/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_OSD/support/UPLOAD-plane-STLINK.sh +++ b/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_CTR/support/DOWNLOAD-STLINK.sh @@ -4,6 +4,6 @@ #/usr/local/stlink/st-flash --reset write /tmp/ArduCopter.build/f4light_Revolution.bin 0x08010000 #bare metal binary -/usr/local/stlink/st-flash --reset write ../../../../../ArduPlane/f4light_AirbotV2.bin 0x08000000 && /usr/local/stlink/st-util -m +/usr/local/stlink/st-flash --reset read readout.bin 0x08000000 0x100000 diff --git a/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_OSD/support/Rebuild.sh b/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_CTR/support/Rebuild.sh similarity index 59% rename from libraries/AP_HAL_F4Light/boards/f4light_MatekF405_OSD/support/Rebuild.sh rename to libraries/AP_HAL_F4Light/boards/f4light_MatekF405_CTR/support/Rebuild.sh index 61d85b0e52..c287b8967a 100755 --- a/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_OSD/support/Rebuild.sh +++ b/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_CTR/support/Rebuild.sh @@ -8,14 +8,13 @@ export PATH=/usr/local/bin:$PATH echo $ROOT -( # AirBotF4 board +( # MatekF405_CTR board cd $ROOT/ArduCopter make f4light-clean - make f4light VERBOSE=1 BOARD=f4light_AirbotV2 + make f4light VERBOSE=1 BOARD=f4light_MatekF405_CTR ) && ( cd $ROOT/ArduPlane make f4light-clean - make f4light VERBOSE=1 BOARD=f4light_AirbotV2 + make f4light VERBOSE=1 BOARD=f4light_MatekF405_CTR ) -# at 4e017bf5b3da4f2a9ffc2e1cc0a37b94edac2bdc diff --git a/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_CTR/support/UPLOAD-DFU.sh b/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_CTR/support/UPLOAD-DFU.sh new file mode 100755 index 0000000000..ebc73e3f4e --- /dev/null +++ b/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_CTR/support/UPLOAD-DFU.sh @@ -0,0 +1,7 @@ +#!/bin/sh + +#production binary for bootloader +dfu-util -a 0 --dfuse-address 0x08010000:unprotect:force -D ../../../../../ArduCopter/f4light_MatekF405_CTR.bin -R + + + diff --git a/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_OSD/support/UPLOAD-STLINK.sh b/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_CTR/support/UPLOAD-STLINK.sh similarity index 52% rename from libraries/AP_HAL_F4Light/boards/f4light_MatekF405_OSD/support/UPLOAD-STLINK.sh rename to libraries/AP_HAL_F4Light/boards/f4light_MatekF405_CTR/support/UPLOAD-STLINK.sh index 72fbf7f49f..32ee6f3d2e 100755 --- a/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_OSD/support/UPLOAD-STLINK.sh +++ b/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_CTR/support/UPLOAD-STLINK.sh @@ -1,9 +1,10 @@ #!/bin/sh -# production binary with bootloader +# production binary without bootloader #/usr/local/stlink/st-flash --reset write /tmp/ArduCopter.build/f4light_Revolution.bin 0x08010000 -#bare metal binary -/usr/local/stlink/st-flash --reset write ../../../../../ArduCopter/f4light_AirbotV2.bin 0x08000000 && /usr/local/stlink/st-util -m +#bare metal binary or binary with bootloader +/usr/local/stlink/st-flash --reset write ../../../../../ArduCopter/f4light_MatekF405_CTR.bin 0x08010000 && \ +/usr/local/stlink/st-util -m diff --git a/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_CTR/support/UPLOAD-plane-STLINK.sh b/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_CTR/support/UPLOAD-plane-STLINK.sh new file mode 100755 index 0000000000..4610a2f487 --- /dev/null +++ b/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_CTR/support/UPLOAD-plane-STLINK.sh @@ -0,0 +1,7 @@ +#!/bin/sh + + +/usr/local/stlink/st-flash --reset write ../../../../../ArduPlane/f4light_MatekF405_CTR.bin 0x08010000 && \ +/usr/local/stlink/st-util -m + + diff --git a/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_CTR/support/bl/UPLOAD-STLINK.sh b/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_CTR/support/bl/UPLOAD-STLINK.sh new file mode 100755 index 0000000000..36e1c8bd44 --- /dev/null +++ b/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_CTR/support/bl/UPLOAD-STLINK.sh @@ -0,0 +1,12 @@ +#!/bin/sh + +# production binary without bootloader +#/usr/local/stlink/st-flash --reset write /tmp/ArduCopter.build/f4light_Revolution.bin 0x08010000 + +#bare metal binary or binary with bootloader +/usr/local/stlink/st-flash --reset read eeprom.bin 0x08004000 0xc000 && \ +/usr/local/stlink/st-flash --reset write ../../../../../../ArduCopter/f4light_MatekF405_CTR_bl.bin 0x08000000 && \ +/usr/local/stlink/st-flash --reset write eeprom.bin 0x08004000 && \ +/usr/local/stlink/st-util -m + + diff --git a/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_CTR/support/bl/UPLOAD-plane-STLINK.sh b/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_CTR/support/bl/UPLOAD-plane-STLINK.sh new file mode 100755 index 0000000000..8c0833b790 --- /dev/null +++ b/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_CTR/support/bl/UPLOAD-plane-STLINK.sh @@ -0,0 +1,12 @@ +#!/bin/sh + +# production binary with bootloader +#/usr/local/stlink/st-flash --reset write /tmp/ArduCopter.build/f4light_Revolution.bin 0x08010000 + +#bare metal binary +/usr/local/stlink/st-flash --reset read eeprom.bin 0x08004000 0xc000 && \ +/usr/local/stlink/st-flash --reset write ../../../../../../ArduPlane/f4light_MatekF405_CTR_bl.bin 0x08000000 +/usr/local/stlink/st-flash --reset write eeprom.bin 0x08004000 +/usr/local/stlink/st-util -m + + diff --git a/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_OSD/system_stm32f4xx.c b/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_CTR/system_stm32f4xx.c similarity index 99% rename from libraries/AP_HAL_F4Light/boards/f4light_MatekF405_OSD/system_stm32f4xx.c rename to libraries/AP_HAL_F4Light/boards/f4light_MatekF405_CTR/system_stm32f4xx.c index 765ce94bda..788d671184 100644 --- a/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_OSD/system_stm32f4xx.c +++ b/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_CTR/system_stm32f4xx.c @@ -333,7 +333,7 @@ void SystemCoreClockUpdate(void) SystemCoreClock >>= tmp; } -extern void __error(uint32_t num, uint32_t pc, uint32_t lr); +extern void __error(uint32_t num, uint32_t pc, uint32_t lr, uint32_t flag); /** * @brief Configures the System clock source, PLL Multiplier and Divider factors, @@ -444,7 +444,7 @@ void SetSysClock(uint8_t oc) RCC->CR |= RCC_CR_PLLON | cr_flags; - // Wait till the main PLL is ready. Yes this is endless loop but this is a very early stage + /* Wait till the main PLL is ready */ while((RCC->CR & RCC_CR_PLLRDY) == 0) { } diff --git a/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_OSD/target-config.mk b/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_CTR/target-config.mk similarity index 96% rename from libraries/AP_HAL_F4Light/boards/f4light_MatekF405_OSD/target-config.mk rename to libraries/AP_HAL_F4Light/boards/f4light_MatekF405_CTR/target-config.mk index 4e1566f15d..ed28edbf11 100644 --- a/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_OSD/target-config.mk +++ b/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_CTR/target-config.mk @@ -7,7 +7,7 @@ SRAM_SIZE := 131072 BOARD_TYPE := 70 - BOARD_REV := 2 + BOARD_REV := 8 BOOTLOADER := revo405_bl # Memory target-specific configuration values diff --git a/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_OSD/1_read_me.md b/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_OSD/1_read_me.md deleted file mode 100644 index e9a3f90c15..0000000000 --- a/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_OSD/1_read_me.md +++ /dev/null @@ -1,2 +0,0 @@ - -port is not completed diff --git a/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_OSD/board.h b/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_OSD/board.h deleted file mode 100644 index df23f7c4cd..0000000000 --- a/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_OSD/board.h +++ /dev/null @@ -1,204 +0,0 @@ -#ifndef _BOARD_STM32V1F4_H_ -#define _BOARD_STM32V1F4_H_ - - -/** - * @brief Configuration of the Cortex-M4 Processor and Core Peripherals - */ -#define __CM4_REV 0x0001 /*!< Core revision r0p1 */ -#define __MPU_PRESENT 1 /*!< STM32F4XX provides an MPU */ -#define __NVIC_PRIO_BITS 4 /*!< STM32F4XX uses 4 Bits for the Priority Levels */ -#define __Vendor_SysTickConfig 0 /*!< Set to 1 if different SysTick Config is used */ -#define __FPU_PRESENT 1 /*!< FPU present */ - -#define HSE_VALUE (8000000) - -#define CYCLES_PER_MICROSECOND (SystemCoreClock / 1000000) -#define SYSTICK_RELOAD_VAL (CYCLES_PER_MICROSECOND*1000-1) - -#undef STM32_PCLK1 -#undef STM32_PCLK2 -#define STM32_PCLK1 (CYCLES_PER_MICROSECOND*1000000/4) -#define STM32_PCLK2 (CYCLES_PER_MICROSECOND*1000000/2) - -#define BOARD_BUTTON_PIN 254 - -#ifndef LOW -# define LOW 0 -#endif -#ifndef HIGH -# define HIGH 1 -#endif - -#define BOARD_BUZZER_PIN 19 - -#define BOARD_NR_USARTS 5 -#define BOARD_USART1_TX_PIN 23 -#define BOARD_USART1_RX_PIN 24 -#define BOARD_USART3_TX_PIN 16 -#define BOARD_USART3_RX_PIN 17 - -#define BOARD_USART2_RX_PIN 50 -#define BOARD_USART2_TX_PIN 49 - -#define BOARD_USART4_RX_PIN 48 -#define BOARD_USART4_TX_PIN 47 - -#define BOARD_USART5_RX_PIN 26 -#define BOARD_USART5_TX_PIN 18 -#define BOARD_USART6_TX_PIN 255 -#define BOARD_USART6_RX_PIN 255 - - -#define BOARD_DSM_USART (_USART2) - -#define BOARD_NR_SPI 3 -#define BOARD_SPI1_SCK_PIN 52 // PA5 -#define BOARD_SPI1_MISO_PIN 53 // PA6 -#define BOARD_SPI1_MOSI_PIN 54 // PA7 -#define BOARD_SPI2_SCK_PIN 3 // PB13 -#define BOARD_SPI2_MISO_PIN 4 // PB14 -#define BOARD_SPI2_MOSI_PIN 5 // PB15 -#define BOARD_SPI3_SCK_PIN 104 // PB3 -#define BOARD_SPI3_MISO_PIN 105 // PB4 -#define BOARD_SPI3_MOSI_PIN 36 // PB5 - - -#define BOARD_MPU6000_CS_PIN 8 // PC2 -#define BOARD_MPU6000_DRDY_PIN 9 // PC3 - - -#define BOARD_SBUS_INVERTER - -#define BOARD_USB_SENSE 2 // - - -// bus 2 (soft) pins -#define BOARD_SOFT_SCL 14 -#define BOARD_SOFT_SDA 15 - -// SoftSerial pins -//#define BOARD_SOFTSERIAL_TX 14 -//#define BOARD_SOFTSERIAL_RX 15 - - -# define BOARD_BLUE_LED_PIN 25 // PB9 -# define BOARD_GREEN_LED_PIN 107 // PA14 - -# define HAL_GPIO_A_LED_PIN BOARD_BLUE_LED_PIN -# define HAL_GPIO_B_LED_PIN BOARD_GREEN_LED_PIN - -# define BOARD_LED_ON LOW -# define BOARD_LED_OFF HIGH -# define HAL_LED_ON LOW -# define HAL_LED_OFF HIGH - - -#define BOARD_NR_GPIO_PINS 109 - -#define BOARD_I2C_BUS_INT 1 // hardware internal I2C -//#define BOARD_I2C_BUS_EXT 1 // external I2C -#define BOARD_I2C_BUS_SLOW 1 // slow down bus with this number - -#define BOARD_I2C1_DISABLE // lots of drivers tries to scan all buses, spoiling device setup - -#define BOARD_BARO_DEFAULT HAL_BARO_BMP280_SPI -#define HAL_BARO_BMP280_NAME "bmp280" -#define BOARD_BMP280_CS_PIN 104 - -#define BOARD_COMPASS_DEFAULT HAL_COMPASS_HMC5843 -#define BOARD_COMPASS_HMC5843_I2C_ADDR 0x1E -#define BOARD_COMPASS_HMC5843_ROTATION ROTATION_NONE - -#define HAL_COMPASS_HMC5843_I2C_BUS BOARD_I2C_BUS_INT -#define HAL_COMPASS_HMC5843_I2C_ADDR BOARD_COMPASS_HMC5843_I2C_ADDR -#define HAL_COMPASS_HMC5843_ROTATION BOARD_COMPASS_HMC5843_ROTATION - - -#define BOARD_INS_DEFAULT HAL_INS_MPU60XX_SPI -#define BOARD_INS_ROTATION ROTATION_YAW_270 -#define BOARD_INS_MPU60x0_NAME "mpu6000" - -#define BOARD_STORAGE_SIZE 8192 // 4096 // EEPROM size - - -#define BOARD_SDCARD_NAME "sdcard" -#define BOARD_SDCARD_CS_PIN 7 -//#define BOARD_SDCARD_DET_PIN 38 // PB7 - -#define BOARD_HAS_SDIO -#define HAL_BOARD_LOG_DIRECTORY "0:/APM/LOGS" -#define HAL_BOARD_TERRAIN_DIRECTORY "0:/APM/TERRAIN" -//#define HAL_PARAM_DEFAULTS_PATH "0:/APM/defaults.parm" -#define USB_MASSSTORAGE - -#define BOARD_OSD_NAME "osd" -#define BOARD_OSD_CS_PIN 0 -//#define BOARD_OSD_VSYNC_PIN 9 -//#define BOARD_OSD_RESET_PIN 6 - - -#define BOARD_OWN_NAME "MatekF4_OSD" - -# define BOARD_PUSHBUTTON_PIN 254 -# define BOARD_USB_MUX_PIN -1 -# define BOARD_BATTERY_VOLT_PIN 11 // Battery voltage on C5 -# define BOARD_BATTERY_CURR_PIN 10 // Battery current on C4 -# define BOARD_SONAR_SOURCE_ANALOG_PIN 45 // rssi - -#define BOARD_USB_DMINUS 108 - -#define BOARD_SBUS_UART 1 // can use some UART as hardware inverted input - -#define USE_SERIAL_4WAY_BLHELI_INTERFACE - -#define BOARD_UARTS_LAYOUT 6 - -// use soft I2C driver instead hardware -//#define BOARD_SOFT_I2C - -#define SERVO_PIN_1 12 // PC6 -#define SERVO_PIN_2 13 // PC7 -#define SERVO_PIN_3 14 // PC8 -#define SERVO_PIN_4 15 // PC9 -#define SERVO_PIN_5 103 // PA15 -#define SERVO_PIN_6 22 // PA8 - -#if 1 - #define HAL_CONSOLE USB_Driver // console on USB - #define HAL_CONSOLE_PORT 0 -#else - #define HAL_CONSOLE uart1Driver // console on radio - #define HAL_CONSOLE_PORT 1 -#endif - -/* - - - // @Param: USB_STORAGE - // @DisplayName: allows access to SD card at next reboot - // @Description: Allows to read/write internal SD card via USB mass-storage protocol. Auto-reset. - // @Values: 0:normal, 1:work as USB flash drive - // @User: Advanced - AP_GROUPINFO("USB_STORAGE", 8, AP_Param_Helper, _usb_storage, 0), \ - - // @Param: SD_REFORMAT - // @DisplayName: Allows to re-format SD card in case of errors in FS - // @Description: Any FS errors that cause failure of logging will be corrected by SD card formatting - // @Values: 0: not allow, 1:allow - // @User: Advanced - AP_GROUPINFO("SD_REFORMAT", 7, AP_Param_Helper, _sd_format, 0), - -*/ -#define BOARD_HAL_VARINFO \ - AP_GROUPINFO("USB_STORAGE", 30, AP_Param_Helper, _usb_storage, 0), \ - AP_GROUPINFO("SD_REFORMAT", 31, AP_Param_Helper, _sd_format, 0), - - -// parameters -#define BOARD_HAL_PARAMS \ - AP_Int8 _usb_storage; \ - AP_Int8 _sd_format; -#endif - - diff --git a/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_OSD/support/UPLOAD-DFU.sh b/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_OSD/support/UPLOAD-DFU.sh deleted file mode 100755 index 48b0d30b5d..0000000000 --- a/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_OSD/support/UPLOAD-DFU.sh +++ /dev/null @@ -1,12 +0,0 @@ -#!/bin/sh - -#production binary for bootloader -#dfu-util -a 0 --dfuse-address 0x08010000 -D /tmp/ArduCopter.build/f4light_AirbotV2.bin - -# bare metal binary - -#dfu-util -a 0 --dfuse-address 0x08000000:unprotect:force -D /tmp/ArduCopter.build/f4light_Revolution.bin -#dfu-util -a 0 --dfuse-address 0x08000000:leave -D ../../../../../ArduCopter/f4light_Revolution.bin -R - -dfu-util -a 0 --dfuse-address 0x08000000:unprotect:force -D ../../../../../ArduCopter/f4light_AirbotV2.bin -R - diff --git a/libraries/AP_HAL_F4Light/boards/f4light_MiniF4_OSD/board.h b/libraries/AP_HAL_F4Light/boards/f4light_MiniF4_OSD/board.h index e7d991db5b..e77a7d916c 100644 --- a/libraries/AP_HAL_F4Light/boards/f4light_MiniF4_OSD/board.h +++ b/libraries/AP_HAL_F4Light/boards/f4light_MiniF4_OSD/board.h @@ -76,6 +76,11 @@ #define BOARD_NR_GPIO_PINS 109 +#define I2C1_SDA PB9 +#define I2C1_SCL PB8 + +#define I2C2_SDA PB11 +#define I2C2_SCL PB10 #define BOARD_I2C_BUS_INT 1 // hardware internal I2C @@ -148,6 +153,7 @@ #define SERVO_PIN_5 48 // PA1 #define SERVO_PIN_6 22 // PA8 +#define MOTOR_LAYOUT_DEFAULT 0 //#define HAL_CONSOLE uart1Driver // console on radio #define HAL_CONSOLE USB_Driver // console on USB diff --git a/libraries/AP_HAL_F4Light/boards/f4light_Revolution/board.h b/libraries/AP_HAL_F4Light/boards/f4light_Revolution/board.h index dd38ddd640..443bc119d7 100644 --- a/libraries/AP_HAL_F4Light/boards/f4light_Revolution/board.h +++ b/libraries/AP_HAL_F4Light/boards/f4light_Revolution/board.h @@ -108,6 +108,12 @@ #define BOARD_NR_GPIO_PINS 109 +#define I2C1_SDA PB9 +#define I2C1_SCL PB8 + +#define I2C2_SDA PB11 +#define I2C2_SCL PB10 + #define BOARD_I2C_BUS_INT 0 // hardware I2C #define BOARD_I2C_BUS_EXT 2 // external soft I2C or flexiPort (by parameter) @@ -172,6 +178,7 @@ #define SERVO_PIN_5 48 // PA1 #define SERVO_PIN_6 47 // PA0 +#define MOTOR_LAYOUT_DEFAULT 0 #define USE_SERIAL_4WAY_BLHELI_INTERFACE diff --git a/libraries/AP_HAL_F4Light/boards/f4light_Revolution_EE128/board.h b/libraries/AP_HAL_F4Light/boards/f4light_Revolution_EE128/board.h index 35d8d5e923..1908679315 100644 --- a/libraries/AP_HAL_F4Light/boards/f4light_Revolution_EE128/board.h +++ b/libraries/AP_HAL_F4Light/boards/f4light_Revolution_EE128/board.h @@ -108,6 +108,12 @@ #define BOARD_NR_GPIO_PINS 109 +#define I2C1_SDA PB9 +#define I2C1_SCL PB8 + +#define I2C2_SDA PB11 +#define I2C2_SCL PB10 + #define BOARD_I2C_BUS_INT 0 // hardware I2C #define BOARD_I2C_BUS_EXT 2 // external soft I2C or flexiPort (by parameter) @@ -178,6 +184,7 @@ #define SERVO_PIN_5 48 // PA1 #define SERVO_PIN_6 47 // PA0 +#define MOTOR_LAYOUT_DEFAULT 0 #define USE_SERIAL_4WAY_BLHELI_INTERFACE diff --git a/libraries/AP_HAL_F4Light/boards/f4light_Revolution_SD/board.cpp b/libraries/AP_HAL_F4Light/boards/f4light_Revolution_SD/board.cpp index 56a9a2fa5c..5fe7c2ab90 100644 --- a/libraries/AP_HAL_F4Light/boards/f4light_Revolution_SD/board.cpp +++ b/libraries/AP_HAL_F4Light/boards/f4light_Revolution_SD/board.cpp @@ -158,7 +158,7 @@ extern const SPIDesc spi_device_table[] = { // different SPI tables per board // name device bus mode cs_pin speed_low speed_high dma priority assert_dly release_dly { BOARD_INS_MPU60x0_NAME, _SPI1, 1, SPI_MODE_0, BOARD_MPU6000_CS_PIN, SPI_1_125MHZ, SPI_9MHZ, SPI_TRANSFER_DMA, DMA_Priority_VeryHigh, 1, 5 }, // { BOARD_DATAFLASH_NAME, _SPI3, 3, SPI_MODE_3, 255 /* caller controls CS */, SPI_1_125MHZ, SPI_18MHZ, SPI_TRANSFER_DMA, DMA_Priority_Medium, 0, 1 }, // we can use dataflash as EEPROM - { BOARD_SDCARD_NAME, _SPI3, 2, SPI_MODE_3, 255, SPI_1_125MHZ, SPI_18MHZ, SPI_TRANSFER_DMA, DMA_Priority_Medium, 0, 1 }, + { BOARD_SDCARD_NAME, _SPI3, 3, SPI_MODE_3, 255, SPI_1_125MHZ, SPI_18MHZ, SPI_TRANSFER_DMA, DMA_Priority_Medium, 0, 1 }, }; extern const uint8_t F4Light_SPI_DEVICE_NUM_DEVICES = ARRAY_SIZE(spi_device_table); diff --git a/libraries/AP_HAL_F4Light/boards/f4light_Revolution_SD/board.h b/libraries/AP_HAL_F4Light/boards/f4light_Revolution_SD/board.h index 9b316f619f..85b63d51c5 100644 --- a/libraries/AP_HAL_F4Light/boards/f4light_Revolution_SD/board.h +++ b/libraries/AP_HAL_F4Light/boards/f4light_Revolution_SD/board.h @@ -100,6 +100,11 @@ #define BOARD_NR_GPIO_PINS 109 +#define I2C1_SDA PB9 +#define I2C1_SCL PB8 + +#define I2C2_SDA PB11 +#define I2C2_SCL PB10 #define BOARD_I2C_BUS_INT 0 // hardware I2C @@ -174,6 +179,7 @@ #define SERVO_PIN_5 48 // PA1 #define SERVO_PIN_6 47 // PA0 +#define MOTOR_LAYOUT_DEFAULT 0 #define USE_SERIAL_4WAY_BLHELI_INTERFACE diff --git a/libraries/AP_HAL_F4Light/boards/f4light_Revolution_SD/target-config.mk b/libraries/AP_HAL_F4Light/boards/f4light_Revolution_SD/target-config.mk index 9080b0a245..baf94cab67 100644 --- a/libraries/AP_HAL_F4Light/boards/f4light_Revolution_SD/target-config.mk +++ b/libraries/AP_HAL_F4Light/boards/f4light_Revolution_SD/target-config.mk @@ -7,7 +7,7 @@ SRAM_SIZE := 131072 BOARD_TYPE := 70 - BOARD_REV := 4 + BOARD_REV := 7 BOOTLOADER := revo405_bl # Memory target-specific configuration values diff --git a/libraries/AP_HAL_F4Light/boards/f4light_cl_racing/board.h b/libraries/AP_HAL_F4Light/boards/f4light_cl_racing/board.h index f1850418f5..ad7394a5bf 100644 --- a/libraries/AP_HAL_F4Light/boards/f4light_cl_racing/board.h +++ b/libraries/AP_HAL_F4Light/boards/f4light_cl_racing/board.h @@ -86,6 +86,13 @@ //TODO add #define BOARD_HAS_UART3 ? +#define I2C1_SDA PB9 +#define I2C1_SCL PB8 + +#define I2C2_SDA PB11 +#define I2C2_SCL PB10 + + //#define BOARD_I2C_BUS_INT 1 // hardware internal I2C #define BOARD_I2C_BUS_EXT 2 // external I2C #define BOARD_I2C_BUS_SLOW 2 // slow down bus with this number @@ -165,6 +172,8 @@ #define SERVO_PIN_5 105 // PB4 - buzzer //#define SERVO_PIN_6 22 // PA8 +#define MOTOR_LAYOUT_DEFAULT 3 // Cleanflight + #define HAL_CONSOLE USB_Driver // console on USB #define HAL_CONSOLE_PORT 0 diff --git a/libraries/AP_HAL_F4Light/hardware/hal/i2c.c b/libraries/AP_HAL_F4Light/hardware/hal/i2c.c index 6d409d8305..56dce015de 100644 --- a/libraries/AP_HAL_F4Light/hardware/hal/i2c.c +++ b/libraries/AP_HAL_F4Light/hardware/hal/i2c.c @@ -12,17 +12,16 @@ based on: datasheet #include "systick.h" #include "stm32f4xx_i2c.h" #include "stm32f4xx_dma.h" +#include - +#if defined(I2C1_SDA) && defined(I2C1_SCL) static i2c_state i2c1_state IN_CCM; -static i2c_state i2c2_state IN_CCM; static const i2c_dev i2c_dev1 = { .I2Cx = I2C1, - .gpio_port = &gpiob, - .sda_pin = 9, - .scl_pin = 8, + .sda_pin = I2C1_SDA, + .scl_pin = I2C1_SCL, // 101 PB8 .clk = RCC_APB1Periph_I2C1, .gpio_af = GPIO_AF_I2C1, .ev_nvic_line = I2C1_EV_IRQn, @@ -32,13 +31,15 @@ static const i2c_dev i2c_dev1 = { }; /** I2C1 device */ const i2c_dev* const _I2C1 = &i2c_dev1; +#endif +#if defined(I2C2_SDA) && defined(I2C2_SCL) +static i2c_state i2c2_state IN_CCM; static const i2c_dev i2c_dev2 = { .I2Cx = I2C2, - .gpio_port = &gpiob, - .sda_pin = 11, - .scl_pin = 10, + .sda_pin = I2C2_SDA, + .scl_pin = I2C2_SCL, .clk = RCC_APB1Periph_I2C2, .gpio_af = GPIO_AF_I2C2, .ev_nvic_line = I2C2_EV_IRQn, @@ -49,6 +50,25 @@ static const i2c_dev i2c_dev2 = { /** I2C2 device */ const i2c_dev* const _I2C2 = &i2c_dev2; +#endif + +#if defined(I2C3_SDA) && defined(I2C3_SCL) +static i2c_state i2c3_state IN_CCM; + +static const i2c_dev i2c_dev3 = { + .I2Cx = I2C3, + .sda_pin = I2C3_SDA, + .scl_pin = I2C3_SCL, + .clk = RCC_APB1Periph_I2C3, + .gpio_af = GPIO_AF_I2C3, + .ev_nvic_line = I2C3_EV_IRQn, + .er_nvic_line = I2C3_ER_IRQn, + .state = &i2c3_state, +}; + +/** I2C3 device */ +const i2c_dev* const _I2C3 = &i2c_dev3; +#endif typedef enum {TX = 0, RX = 1, TXREG = 2} I2C_Dir; @@ -78,13 +98,21 @@ void i2c_lowLevel_deinit(const i2c_dev *dev){ GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL; GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz; // low speed to prevent glitches - /*!< Configure I2C pins: SCL */ - GPIO_InitStructure.GPIO_Pin = BIT(dev->scl_pin); - GPIO_Init(dev->gpio_port->GPIOx, &GPIO_InitStructure); + { + const stm32_pin_info *p = &PIN_MAP[dev->scl_pin]; - /*!< Configure I2C pins: SDA */ - GPIO_InitStructure.GPIO_Pin = BIT(dev->sda_pin); - GPIO_Init(dev->gpio_port->GPIOx, &GPIO_InitStructure); + /*!< Configure I2C pins: SCL */ + GPIO_InitStructure.GPIO_Pin = BIT(p->gpio_bit); + GPIO_Init(p->gpio_device->GPIOx, &GPIO_InitStructure); + } + + { + const stm32_pin_info *p = &PIN_MAP[dev->sda_pin]; + + /*!< Configure I2C pins: SDA */ + GPIO_InitStructure.GPIO_Pin = BIT(p->gpio_bit); + GPIO_Init(p->gpio_device->GPIOx, &GPIO_InitStructure); + } } /** @@ -102,9 +130,6 @@ static inline void i2c_lowLevel_init(const i2c_dev *dev) { RCC_APB1PeriphResetCmd(dev->clk, ENABLE); RCC_APB1PeriphResetCmd(dev->clk, DISABLE); - /* Enable the GPIOs for the SCL/SDA Pins */ - RCC_AHB1PeriphClockCmd(dev->gpio_port->clk, ENABLE); - memset(dev->state,0,sizeof(i2c_state)); // common configuration @@ -114,17 +139,28 @@ static inline void i2c_lowLevel_init(const i2c_dev *dev) { GPIO_InitStructure.GPIO_OType = GPIO_OType_OD; GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP; - /* Configure SCL */ - GPIO_InitStructure.GPIO_Pin = BIT(dev->scl_pin); - GPIO_Init(dev->gpio_port->GPIOx, &GPIO_InitStructure); + { /* Configure SCL */ + const stm32_pin_info *p = &PIN_MAP[dev->scl_pin]; - /* Configure SDA */ - GPIO_InitStructure.GPIO_Pin = BIT(dev->sda_pin); - GPIO_Init(dev->gpio_port->GPIOx, &GPIO_InitStructure); + /* Enable the GPIOs for the SCL/SDA Pins */ + RCC_AHB1PeriphClockCmd(p->gpio_device->clk, ENABLE); - /* Connect GPIO pins to peripheral, SCL must be first! */ - gpio_set_af_mode(dev->gpio_port, dev->scl_pin, dev->gpio_af); - gpio_set_af_mode(dev->gpio_port, dev->sda_pin, dev->gpio_af); + GPIO_InitStructure.GPIO_Pin = BIT(p->gpio_bit); + GPIO_Init(p->gpio_device->GPIOx, &GPIO_InitStructure); + /* Connect GPIO pins to peripheral, SCL must be first! */ + gpio_set_af_mode(p->gpio_device, p->gpio_bit, dev->gpio_af); + } + + { /* Configure SDA */ + const stm32_pin_info *p = &PIN_MAP[dev->sda_pin]; + + /* Enable the GPIOs for the SCL/SDA Pins */ + RCC_AHB1PeriphClockCmd(p->gpio_device->clk, ENABLE); + + GPIO_InitStructure.GPIO_Pin = BIT(p->gpio_bit); + GPIO_Init(p->gpio_device->GPIOx, &GPIO_InitStructure); + gpio_set_af_mode(p->gpio_device, p->gpio_bit, dev->gpio_af); + } } void i2c_init(const i2c_dev *dev, uint16_t address, uint32_t speed) @@ -176,7 +212,10 @@ void I2C1_EV_IRQHandler(); // to avoid warnings void I2C1_ER_IRQHandler(); void I2C2_EV_IRQHandler(); void I2C2_ER_IRQHandler(); +void I2C3_EV_IRQHandler(); +void I2C3_ER_IRQHandler(); +#if defined(I2C1_SDA) && defined(I2C1_SCL) void I2C1_EV_IRQHandler(){ // I2C1 Event ev_handler(_I2C1, false); } @@ -184,7 +223,9 @@ void I2C1_EV_IRQHandler(){ // I2C1 Event void I2C1_ER_IRQHandler(){ // I2C1 Error ev_handler(_I2C1, true); } +#endif +#if defined(I2C2_SDA) && defined(I2C2_SCL) void I2C2_EV_IRQHandler(){ // I2C2 Event ev_handler(_I2C2, false); } @@ -192,14 +233,26 @@ void I2C2_EV_IRQHandler(){ // I2C2 Event void I2C2_ER_IRQHandler(){ // I2C2 Error ev_handler(_I2C2, true); } +#endif +#if defined(I2C3_SDA) && defined(I2C3_SCL) +void I2C3_EV_IRQHandler(){ // I2C2 Event + ev_handler(_I2C3, false); +} +void I2C3_ER_IRQHandler(){ // I2C2 Error + ev_handler(_I2C3, true); +} +#endif void i2c_master_release_bus(const i2c_dev *dev) { - gpio_write_bit(dev->gpio_port, dev->scl_pin, 1); - gpio_write_bit(dev->gpio_port, dev->sda_pin, 1); - gpio_set_mode(dev->gpio_port, dev->scl_pin, GPIO_OUTPUT_OD_PU); - gpio_set_mode(dev->gpio_port, dev->sda_pin, GPIO_OUTPUT_OD_PU); + const stm32_pin_info *p_sda = &PIN_MAP[dev->sda_pin]; + const stm32_pin_info *p_scl = &PIN_MAP[dev->scl_pin]; + + gpio_write_bit(p_scl->gpio_device, p_scl->gpio_bit, 1); + gpio_write_bit(p_sda->gpio_device, p_sda->gpio_bit, 1); + gpio_set_mode(p_scl->gpio_device, p_scl->gpio_bit, GPIO_OUTPUT_OD_PU); + gpio_set_mode(p_sda->gpio_device, p_sda->gpio_bit, GPIO_OUTPUT_OD_PU); } @@ -222,6 +275,9 @@ bool i2c_bus_reset(const i2c_dev *dev) { uint32_t t=systick_uptime(); + const stm32_pin_info *p_sda = &PIN_MAP[dev->sda_pin]; + const stm32_pin_info *p_scl = &PIN_MAP[dev->scl_pin]; + /* * Make sure the bus is free by clocking it until any slaves release the * bus. @@ -229,43 +285,43 @@ bool i2c_bus_reset(const i2c_dev *dev) { again: /* Wait for any clock stretching to finish */ - while (!gpio_read_bit(dev->gpio_port, dev->scl_pin)) {// device can output 1 so check clock first + while (!gpio_read_bit(p_scl->gpio_device, p_scl->gpio_bit)) {// device can output 1 so check clock first if(systick_uptime()-t > MAX_I2C_TIME) return false; hal_yield(10); } delay_10us(); // 50kHz - while (!gpio_read_bit(dev->gpio_port, dev->sda_pin)) { + while (!gpio_read_bit(p_sda->gpio_device, p_sda->gpio_bit)) { /* Wait for any clock stretching to finish */ - while (!gpio_read_bit(dev->gpio_port, dev->scl_pin)){ + while (!gpio_read_bit(p_scl->gpio_device, p_scl->gpio_bit)){ if(systick_uptime()-t > MAX_I2C_TIME) return false; hal_yield(10); } delay_10us(); // 50kHz /* Pull low */ - gpio_write_bit(dev->gpio_port, dev->scl_pin, 0); + gpio_write_bit(p_scl->gpio_device, p_scl->gpio_bit, 0); delay_10us(); /* Release high again */ - gpio_write_bit(dev->gpio_port, dev->scl_pin, 1); + gpio_write_bit(p_scl->gpio_device, p_scl->gpio_bit, 1); delay_10us(); } /* Generate start then stop condition */ - gpio_write_bit(dev->gpio_port, dev->sda_pin, 0); + gpio_write_bit(p_sda->gpio_device, p_sda->gpio_bit, 0); delay_10us(); - gpio_write_bit(dev->gpio_port, dev->scl_pin, 0); + gpio_write_bit(p_scl->gpio_device, p_scl->gpio_bit, 0); delay_10us(); - gpio_write_bit(dev->gpio_port, dev->scl_pin, 1); + gpio_write_bit(p_scl->gpio_device, p_scl->gpio_bit, 1); delay_10us(); - gpio_write_bit(dev->gpio_port, dev->sda_pin, 1); + gpio_write_bit(p_sda->gpio_device, p_sda->gpio_bit, 1); uint32_t rtime = stopwatch_getticks(); uint32_t dt = us_ticks * 50; // 50uS while ((stopwatch_getticks() - rtime) < dt) { - if (!gpio_read_bit(dev->gpio_port, dev->scl_pin)) goto again; // any SCL activity after STOP + if (!gpio_read_bit(p_scl->gpio_device, p_scl->gpio_bit)) goto again; // any SCL activity after STOP } // we was generating signals on I2C bus, but BUSY flag senses it even when hardware is off diff --git a/libraries/AP_HAL_F4Light/hardware/hal/i2c.h b/libraries/AP_HAL_F4Light/hardware/hal/i2c.h index 12f8bc2baa..779371bf1e 100644 --- a/libraries/AP_HAL_F4Light/hardware/hal/i2c.h +++ b/libraries/AP_HAL_F4Light/hardware/hal/i2c.h @@ -98,7 +98,6 @@ extern uint32_t i2c_bit_time; */ typedef struct i2c_dev { I2C_TypeDef* I2Cx; - const gpio_dev *gpio_port; uint8_t sda_pin; uint8_t scl_pin; uint32_t clk; @@ -158,6 +157,7 @@ uint32_t i2c_get_operation_time(uint8_t *psr1); extern const i2c_dev* const _I2C1; extern const i2c_dev* const _I2C2; +extern const i2c_dev* const _I2C3; #ifdef __cplusplus } diff --git a/libraries/AP_HAL_F4Light/hardware/hal/timer.c b/libraries/AP_HAL_F4Light/hardware/hal/timer.c index 4ee60aeb64..8b7d49d09b 100644 --- a/libraries/AP_HAL_F4Light/hardware/hal/timer.c +++ b/libraries/AP_HAL_F4Light/hardware/hal/timer.c @@ -444,7 +444,7 @@ void timer_set_mode(const timer_dev *dev, timer_Channel channel, timer_mode mode /* TODO decide about the basic timers */ assert_param(dev->type != TIMER_BASIC); - if (dev->type == TIMER_BASIC) + if (!dev || dev->type == TIMER_BASIC) return; switch (mode) { diff --git a/libraries/AP_HAL_F4Light/hardware/hal/usart.c b/libraries/AP_HAL_F4Light/hardware/hal/usart.c index eda49b7cca..d39986d5bf 100644 --- a/libraries/AP_HAL_F4Light/hardware/hal/usart.c +++ b/libraries/AP_HAL_F4Light/hardware/hal/usart.c @@ -34,7 +34,6 @@ static const usart_dev usart1 = { const usart_dev * const _USART1 = &usart1; #if defined(BOARD_USART2_RX_PIN) && defined(BOARD_USART2_RX_PIN) - static ring_buffer usart2_txrb IN_CCM; static ring_buffer usart2_rxrb IN_CCM; static usart_state u2state IN_CCM; @@ -95,14 +94,14 @@ const usart_dev * const _UART4 = &uart4; #endif #if defined(BOARD_USART5_RX_PIN) && defined(BOARD_USART5_TX_PIN) -//static ring_buffer uart5_txrb IN_CCM; - RX-only UART +static ring_buffer uart5_txrb IN_CCM; static ring_buffer uart5_rxrb IN_CCM; static usart_state u5state IN_CCM; static const usart_dev uart5 = { .USARTx = UART5, .clk = RCC_APB1Periph_UART5, - .txrb = NULL, // RX-only + .txrb = &uart5_txrb, .rxrb = &uart5_rxrb, .state = &u5state, .irq = UART5_IRQn, @@ -114,6 +113,7 @@ static const usart_dev uart5 = { const usart_dev * const _UART5 = &uart5; #endif +#if defined(BOARD_USART6_RX_PIN) && defined(BOARD_USART6_TX_PIN) static ring_buffer usart6_txrb IN_CCM; static ring_buffer usart6_rxrb IN_CCM; static usart_state u6state IN_CCM; @@ -131,11 +131,12 @@ static const usart_dev usart6 = { }; /** UART6 device */ const usart_dev * const _USART6 = &usart6; +#endif const usart_dev * const UARTS[] = { NULL, &usart1, -#if defined(USART2_USED) +#if defined(BOARD_USART2_RX_PIN) && defined(BOARD_USART2_RX_PIN) &usart2, #else NULL, @@ -146,28 +147,35 @@ const usart_dev * const UARTS[] = { #else NULL, #endif -#if defined(BOARD_USART5_RX_PIN) +#if defined(BOARD_USART5_RX_PIN) && defined(BOARD_USART5_TX_PIN) &uart5, #else NULL, #endif +#if defined(BOARD_USART6_RX_PIN) && defined(BOARD_USART6_TX_PIN) &usart6, +#else + NULL, +#endif + }; void usart_foreach(void (*fn)(const usart_dev*)) { fn(_USART1); -#if defined(USART2_USED) +#if defined(BOARD_USART2_RX_PIN) && defined(BOARD_USART2_RX_PIN) fn(_USART2); #endif fn(_USART3); -#if defined( BOARD_USART4_RX_PIN) && defined( BOARD_USART4_TX_PIN) +#if defined(BOARD_USART4_RX_PIN) && defined(BOARD_USART4_TX_PIN) fn(_UART4); #endif -#if defined( BOARD_USART5_RX_PIN) +#if defined(BOARD_USART5_RX_PIN) && defined(BOARD_USART5_TX_PIN) fn(_UART5); #endif +#if defined(BOARD_USART6_RX_PIN) && defined(BOARD_USART6_TX_PIN) fn(_USART6); +#endif } extern uint32_t us_ticks; @@ -357,7 +365,7 @@ void USART1_IRQHandler(void) usart_tx_irq(_USART1); } -#if defined(USART2_USED) +#if defined(BOARD_USART2_RX_PIN) && defined(BOARD_USART2_RX_PIN) void USART2_IRQHandler(void) { usart_rx_irq(_USART2); @@ -379,7 +387,7 @@ void UART4_IRQHandler(void) } #endif -#if defined( BOARD_USART5_RX_PIN) +#if defined( BOARD_USART5_RX_PIN) && defined( BOARD_USART5_TX_PIN) void UART5_IRQHandler(void) { usart_rx_irq(_UART5); @@ -387,9 +395,10 @@ void UART5_IRQHandler(void) } #endif +#if defined( BOARD_USART6_RX_PIN) && defined( BOARD_USART6_TX_PIN) void USART6_IRQHandler(void) { usart_rx_irq(_USART6); usart_tx_irq(_USART6); } - +#endif diff --git a/libraries/AP_HAL_F4Light/hardware/hal/usart.h b/libraries/AP_HAL_F4Light/hardware/hal/usart.h index 9f410576a4..044adac77c 100644 --- a/libraries/AP_HAL_F4Light/hardware/hal/usart.h +++ b/libraries/AP_HAL_F4Light/hardware/hal/usart.h @@ -57,11 +57,6 @@ extern const usart_dev * const _UART4; extern const usart_dev * const _UART5; extern const usart_dev * const _USART6; -//#define USART2_USED - - - - #define USART_F_RXNE 0x20 #define USART_F_TXE 0x80 #define USART_F_ORE 0x8 diff --git a/libraries/AP_HAL_F4Light/params.h b/libraries/AP_HAL_F4Light/params.h index 562f8b4505..52696e1f7a 100644 --- a/libraries/AP_HAL_F4Light/params.h +++ b/libraries/AP_HAL_F4Light/params.h @@ -75,7 +75,7 @@ // common parameters for all boards #define F4LIGHT_HAL_VARINFO \ - AP_GROUPINFO("MOTOR_LAYOUT", 1, AP_Param_Helper, _motor_layout, 0), \ + AP_GROUPINFO("MOTOR_LAYOUT", 1, AP_Param_Helper, _motor_layout, MOTOR_LAYOUT_DEFAULT), \ AP_GROUPINFO("SOFTSERIAL", 2, AP_Param_Helper, _use_softserial, 0), \ AP_GROUPINFO("UART_SBUS", 3, AP_Param_Helper, _uart_sbus, 0), \ AP_GROUPINFO("SERVO_MASK", 4, AP_Param_Helper, _servo_mask, 0), \ diff --git a/libraries/AP_HAL_F4Light/support/MMM.sh b/libraries/AP_HAL_F4Light/support/MMM.sh index adb59b550d..17fdb36ab3 100755 --- a/libraries/AP_HAL_F4Light/support/MMM.sh +++ b/libraries/AP_HAL_F4Light/support/MMM.sh @@ -11,129 +11,55 @@ mkdir -p $ROOT/Release/Copter mkdir -p $ROOT/Release/Plane -( # RevoMini board +make_copter(){ + local BOARD=$1 + cd $ROOT/ArduCopter make f4light-clean - make f4light VERBOSE=1 BOARD=f4light_Revolution && ( + make f4light BOARD=$BOARD && ( - cp $ROOT/ArduCopter/f4light_Revolution.bin $ROOT/Release/Copter - cp $ROOT/ArduCopter/f4light_Revolution.hex $ROOT/Release/Copter - cp $ROOT/ArduCopter/f4light_Revolution.dfu $ROOT/Release/Copter - cp $ROOT/ArduCopter/f4light_Revolution_bl.bin $ROOT/Release/Copter - cp $ROOT/ArduCopter/f4light_Revolution_bl.dfu $ROOT/Release/Copter + cp $ROOT/ArduCopter/$BOARD.bin $ROOT/Release/Copter + cp $ROOT/ArduCopter/$BOARD.hex $ROOT/Release/Copter + cp $ROOT/ArduCopter/$BOARD.dfu $ROOT/Release/Copter + cp $ROOT/ArduCopter/${BOARD}_bl.bin $ROOT/Release/Copter + cp $ROOT/ArduCopter/${BOARD}_bl.dfu $ROOT/Release/Copter ) -) && ( - cd $ROOT/ArduPlane - make f4light-clean - make f4light VERBOSE=1 BOARD=f4light_Revolution && ( +} - cp $ROOT/ArduPlane/f4light_Revolution.bin $ROOT/Release/Plane - cp $ROOT/ArduPlane/f4light_Revolution.hex $ROOT/Release/Plane - cp $ROOT/ArduPlane/f4light_Revolution.dfu $ROOT/Release/Plane - cp $ROOT/ArduPlane/f4light_Revolution_bl.bin $ROOT/Release/Plane - cp $ROOT/ArduPlane/f4light_Revolution_bl.dfu $ROOT/Release/Plane - ) -) && ( # AirBotF4 board - cd $ROOT/ArduCopter - make f4light-clean - make f4light VERBOSE=1 BOARD=f4light_Airbot && ( - - cp $ROOT/ArduCopter/f4light_Airbot.bin $ROOT/Release/Copter - cp $ROOT/ArduCopter/f4light_Airbot.hex $ROOT/Release/Copter - cp $ROOT/ArduCopter/f4light_Airbot.dfu $ROOT/Release/Copter - cp $ROOT/ArduCopter/f4light_Airbot_bl.bin $ROOT/Release/Copter - cp $ROOT/ArduCopter/f4light_Airbot_bl.dfu $ROOT/Release/Copter - - make f4light-clean +make_plane(){ + local BOARD=$1 - ) -) && ( cd $ROOT/ArduPlane make f4light-clean - make f4light VERBOSE=1 BOARD=f4light_Airbot && ( - - cp $ROOT/ArduPlane/f4light_Airbot.bin $ROOT/Release/Plane - cp $ROOT/ArduPlane/f4light_Airbot.hex $ROOT/Release/Plane - cp $ROOT/ArduPlane/f4light_Airbot.dfu $ROOT/Release/Plane - cp $ROOT/ArduPlane/f4light_Airbot_bl.bin $ROOT/Release/Plane - cp $ROOT/ArduPlane/f4light_Airbot_bl.dfu $ROOT/Release/Plane - - make f4light-clean + make f4light VERBOSE=1 BOARD=$BOARD && ( + cp $ROOT/ArduPlane/$BOARD.bin $ROOT/Release/Plane + cp $ROOT/ArduPlane/$BOARD.hex $ROOT/Release/Plane + cp $ROOT/ArduPlane/$BOARD.dfu $ROOT/Release/Plane + cp $ROOT/ArduPlane/${BOARD}_bl.bin $ROOT/Release/Plane + cp $ROOT/ArduPlane/${BOARD}_bl.dfu $ROOT/Release/Plane ) -) && ( # Cl_Racing F4 board - cd $ROOT/ArduCopter - make f4light-clean - make f4light VERBOSE=1 BOARD=f4light_cl_racing && ( - - cp $ROOT/ArduCopter/f4light_cl_racing.bin $ROOT/Release/Copter - cp $ROOT/ArduCopter/f4light_cl_racing.hex $ROOT/Release/Copter - cp $ROOT/ArduCopter/f4light_cl_racing.dfu $ROOT/Release/Copter - cp $ROOT/ArduCopter/f4light_cl_racing_bl.bin $ROOT/Release/Copter - cp $ROOT/ArduCopter/f4light_cl_racing_bl.dfu $ROOT/Release/Copter - make f4light-clean - - ) -) && ( - cd $ROOT/ArduPlane - make f4light-clean - make f4light VERBOSE=1 BOARD=f4light_Airbot && ( +} - cp $ROOT/ArduPlane/f4light_cl_racing.bin $ROOT/Release/Plane - cp $ROOT/ArduPlane/f4light_cl_racing.hex $ROOT/Release/Plane - cp $ROOT/ArduPlane/f4light_cl_racing.dfu $ROOT/Release/Plane - cp $ROOT/ArduPlane/f4light_cl_racing_bl.bin $ROOT/Release/Plane - cp $ROOT/ArduPlane/f4light_cl_racing_bl.dfu $ROOT/Release/Plane - - ) +( # RevoMini board + make_copter "f4light_Revolution" && \ + make_plane "f4light_Revolution" ) && ( # AirBotF4 board - cd $ROOT/ArduCopter - make f4light-clean - make f4light VERBOSE=1 BOARD=f4light_AirbotV2 && ( - - cp $ROOT/ArduCopter/f4light_AirbotV2.bin $ROOT/Release/Copter - cp $ROOT/ArduCopter/f4light_AirbotV2.hex $ROOT/Release/Copter - cp $ROOT/ArduCopter/f4light_AirbotV2.dfu $ROOT/Release/Copter - cp $ROOT/ArduCopter/f4light_AirbotV2_bl.bin $ROOT/Release/Copter - cp $ROOT/ArduCopter/f4light_AirbotV2_bl.dfu $ROOT/Release/Copter - - - ) -) && ( - cd $ROOT/ArduPlane - make f4light-clean - make f4light VERBOSE=1 BOARD=f4light_AirbotV2 && ( - - cp $ROOT/ArduPlane/f4light_AirbotV2.bin $ROOT/Release/Plane - cp $ROOT/ArduPlane/f4light_AirbotV2.hex $ROOT/Release/Plane - cp $ROOT/ArduPlane/f4light_AirbotV2.dfu $ROOT/Release/Plane - cp $ROOT/ArduPlane/f4light_AirbotV2_bl.bin $ROOT/Release/Plane - cp $ROOT/ArduPlane/f4light_AirbotV2_bl.dfu $ROOT/Release/Plane - ) - + make_copter "f4light_Airbot" && \ + make_plane "f4light_Airbot" +) && ( # Cl_Racing F4 board + make_copter "f4light_cl_racing" && \ + make_plane "f4light_cl_racing" +) && ( # AirBotV2 board + make_copter "f4light_AirbotV2" && \ + make_plane "f4light_AirbotV2" ) && ( # RevoMini board with SD card - cd $ROOT/ArduCopter - make f4light-clean - make f4light VERBOSE=1 BOARD=f4light_Revolution_SD && ( - - cp $ROOT/ArduCopter/f4light_Revolution_SD.bin $ROOT/Release/Copter - cp $ROOT/ArduCopter/f4light_Revolution_SD.hex $ROOT/Release/Copter - cp $ROOT/ArduCopter/f4light_Revolution_SD.dfu $ROOT/Release/Copter - cp $ROOT/ArduCopter/f4light_Revolution_SD_bl.bin $ROOT/Release/Copter - cp $ROOT/ArduCopter/f4light_Revolution_SD_bl.dfu $ROOT/Release/Copter - ) -) && ( - cd $ROOT/ArduPlane - make f4light-clean - make f4light VERBOSE=1 BOARD=f4light_Revolution_SD && ( - - cp $ROOT/ArduPlane/f4light_Revolution_SD.bin $ROOT/Release/Plane - cp $ROOT/ArduPlane/f4light_Revolution_SD.hex $ROOT/Release/Plane - cp $ROOT/ArduPlane/f4light_Revolution_SD.dfu $ROOT/Release/Plane - cp $ROOT/ArduPlane/f4light_Revolution_SD_bl.bin $ROOT/Release/Plane - cp $ROOT/ArduPlane/f4light_Revolution_SD_bl.dfu $ROOT/Release/Plane - ) + make_copter "f4light_Revolution_SD" && \ + make_plane "f4light_Revolution_SD" +) && ( # MatekF405_CTR board + make_copter "f4light_MatekF405_CTR" && \ + make_plane "f4light_MatekF405_CTR" ) && ( cd $ROOT