diff --git a/src/main/target/RACEBASE/hardware_revision.c b/src/main/target/RACEBASE/hardware_revision.c new file mode 100755 index 0000000000..e880f2babb --- /dev/null +++ b/src/main/target/RACEBASE/hardware_revision.c @@ -0,0 +1,69 @@ +/* + * 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 + +#include "platform.h" + +#include "build_config.h" + +#include "drivers/system.h" +#include "drivers/bus_spi.h" +#include "drivers/sensor.h" +#include "drivers/io.h" +#include "drivers/gpio.h" +#include "drivers/exti.h" +#include "drivers/accgyro.h" +#include "drivers/accgyro_mpu.h" +#include "drivers/accgyro_mpu6500.h" + +#include "hardware_revision.h" + +uint8_t hardwareRevision = 1; + +void detectHardwareRevision(void) +{ + gpio_config_t gpio; + + // GYRO CS as output + gpio.pin = GPIO_Pin_5; + gpio.mode = Mode_Out_PP; + gpio.speed = Speed_2MHz; + gpioInit(GPIOB, &gpio); + GPIO_SetBits(GPIOB, GPIO_Pin_5); + + gpio.pin = GPIO_Pin_7; + gpio.mode = Mode_Out_PP; + gpio.speed = Speed_2MHz; + gpioInit(GPIOA, &gpio); + GPIO_SetBits(GPIOA, GPIO_Pin_7); + + gpio.pin = GPIO_Pin_12; + gpio.mode = Mode_Out_PP; + gpio.speed = Speed_2MHz; + gpioInit(GPIOB, &gpio); + GPIO_SetBits(GPIOB, GPIO_Pin_12); +} + + +void updateHardwareRevision(void) +{ + +} + diff --git a/src/main/target/RACEBASE/hardware_revision.h b/src/main/target/RACEBASE/hardware_revision.h new file mode 100755 index 0000000000..a331babad8 --- /dev/null +++ b/src/main/target/RACEBASE/hardware_revision.h @@ -0,0 +1,24 @@ +/* + * 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 + +#include "drivers/exti.h" + +extern uint8_t hardwareRevision; + +void updateHardwareRevision(void); +void detectHardwareRevision(void); diff --git a/src/main/target/RACEBASE/target.h b/src/main/target/RACEBASE/target.h index 8e892151d4..e2bf73f640 100755 --- a/src/main/target/RACEBASE/target.h +++ b/src/main/target/RACEBASE/target.h @@ -18,6 +18,7 @@ #pragma once #define TARGET_BOARD_IDENTIFIER "RBFC" +#define USE_HARDWARE_REVISION_DETECTION #define TARGET_CONFIG #define LED0 PB3 @@ -76,6 +77,9 @@ #define USE_MAX7456 #define MAX7456_SPI_INSTANCE SPI2 #define MAX7456_SPI_CS_PIN PA7 +#define MAX7456_SPI_CLK (SPI_CLOCK_STANDARD*2) +#define MAX7456_RESTORE_CLK (SPI_CLOCK_FAST) + #define M25P16_CS_PIN PB12 #define M25P16_SPI_INSTANCE SPI2