diff --git a/docs/boards/Board - FF_RacePIT.md b/docs/boards/Board - FF_RacePIT.md index 4874726e42..0284c98a9d 100644 --- a/docs/boards/Board - FF_RacePIT.md +++ b/docs/boards/Board - FF_RacePIT.md @@ -1,10 +1,10 @@ -# FuriusFPV RacePIT V1.0 +# FuriusFPV RacePIT (v1.x) and RacePIT mini (V2.x) ## Features - Built-in RealPIT for VTX power. - More UARTS (Full 6 Uart) for Simultaneous Connections of USB, Runcam Device, GPS, CRFS Rx, Black-box, Bluetooth - Selecting Internal 5V or External 5V ESC -- 2 Port Camera Control and LED Strip for Simultaneous Connections +- 2 Port Camera Control and LED Strip for Simultaneous Connections (RacePIT only) - Built-in ESC connector - Clean and Easy to Connect 4-in-1 ESC - Use MPU6000 accelerometers and gyroscopes - Ultra Simplified OSD Interface w/ No PC Necessary @@ -20,7 +20,7 @@ - STM32F405 main chip - Built-in REALPIT for VTX power supply - 6 UARTs -- Camera control, support foxxer (built-in capacitor) and another camera (without capacitor) +- Camera control, support foxxer (built-in capacitor) and another camera (without capacitor) (RacePIT only) - LED strip control - MPU6000 - BEC 5V 1.5A 2-6S @@ -29,9 +29,7 @@ - Current sensor support - 4 ESCs signal -## BoardLayout +## BoardLayout RacePIT ![RacePIT](images/FF_RacePIT.jpg) -## Camera Connections -![RacePIT](images/FF_RacePIT_CAM.jpg) -## Connections -![RacePIT](images/FF_RacePIT_Connection.jpg) +## BoardLayout RacePIT mini +![RacePIT](images/FF_RacePIT_mini.jpg) diff --git a/docs/boards/images/FF_RacePIT.jpg b/docs/boards/images/FF_RacePIT.jpg index 641d44ada2..34e4cb5910 100644 Binary files a/docs/boards/images/FF_RacePIT.jpg and b/docs/boards/images/FF_RacePIT.jpg differ diff --git a/docs/boards/images/FF_RacePIT_CAM.jpg b/docs/boards/images/FF_RacePIT_CAM.jpg deleted file mode 100644 index eb671c8583..0000000000 Binary files a/docs/boards/images/FF_RacePIT_CAM.jpg and /dev/null differ diff --git a/docs/boards/images/FF_RacePIT_Connection.jpg b/docs/boards/images/FF_RacePIT_Connection.jpg deleted file mode 100644 index b52983848e..0000000000 Binary files a/docs/boards/images/FF_RacePIT_Connection.jpg and /dev/null differ diff --git a/docs/boards/images/FF_RacePIT_mini.jpg b/docs/boards/images/FF_RacePIT_mini.jpg new file mode 100644 index 0000000000..bffe020cad Binary files /dev/null and b/docs/boards/images/FF_RacePIT_mini.jpg differ diff --git a/src/main/target/FF_RACEPIT/config.c b/src/main/target/FF_RACEPIT/config.c index c685e477b0..ac8e36153e 100644 --- a/src/main/target/FF_RACEPIT/config.c +++ b/src/main/target/FF_RACEPIT/config.c @@ -30,8 +30,21 @@ #include "pg/pinio.h" #include "pg/piniobox.h" +#include "hardware_revision.h" + +#include "sensors/gyro.h" + +#include "pg/gyrodev.h" + void targetConfiguration(void) { + if (hardwareRevision == FF_RACEPIT_REV_1) { + gyroDeviceConfigMutable(0)->align = CW180_DEG; + } + else { + gyroDeviceConfigMutable(0)->align = CW90_DEG_FLIP; + } + telemetryConfigMutable()->halfDuplex = false; pinioConfigMutable()->config[1] = PINIO_CONFIG_OUT_INVERTED | PINIO_CONFIG_MODE_OUT_PP; diff --git a/src/main/target/FF_RACEPIT/hardware_revision.c b/src/main/target/FF_RACEPIT/hardware_revision.c new file mode 100644 index 0000000000..68ae88424e --- /dev/null +++ b/src/main/target/FF_RACEPIT/hardware_revision.c @@ -0,0 +1,57 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software 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 and Betaflight are distributed in the hope that they + * 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 this software. + * + * If not, see . + */ + +#include +#include +#include + +#include "platform.h" + +#include "build/build_config.h" + +#include "drivers/io.h" +#include "drivers/time.h" + +#include "hardware_revision.h" + +#define HW_PIN PC5 + +uint8_t hardwareRevision = FF_RACEPIT_UNKNOWN; + +static IO_t HWDetectPinA = IO_NONE; + +void detectHardwareRevision(void) +{ + HWDetectPinA = IOGetByTag(IO_TAG(HW_PIN)); + IOInit(HWDetectPinA, OWNER_SYSTEM, 0); + IOConfigGPIO(HWDetectPinA, IOCFG_IPU); + + delayMicroseconds(10); // allow configuration to settle + + if (!IORead(HWDetectPinA)) { + hardwareRevision = FF_RACEPIT_REV_1; + } else { + hardwareRevision = FF_RACEPIT_REV_2; + } +} + +void updateHardwareRevision(void) +{ +} diff --git a/src/main/target/FF_RACEPIT/hardware_revision.h b/src/main/target/FF_RACEPIT/hardware_revision.h new file mode 100644 index 0000000000..8cca4d20bb --- /dev/null +++ b/src/main/target/FF_RACEPIT/hardware_revision.h @@ -0,0 +1,32 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software 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 and Betaflight are distributed in the hope that they + * 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 this software. + * + * If not, see . + */ + +#pragma once + +typedef enum ffRacapitHardwareRevision_t { + FF_RACEPIT_UNKNOWN = 0, + FF_RACEPIT_REV_1, // RacePIT + FF_RACEPIT_REV_2, // RacePIT mini +} ffRacepitHardwareRevision_e; + +extern uint8_t hardwareRevision; + +void updateHardwareRevision(void); +void detectHardwareRevision(void); diff --git a/src/main/target/FF_RACEPIT/target.h b/src/main/target/FF_RACEPIT/target.h index cbe573e22f..ba7a4add82 100644 --- a/src/main/target/FF_RACEPIT/target.h +++ b/src/main/target/FF_RACEPIT/target.h @@ -23,6 +23,8 @@ #define USBD_PRODUCT_STRING "RacePit" #define USE_TARGET_CONFIG +#define USE_HARDWARE_REVISION_DETECTION + /*--------------LED----------------*/ #define LED0_PIN PB9 #define LED1_PIN PB8 @@ -56,8 +58,6 @@ #define GYRO_1_CS_PIN SPI1_NSS_PIN #define GYRO_1_SPI_INSTANCE SPI1 - -#define GYRO_1_ALIGN CW90_DEG_FLIP /*---------------------------------*/ diff --git a/unified_targets/configs/FF_RACEPIT.config b/unified_targets/configs/FF_RACEPIT.config index 2dd7cc2d41..f9d20302da 100644 --- a/unified_targets/configs/FF_RACEPIT.config +++ b/unified_targets/configs/FF_RACEPIT.config @@ -50,7 +50,6 @@ resource OSD_CS 1 B12 set max7456_spi_bus = 2 # Timers -# timer is zero origin timer B00 AF2 # pin B00: TIM3 CH3 (AF2) timer B01 AF2 diff --git a/unified_targets/configs/FF_RACEPIT_mini.config b/unified_targets/configs/FF_RACEPIT_mini.config new file mode 100644 index 0000000000..b729d84c0f --- /dev/null +++ b/unified_targets/configs/FF_RACEPIT_mini.config @@ -0,0 +1,123 @@ +# Name: FF_RACEPIT_mini +# Description: FuriousFPV RACEPIT with Blackbox Standard target configuration + +# Betaflight / STM32F405 (S405) 4.0.0 Mar 2 2019 / 07:01:01 (29db27584) MSP API: 1.4 + +board_name FF_RACEPIT +manufacturer_id FFPV + +defaults nosave + +# Basic I/O +resource LED 1 B09 +resource LED 2 B08 +resource BEEPER 1 C03 +set beeper_inversion = ON +set beeper_od = OFF +resource PINIO 1 C00 + +# Buses +resource I2C_SCL 3 A08 +resource I2C_SDA 3 C09 +set i2c3_pullup = ON + +resource SPI_SCK 1 A05 +resource SPI_MISO 1 A06 +resource SPI_MOSI 1 A07 + +resource SPI_SCK 2 B13 +resource SPI_MISO 2 B14 +resource SPI_MOSI 2 B15 + +resource SPI_SCK 3 B03 +resource SPI_MISO 3 B04 +resource SPI_MOSI 3 B05 + +# Acc/gyro +resource GYRO_CS 1 A04 +resource GYRO_EXTI 1 C04 +set gyro_1_bustype = SPI +set gyro_1_spibus = 1 +set gyro_1_sensor_align = CW180 + +# SPI Flash +set flash_spi_bus = 3 +resource FLASH_CS 1 A15 + +# OSD +resource OSD_CS 1 B12 +set max7456_spi_bus = 2 + +# Timers +timer B00 AF2 +# pin B00: TIM3 CH3 (AF2) +timer B01 AF2 +# pin B01: TIM3 CH4 (AF2) +timer B11 AF1 +# pin B11: TIM2 CH4 (AF1) +timer B10 AF1 +# pin B10: TIM2 CH3 (AF1) +timer A10 AF1 +# pin A10: TIM1 CH3 (AF1) +timer B06 AF2 +# pin B06: TIM4 CH1 (AF2) +resource MOTOR 1 B00 +resource MOTOR 2 B01 +resource MOTOR 3 B11 +resource MOTOR 4 B10 +resource LED_STRIP 1 B06 + +# DMA +dma ADC 2 1 # ADC 2: DMA2 Stream 3 Channel 1 +dma pin B06 0 # pin B06: DMA1 Stream 0 Channel 2 +dma pin B00 0 # pin B00: DMA1 Stream 7 Channel 5 +dma pin B01 0 # pin B01: DMA1 Stream 2 Channel 5 +dma pin B10 0 # pin B10: DMA1 Stream 1 Channel 3 +dma pin B11 1 # pin B11: DMA1 Stream 7 Channel 3 + +set dshot_burst = ON +set motor_pwm_protocol = Dshot600 + +# Serial ports +resource SERIAL_TX 1 A09 +resource SERIAL_RX 1 B07 + +resource SERIAL_TX 2 A02 +resource SERIAL_RX 2 A03 + +resource SERIAL_TX 3 C10 +resource SERIAL_RX 3 C11 +resource INVERTER 3 C15 + +resource SERIAL_TX 4 A00 +resource SERIAL_RX 4 A01 + +resource SERIAL_TX 5 C12 +resource SERIAL_RX 5 D02 + +resource SERIAL_TX 6 C06 +resource SERIAL_RX 6 C07 + +# ADC +resource ADC_BATT 1 C02 +resource ADC_CURR 1 C01 + +# Remaining +resource ESCSERIAL 1 B00 + +# Some configs +feature RX_SERIAL +feature OSD +serial 0 0 115200 57600 0 115200 +serial 1 0 115200 57600 0 115200 +serial 2 64 115200 57600 0 115200 +serial 3 0 115200 57600 0 115200 +serial 4 0 115200 57600 0 115200 +serial 5 0 115200 57600 0 115200 +set pinio_config = 1,129,1,1 +set pinio_box = 40,41,255,255 +set tlm_halfduplex = OFF +set blackbox_device = SPIFLASH +set adc_device = 2 +set battery_meter = ADC +set current_meter = ADC