diff --git a/src/main/drivers/max7456.c b/src/main/drivers/max7456.c old mode 100644 new mode 100755 index 82f3f29af..9fcf45e03 --- a/src/main/drivers/max7456.c +++ b/src/main/drivers/max7456.c @@ -296,7 +296,7 @@ void max7456_write_nvm(uint8_t char_address, uint8_t *font_data) { max7456_send(MAX7456ADD_CMM, WRITE_NVR); // wait until bit 5 in the status register returns to 0 (12ms) - while ((spiTransferByte(MAX7456_SPI_INSTANCE, MAX7456ADD_STAT) & STATUS_REG_NVR_BUSY) != 0); + while ((max7456_send(MAX7456ADD_STAT, 0) & STATUS_REG_NVR_BUSY) != 0x00); max7456_send(VM0_REG, video_signal_type | 0x0C); DISABLE_MAX7456; diff --git a/src/main/target/RACEBASE/README.md b/src/main/target/RACEBASE/README.md new file mode 100755 index 000000000..1a06de5f2 --- /dev/null +++ b/src/main/target/RACEBASE/README.md @@ -0,0 +1,25 @@ +##RACABASE FC + +Owner: Marcin Baliniak (marcin baliniak.pl) + +Available at: shop.rotoracer.com + +###Board information: + +- CPU - STM32F303CCT6 +- MPU-6000 - connected to SPI2 +- SPI Flash - connected to SPI2 +- MAX7456 - connected to SPI2 (NO DMA) +- Build in 5V BEC + LC filter - board can be powered from main battery +- Input voltage: 5V - 17.4V +- RC input: PPM, S.BUS (build in inverter) - Uart2, Spectrum-Uart3 +- Other connectors: RSSI, Current sensor, LED strip, Buzzer, Video IN/Out + LC filter +- Weight: 6 g +- Size: 36 mm x 36 mm x 5 mm + +###Photo +![Board photo](https://cdn.shoplo.com/0639/products/th1024/aaaw/838-rr_flight_controller_rotoracer_fc_rotoracer_racebase.jpg) + + +###Port description +![Port description](https://cdn.shoplo.com/0639/products/th1024/aaaw/844-racebase-render-en.png) diff --git a/src/main/target/RACEBASE/config.c b/src/main/target/RACEBASE/config.c new file mode 100755 index 000000000..0ad304995 --- /dev/null +++ b/src/main/target/RACEBASE/config.c @@ -0,0 +1,83 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#include + +#include + +#include "build_config.h" + +#include "blackbox/blackbox_io.h" + +#include "common/color.h" +#include "common/axis.h" +#include "common/filter.h" + +#include "drivers/sensor.h" +#include "drivers/accgyro.h" +#include "drivers/compass.h" +#include "drivers/system.h" +#include "drivers/timer.h" +#include "drivers/pwm_rx.h" +#include "drivers/serial.h" +#include "drivers/pwm_output.h" +#include "drivers/max7456.h" +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" + +#include "sensors/sensors.h" +#include "sensors/gyro.h" +#include "sensors/compass.h" +#include "sensors/acceleration.h" +#include "sensors/barometer.h" +#include "sensors/boardalignment.h" +#include "sensors/battery.h" + +#include "io/beeper.h" +#include "io/serial.h" +#include "io/gimbal.h" +#include "io/escservo.h" +#include "io/rc_controls.h" +#include "io/rc_curves.h" +#include "io/ledstrip.h" +#include "io/gps.h" +#include "io/osd.h" +#include "io/vtx.h" + +#include "rx/rx.h" + +#include "telemetry/telemetry.h" + +#include "flight/mixer.h" +#include "flight/pid.h" +#include "flight/imu.h" +#include "flight/failsafe.h" +#include "flight/altitudehold.h" +#include "flight/navigation.h" + +#include "config/runtime_config.h" +#include "config/config.h" + +#include "config/config_profile.h" +#include "config/config_master.h" + +// alternative defaults settings for COLIBRI RACE targets +void targetConfiguration(master_t *config) { + config->rxConfig.sbus_inversion = 0; + config->rxConfig.rssi_scale = 19; + config->rxConfig.serialrx_provider = SERIALRX_SBUS; +} diff --git a/src/main/target/RACEBASE/readme.txt b/src/main/target/RACEBASE/readme.txt new file mode 100755 index 000000000..a2507bcd3 --- /dev/null +++ b/src/main/target/RACEBASE/readme.txt @@ -0,0 +1,24 @@ +==RACABASE FC== + +Owner: Marcin Baliniak (marcin baliniak.pl) + +Available at: shop.rotoracer.com + +Board information: + +- CPU - STM32F303CCT6 +- MPU-6000 - connected to SPI2 +- SPI Flash - connected to SPI2 +- MAX7456 - connected to SPI2 (NO DMA) +- Build in 5V BEC + LC filter - board can be powered from main battery +- Input voltage: 5V - 17.4V +- RC input: PPM, S.BUS (build in inverter) - Uart2, Spectrum-Uart3 +- Other connectors: RSSI, Current sensor, LED strip, Buzzer, Video IN/Out + LC filter +- Weight: 6 g +- Size: 36 mm x 36 mm x 5 mm + +Photo: +https://cdn.shoplo.com/0639/products/th1024/aaaw/838-rr_flight_controller_rotoracer_fc_rotoracer_racebase.jpg + +Port description: +https://cdn.shoplo.com/0639/products/th1024/aaaw/844-racebase-render-en.png \ No newline at end of file diff --git a/src/main/target/RACEBASE/target.c b/src/main/target/RACEBASE/target.c new file mode 100755 index 000000000..0b6a8f169 --- /dev/null +++ b/src/main/target/RACEBASE/target.c @@ -0,0 +1,59 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#include + +#include +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" + +const uint16_t multiPPM[] = { + PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input + PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), + 0xFFFF +}; + +const uint16_t multiPWM[] = { + PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input + PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), + 0xFFFF +}; + +const uint16_t airPPM[] = { + 0xFFFF +}; + +const uint16_t airPWM[] = { + 0xFFFF +}; + +const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1}, + + { TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2}, // PWM2 - PC6 + { TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2}, // PWM3 - PC7 + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2}, // PMW4 - PC8 + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2}, // PWM5 - PC9 +}; + + diff --git a/src/main/target/RACEBASE/target.h b/src/main/target/RACEBASE/target.h new file mode 100755 index 000000000..8e892151d --- /dev/null +++ b/src/main/target/RACEBASE/target.h @@ -0,0 +1,124 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "RBFC" +#define TARGET_CONFIG + +#define LED0 PB3 +#define LED0_INVERTED + +#define LED1 PB4 +#define LED1_INVERTED + +#define BEEPER PA12 +#define BEEPER_INVERTED + +#define USE_EXTI +#define MPU_INT_EXTI PC5 +#define EXTI_CALLBACK_HANDLER_COUNT 1 // MPU data ready +#define USE_MPU_DATA_READY_SIGNAL +#define ENSURE_MPU_DATA_READY_IS_LOW + + +#define MPU6000_CS_PIN PB5 +#define MPU6000_SPI_INSTANCE SPI2 + +#define GYRO +#define USE_GYRO_SPI_MPU6000 + +#define ACC +#define USE_ACC_SPI_MPU6000 + +#define ACC_MPU6000_ALIGN CW90_DEG +#define GYRO_MPU6000_ALIGN CW90_DEG + +#define USE_UART1 +#define USE_UART2 +#define USE_UART3 +#define SERIAL_PORT_COUNT 3 + +#define UART1_TX_PIN PA9 +#define UART1_RX_PIN PA10 + +#define UART2_TX_PIN PA2 +#define UART2_RX_PIN PA3 + +#define UART3_TX_PIN PB10 +#define UART3_RX_PIN PB11 + +#define SERIALRX_UART SERIAL_PORT_USART2 + + +#define USE_SPI +#define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5 + +#define SPI2_NSS_PIN PB12 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 + +#define USE_MAX7456 +#define MAX7456_SPI_INSTANCE SPI2 +#define MAX7456_SPI_CS_PIN PA7 + +#define M25P16_CS_PIN PB12 +#define M25P16_SPI_INSTANCE SPI2 +#define M25P16_SPI_SHARED +#define USE_FLASHFS +#define USE_FLASH_M25P16 + +#define BOARD_HAS_VOLTAGE_DIVIDER +#define USE_ADC +#define ADC_INSTANCE ADC2 +#define VBAT_ADC_PIN PA4 +#define CURRENT_METER_ADC_PIN PA5 +#define RSSI_ADC_PIN PA6 + +#define LED_STRIP +#define USE_LED_STRIP_ON_DMA1_CHANNEL2 +#define WS2811_PIN PA8 +#define WS2811_TIMER TIM1 +#define WS2811_DMA_CHANNEL DMA1_Channel2 +#define WS2811_IRQ DMA1_Channel2_IRQn +#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC2 +#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH2_HANDLER + +#define OSD + +#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT + +#define USE_SERVOS + +#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL +#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_VBAT | FEATURE_RSSI_ADC) + +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +// IO - stm32f303cc in 48pin package +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC (BIT(5)) +#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4)) + +#define USABLE_TIMER_CHANNEL_COUNT 5 +#define USED_TIMERS (TIM_N(2) | TIM_N(4)) +#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM4) +#define TIMER_AHB_PERIPHERALS (RCC_AHBPeriph_GPIOA | RCC_AHBPeriph_GPIOB) + + diff --git a/src/main/target/RACEBASE/target.mk b/src/main/target/RACEBASE/target.mk new file mode 100755 index 000000000..6e4711c5d --- /dev/null +++ b/src/main/target/RACEBASE/target.mk @@ -0,0 +1,12 @@ +F3_TARGETS += $(TARGET) + +FEATURES = ONBOARDFLASH + +TARGET_SRC = \ + drivers/accgyro_mpu.c \ + drivers/accgyro_spi_mpu6000.c \ + drivers/flash_m25p16.c \ + drivers/light_ws2811strip.c \ + drivers/light_ws2811strip_stm32f30x.c \ + drivers/max7456.c \ + io/osd.c