mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-23 00:05:33 +03:00
SIRINFPV target initial code
This commit is contained in:
parent
be038743b2
commit
8a93041ea1
25 changed files with 2016 additions and 9 deletions
23
Makefile
23
Makefile
|
@ -42,7 +42,7 @@ FORKNAME = betaflight
|
||||||
|
|
||||||
CC3D_TARGETS = CC3D CC3D_OPBL
|
CC3D_TARGETS = CC3D CC3D_OPBL
|
||||||
|
|
||||||
VALID_TARGETS = NAZE NAZE32PRO OLIMEXINO STM32F3DISCOVERY CHEBUZZF3 $(CC3D_TARGETS) CJMCU EUSTM32F103RC SPRACINGF3 PORT103R SPARKY ALIENFLIGHTF1 ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB RMDO IRCFUSIONF3 AFROMINI SPRACINGF3MINI
|
VALID_TARGETS = NAZE NAZE32PRO OLIMEXINO STM32F3DISCOVERY CHEBUZZF3 $(CC3D_TARGETS) CJMCU EUSTM32F103RC SPRACINGF3 PORT103R SPARKY ALIENFLIGHTF1 ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB RMDO IRCFUSIONF3 AFROMINI SPRACINGF3MINI SIRINFPV
|
||||||
|
|
||||||
# Valid targets for OP VCP support
|
# Valid targets for OP VCP support
|
||||||
VCP_VALID_TARGETS = $(CC3D_TARGETS)
|
VCP_VALID_TARGETS = $(CC3D_TARGETS)
|
||||||
|
@ -52,9 +52,9 @@ OPBL_VALID_TARGETS = CC3D_OPBL
|
||||||
|
|
||||||
64K_TARGETS = CJMCU
|
64K_TARGETS = CJMCU
|
||||||
128K_TARGETS = ALIENFLIGHTF1 $(CC3D_TARGETS) NAZE OLIMEXINO RMDO AFROMINI
|
128K_TARGETS = ALIENFLIGHTF1 $(CC3D_TARGETS) NAZE OLIMEXINO RMDO AFROMINI
|
||||||
256K_TARGETS = EUSTM32F103RC PORT103R STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 IRCFUSIONF3 SPARKY ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB SPRACINGF3MINI
|
256K_TARGETS = EUSTM32F103RC PORT103R STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 IRCFUSIONF3 SPARKY ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB SPRACINGF3MINI SIRINFPV
|
||||||
|
|
||||||
F3_TARGETS = STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 IRCFUSIONF3 SPARKY ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB RMDO SPRACINGF3MINI
|
F3_TARGETS = STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 IRCFUSIONF3 SPARKY ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB RMDO SPRACINGF3MINI SIRINFPV
|
||||||
|
|
||||||
|
|
||||||
# Configure default flash sizes for the targets
|
# Configure default flash sizes for the targets
|
||||||
|
@ -749,6 +749,23 @@ SPRACINGF3MINI_SRC = \
|
||||||
$(VCP_SRC)
|
$(VCP_SRC)
|
||||||
# $(FATFS_SRC)
|
# $(FATFS_SRC)
|
||||||
|
|
||||||
|
SIRINFPV_SRC = \
|
||||||
|
$(STM32F30x_COMMON_SRC) \
|
||||||
|
drivers/accgyro_mpu.c \
|
||||||
|
drivers/accgyro_spi_mpu6000.c \
|
||||||
|
drivers/serial_usb_vcp.c \
|
||||||
|
drivers/sdcard.c \
|
||||||
|
drivers/sdcard_standard.c \
|
||||||
|
drivers/max7456.c \
|
||||||
|
drivers/rtc6705.c \
|
||||||
|
io/asyncfatfs/asyncfatfs.c \
|
||||||
|
io/asyncfatfs/fat_standard.c \
|
||||||
|
io/osd.c \
|
||||||
|
$(HIGHEND_SRC) \
|
||||||
|
$(COMMON_SRC) \
|
||||||
|
$(VCP_SRC)
|
||||||
|
# $(FATFS_SRC)
|
||||||
|
|
||||||
# Search path and source files for the ST stdperiph library
|
# Search path and source files for the ST stdperiph library
|
||||||
VPATH := $(VPATH):$(STDPERIPH_DIR)/src
|
VPATH := $(VPATH):$(STDPERIPH_DIR)/src
|
||||||
|
|
||||||
|
|
|
@ -395,6 +395,16 @@ static void resetConf(void)
|
||||||
// featureSet(FEATURE_DISPLAY);
|
// featureSet(FEATURE_DISPLAY);
|
||||||
//#endif
|
//#endif
|
||||||
|
|
||||||
|
#ifdef SIRINFPV
|
||||||
|
featureSet(FEATURE_OSD);
|
||||||
|
featureSet(FEATURE_RX_SERIAL);
|
||||||
|
masterConfig.serialConfig.portConfigs[2].functionMask = FUNCTION_RX_SERIAL;
|
||||||
|
//masterConfig.batteryConfig.vbatscale = 20;
|
||||||
|
masterConfig.mag_hardware = MAG_NONE; // disabled by default
|
||||||
|
masterConfig.rxConfig.serialrx_provider = SERIALRX_SBUS;
|
||||||
|
masterConfig.vtx_channel = 0;
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifdef BOARD_HAS_VOLTAGE_DIVIDER
|
#ifdef BOARD_HAS_VOLTAGE_DIVIDER
|
||||||
// only enable the VBAT feature by default if the board has a voltage divider otherwise
|
// only enable the VBAT feature by default if the board has a voltage divider otherwise
|
||||||
// the user may see incorrect readings and unexpected issues with pin mappings may occur.
|
// the user may see incorrect readings and unexpected issues with pin mappings may occur.
|
||||||
|
|
|
@ -44,6 +44,7 @@ typedef enum {
|
||||||
FEATURE_BLACKBOX = 1 << 19,
|
FEATURE_BLACKBOX = 1 << 19,
|
||||||
FEATURE_CHANNEL_FORWARDING = 1 << 20,
|
FEATURE_CHANNEL_FORWARDING = 1 << 20,
|
||||||
FEATURE_TRANSPONDER = 1 << 21,
|
FEATURE_TRANSPONDER = 1 << 21,
|
||||||
|
FEATURE_OSD = 1 << 22,
|
||||||
} features_e;
|
} features_e;
|
||||||
|
|
||||||
void handleOneshotFeatureChangeOnRestart(void);
|
void handleOneshotFeatureChangeOnRestart(void);
|
||||||
|
|
|
@ -125,6 +125,10 @@ typedef struct master_t {
|
||||||
uint8_t transponderData[6];
|
uint8_t transponderData[6];
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifdef OSD
|
||||||
|
uint8_t vtx_channel;
|
||||||
|
#endif
|
||||||
|
|
||||||
profile_t profile[MAX_PROFILE_COUNT];
|
profile_t profile[MAX_PROFILE_COUNT];
|
||||||
uint8_t current_profile_index;
|
uint8_t current_profile_index;
|
||||||
|
|
||||||
|
|
|
@ -345,8 +345,8 @@ void initSpi3(void)
|
||||||
GPIO_PinAFConfig(SPI3_GPIO, SPI3_MOSI_PIN_SOURCE, GPIO_AF_6);
|
GPIO_PinAFConfig(SPI3_GPIO, SPI3_MOSI_PIN_SOURCE, GPIO_AF_6);
|
||||||
|
|
||||||
#ifdef SPI2_NSS_PIN_SOURCE
|
#ifdef SPI2_NSS_PIN_SOURCE
|
||||||
RCC_AHBPeriphClockCmd(SPI3_NNS_PERIPHERAL, ENABLE);
|
RCC_AHBPeriphClockCmd(SPI3_NSS_PERIPHERAL, ENABLE);
|
||||||
GPIO_PinAFConfig(SPI3_NNS_GPIO, SPI3_NSS_PIN_SOURCE, GPIO_AF_6);
|
GPIO_PinAFConfig(SPI3_NSS_GPIO, SPI3_NSS_PIN_SOURCE, GPIO_AF_6);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Init pins
|
// Init pins
|
||||||
|
|
168
src/main/drivers/max7456.c
Normal file
168
src/main/drivers/max7456.c
Normal file
|
@ -0,0 +1,168 @@
|
||||||
|
/*
|
||||||
|
* 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 <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <stdlib.h>
|
||||||
|
#include <stdbool.h>
|
||||||
|
#include <stdint.h>
|
||||||
|
|
||||||
|
#include "platform.h"
|
||||||
|
|
||||||
|
#ifdef USE_MAX7456
|
||||||
|
|
||||||
|
#include "drivers/bus_spi.h"
|
||||||
|
#include "drivers/system.h"
|
||||||
|
|
||||||
|
#include "max7456.h"
|
||||||
|
|
||||||
|
#define DISABLE_MAX7456 GPIO_SetBits(MAX7456_CS_GPIO, MAX7456_CS_PIN)
|
||||||
|
#define ENABLE_MAX7456 GPIO_ResetBits(MAX7456_CS_GPIO, MAX7456_CS_PIN)
|
||||||
|
|
||||||
|
|
||||||
|
uint16_t max_screen_size;
|
||||||
|
uint8_t video_signal_type = 0;
|
||||||
|
uint8_t max7456_lock = 0;
|
||||||
|
char screen[480];
|
||||||
|
|
||||||
|
|
||||||
|
uint8_t max7456_send(uint8_t add, uint8_t data) {
|
||||||
|
spiTransferByte(MAX7456_SPI_INSTANCE, add);
|
||||||
|
return spiTransferByte(MAX7456_SPI_INSTANCE, data);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
// ============================================================ WRITE TO SCREEN
|
||||||
|
|
||||||
|
void max7456_init(void) {
|
||||||
|
uint8_t max7456_reset=0x02;
|
||||||
|
uint8_t max_screen_rows;
|
||||||
|
uint8_t srdata = 0;
|
||||||
|
uint16_t x;
|
||||||
|
|
||||||
|
//Minimum spi clock period for max7456 is 100ns (10Mhz)
|
||||||
|
spiSetDivisor(MAX7456_SPI_INSTANCE, SPI_9MHZ_CLOCK_DIVIDER);
|
||||||
|
|
||||||
|
// force soft reset on Max7456
|
||||||
|
ENABLE_MAX7456;
|
||||||
|
max7456_send(VM0_reg, max7456_reset);
|
||||||
|
delay(100);
|
||||||
|
|
||||||
|
srdata = max7456_send(0xA0, 0xFF);
|
||||||
|
if ((0x01 & srdata) == 0x01){ //PAL
|
||||||
|
video_signal_type = VIDEO_MODE_PAL;
|
||||||
|
}
|
||||||
|
else if((0x02 & srdata) == 0x02){ //NTSC
|
||||||
|
video_signal_type = VIDEO_MODE_NTSC;
|
||||||
|
}
|
||||||
|
|
||||||
|
max7456_reset |= video_signal_type;
|
||||||
|
|
||||||
|
if (video_signal_type) { //PAL
|
||||||
|
max_screen_size = 480;
|
||||||
|
max_screen_rows = 16;
|
||||||
|
} else { // NTSC
|
||||||
|
max_screen_size = 390;
|
||||||
|
max_screen_rows = 13;
|
||||||
|
}
|
||||||
|
|
||||||
|
// set all rows to same charactor black/white level
|
||||||
|
for(x = 0; x < max_screen_rows; x++) {
|
||||||
|
max7456_send(MAX7456ADD_RB0 + x, BWBRIGHTNESS);
|
||||||
|
}
|
||||||
|
|
||||||
|
// make sure the Max7456 is enabled
|
||||||
|
max7456_send(VM0_reg, OSD_ENABLE | video_signal_type);
|
||||||
|
|
||||||
|
DISABLE_MAX7456;
|
||||||
|
delay(100);
|
||||||
|
for (x=0; x<256; x++)
|
||||||
|
screen[x] = (char)x;
|
||||||
|
max7456_draw_screen();
|
||||||
|
}
|
||||||
|
|
||||||
|
// Copy string from ram into screen buffer
|
||||||
|
void max7456_write_string(const char *string, int address) {
|
||||||
|
char *dest = screen + address;
|
||||||
|
|
||||||
|
while(*string)
|
||||||
|
*dest++ = *string++;
|
||||||
|
}
|
||||||
|
|
||||||
|
void max7456_draw_screen(void) {
|
||||||
|
uint16_t xx;
|
||||||
|
if (!max7456_lock) {
|
||||||
|
ENABLE_MAX7456;
|
||||||
|
for (xx = 0; xx < max_screen_size; ++xx) {
|
||||||
|
max7456_send(MAX7456ADD_DMAH, xx>>8);
|
||||||
|
max7456_send(MAX7456ADD_DMAL, xx);
|
||||||
|
max7456_send(MAX7456ADD_DMDI, screen[xx]);
|
||||||
|
screen[xx] = ' ';
|
||||||
|
}
|
||||||
|
DISABLE_MAX7456;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void max7456_draw_screen_fast(void) {
|
||||||
|
uint16_t xx;
|
||||||
|
if (!max7456_lock) {
|
||||||
|
ENABLE_MAX7456;
|
||||||
|
max7456_send(MAX7456ADD_DMAH, 0);
|
||||||
|
max7456_send(MAX7456ADD_DMAL, 0);
|
||||||
|
max7456_send(MAX7456ADD_DMM, 1);
|
||||||
|
for (xx = 0; xx < max_screen_size; ++xx) {
|
||||||
|
max7456_send(MAX7456ADD_DMDI, screen[xx]);
|
||||||
|
screen[xx] = ' ';
|
||||||
|
}
|
||||||
|
max7456_send(MAX7456ADD_DMDI, 0xFF);
|
||||||
|
max7456_send(MAX7456ADD_DMM, 0);
|
||||||
|
DISABLE_MAX7456;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
#define NVM_RAM_SIZE 54
|
||||||
|
#define WRITE_NVR 0xA0
|
||||||
|
#define STATUS_REG_NVR_BUSY 0x20
|
||||||
|
|
||||||
|
|
||||||
|
void max7456_write_nvm(uint8_t char_address, uint8_t *font_data) {
|
||||||
|
uint8_t x;
|
||||||
|
|
||||||
|
max7456_lock = 1;
|
||||||
|
ENABLE_MAX7456;
|
||||||
|
|
||||||
|
// disable display
|
||||||
|
max7456_send(VM0_reg, video_signal_type);
|
||||||
|
|
||||||
|
max7456_send(MAX7456ADD_CMAH, char_address); // set start address high
|
||||||
|
|
||||||
|
for(x = 0; x < 54; x++) {
|
||||||
|
max7456_send(MAX7456ADD_CMAL, x); //set start address low
|
||||||
|
max7456_send(MAX7456ADD_CMDI, font_data[x]);
|
||||||
|
}
|
||||||
|
|
||||||
|
// transfer 54 bytes from shadow ram to NVM
|
||||||
|
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);
|
||||||
|
|
||||||
|
max7456_send(VM0_reg, video_signal_type | 0x0C);
|
||||||
|
DISABLE_MAX7456;
|
||||||
|
max7456_lock = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
#endif
|
130
src/main/drivers/max7456.h
Normal file
130
src/main/drivers/max7456.h
Normal file
|
@ -0,0 +1,130 @@
|
||||||
|
/*
|
||||||
|
* 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 <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#define DATAOUT 11 // MOSI
|
||||||
|
#define DATAIN 12 // MISO
|
||||||
|
#define SPICLOCK 13 // sck
|
||||||
|
#define VSYNC 2 // INT0
|
||||||
|
|
||||||
|
#ifndef WHITEBRIGHTNESS
|
||||||
|
#define WHITEBRIGHTNESS 0x01
|
||||||
|
#endif
|
||||||
|
#ifndef BLACKBRIGHTNESS
|
||||||
|
#define BLACKBRIGHTNESS 0x00
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define BWBRIGHTNESS ((BLACKBRIGHTNESS << 2) | WHITEBRIGHTNESS)
|
||||||
|
|
||||||
|
//MAX7456 opcodes
|
||||||
|
#define DMM_reg 0x04
|
||||||
|
#define DMAH_reg 0x05
|
||||||
|
#define DMAL_reg 0x06
|
||||||
|
#define DMDI_reg 0x07
|
||||||
|
#define VM0_reg 0x00
|
||||||
|
#define VM1_reg 0x01
|
||||||
|
|
||||||
|
// video mode register 0 bits
|
||||||
|
#define VIDEO_BUFFER_DISABLE 0x01
|
||||||
|
//#define MAX7456_RESET 0x02
|
||||||
|
#define VERTICAL_SYNC_NEXT_VSYNC 0x04
|
||||||
|
#define OSD_ENABLE 0x08
|
||||||
|
#define SYNC_MODE_AUTO 0x00
|
||||||
|
#define SYNC_MODE_INTERNAL 0x30
|
||||||
|
#define SYNC_MODE_EXTERNAL 0x20
|
||||||
|
#define VIDEO_MODE_PAL 0x40
|
||||||
|
#define VIDEO_MODE_NTSC 0x00
|
||||||
|
|
||||||
|
// video mode register 1 bits
|
||||||
|
|
||||||
|
|
||||||
|
// duty cycle is on_off
|
||||||
|
#define BLINK_DUTY_CYCLE_50_50 0x00
|
||||||
|
#define BLINK_DUTY_CYCLE_33_66 0x01
|
||||||
|
#define BLINK_DUTY_CYCLE_25_75 0x02
|
||||||
|
#define BLINK_DUTY_CYCLE_75_25 0x03
|
||||||
|
|
||||||
|
// blinking time
|
||||||
|
#define BLINK_TIME_0 0x00
|
||||||
|
#define BLINK_TIME_1 0x04
|
||||||
|
#define BLINK_TIME_2 0x08
|
||||||
|
#define BLINK_TIME_3 0x0C
|
||||||
|
|
||||||
|
// background mode brightness (percent)
|
||||||
|
#define BACKGROUND_BRIGHTNESS_0 0x00
|
||||||
|
#define BACKGROUND_BRIGHTNESS_7 0x01
|
||||||
|
#define BACKGROUND_BRIGHTNESS_14 0x02
|
||||||
|
#define BACKGROUND_BRIGHTNESS_21 0x03
|
||||||
|
#define BACKGROUND_BRIGHTNESS_28 0x04
|
||||||
|
#define BACKGROUND_BRIGHTNESS_35 0x05
|
||||||
|
#define BACKGROUND_BRIGHTNESS_42 0x06
|
||||||
|
#define BACKGROUND_BRIGHTNESS_49 0x07
|
||||||
|
|
||||||
|
#define BACKGROUND_MODE_GRAY 0x40
|
||||||
|
|
||||||
|
//MAX7456 commands
|
||||||
|
#define CLEAR_display 0x04
|
||||||
|
#define CLEAR_display_vert 0x06
|
||||||
|
#define END_string 0xff
|
||||||
|
|
||||||
|
|
||||||
|
#define MAX7456ADD_VM0 0x00 //0b0011100// 00 // 00 ,0011100
|
||||||
|
#define MAX7456ADD_VM1 0x01
|
||||||
|
#define MAX7456ADD_HOS 0x02
|
||||||
|
#define MAX7456ADD_VOS 0x03
|
||||||
|
#define MAX7456ADD_DMM 0x04
|
||||||
|
#define MAX7456ADD_DMAH 0x05
|
||||||
|
#define MAX7456ADD_DMAL 0x06
|
||||||
|
#define MAX7456ADD_DMDI 0x07
|
||||||
|
#define MAX7456ADD_CMM 0x08
|
||||||
|
#define MAX7456ADD_CMAH 0x09
|
||||||
|
#define MAX7456ADD_CMAL 0x0a
|
||||||
|
#define MAX7456ADD_CMDI 0x0b
|
||||||
|
#define MAX7456ADD_OSDM 0x0c
|
||||||
|
#define MAX7456ADD_RB0 0x10
|
||||||
|
#define MAX7456ADD_RB1 0x11
|
||||||
|
#define MAX7456ADD_RB2 0x12
|
||||||
|
#define MAX7456ADD_RB3 0x13
|
||||||
|
#define MAX7456ADD_RB4 0x14
|
||||||
|
#define MAX7456ADD_RB5 0x15
|
||||||
|
#define MAX7456ADD_RB6 0x16
|
||||||
|
#define MAX7456ADD_RB7 0x17
|
||||||
|
#define MAX7456ADD_RB8 0x18
|
||||||
|
#define MAX7456ADD_RB9 0x19
|
||||||
|
#define MAX7456ADD_RB10 0x1a
|
||||||
|
#define MAX7456ADD_RB11 0x1b
|
||||||
|
#define MAX7456ADD_RB12 0x1c
|
||||||
|
#define MAX7456ADD_RB13 0x1d
|
||||||
|
#define MAX7456ADD_RB14 0x1e
|
||||||
|
#define MAX7456ADD_RB15 0x1f
|
||||||
|
#define MAX7456ADD_OSDBL 0x6c
|
||||||
|
#define MAX7456ADD_STAT 0xA0
|
||||||
|
|
||||||
|
// Selectable by video mode
|
||||||
|
//uint8_t ENABLE_display;
|
||||||
|
//uint8_t ENABLE_display_vert;
|
||||||
|
//uint8_t DISABLE_display;
|
||||||
|
uint16_t MAX_screen_size;
|
||||||
|
char screen[480];
|
||||||
|
|
||||||
|
|
||||||
|
void max7456_init(void);
|
||||||
|
void max7456_draw_screen(void);
|
||||||
|
void max7456_draw_screen_fast(void);
|
||||||
|
void max7456_write_string(const char *string, int address);
|
||||||
|
void max7456_write_nvm(uint8_t char_address, uint8_t *font_data);
|
|
@ -562,6 +562,36 @@ static const uint16_t airPWM[] = {
|
||||||
};
|
};
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if defined(SIRINFPV)
|
||||||
|
static const uint16_t multiPPM[] = {
|
||||||
|
PWM1 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||||
|
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||||
|
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||||
|
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||||
|
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||||
|
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||||
|
0xFFFF
|
||||||
|
};
|
||||||
|
|
||||||
|
static const uint16_t multiPWM[] = {
|
||||||
|
PWM1 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||||
|
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||||
|
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||||
|
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||||
|
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||||
|
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||||
|
0xFFFF
|
||||||
|
};
|
||||||
|
|
||||||
|
static const uint16_t airPPM[] = {
|
||||||
|
0xFFFF
|
||||||
|
};
|
||||||
|
|
||||||
|
static const uint16_t airPWM[] = {
|
||||||
|
0xFFFF
|
||||||
|
};
|
||||||
|
#endif
|
||||||
|
|
||||||
static const uint16_t * const hardwareMaps[] = {
|
static const uint16_t * const hardwareMaps[] = {
|
||||||
multiPWM,
|
multiPWM,
|
||||||
multiPPM,
|
multiPPM,
|
||||||
|
|
151
src/main/drivers/rtc6705.c
Normal file
151
src/main/drivers/rtc6705.c
Normal file
|
@ -0,0 +1,151 @@
|
||||||
|
/*
|
||||||
|
* 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 <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <stdlib.h>
|
||||||
|
#include <stdbool.h>
|
||||||
|
#include <stdint.h>
|
||||||
|
|
||||||
|
#include "platform.h"
|
||||||
|
|
||||||
|
#ifdef USE_RTC6705
|
||||||
|
|
||||||
|
#include "drivers/bus_spi.h"
|
||||||
|
#include "drivers/system.h"
|
||||||
|
#include "drivers/gpio.h"
|
||||||
|
|
||||||
|
#include "rtc6705.h"
|
||||||
|
|
||||||
|
#define RTC6705_SPICLK_ON GPIO_SetBits(RTC6705_SPICLK_GPIO, RTC6705_SPICLK_PIN)
|
||||||
|
#define RTC6705_SPICLK_OFF GPIO_ResetBits(RTC6705_SPICLK_GPIO, RTC6705_SPICLK_PIN)
|
||||||
|
|
||||||
|
#define RTC6705_SPIDATA_ON GPIO_SetBits(RTC6705_SPIDATA_GPIO, RTC6705_SPIDATA_PIN)
|
||||||
|
#define RTC6705_SPIDATA_OFF GPIO_ResetBits(RTC6705_SPIDATA_GPIO, RTC6705_SPIDATA_PIN)
|
||||||
|
|
||||||
|
#define RTC6705_SPILE_ON GPIO_SetBits(RTC6705_SPILE_GPIO, RTC6705_SPILE_PIN)
|
||||||
|
#define RTC6705_SPILE_OFF GPIO_ResetBits(RTC6705_SPILE_GPIO, RTC6705_SPILE_PIN)
|
||||||
|
|
||||||
|
char *vtx_bands[] = {
|
||||||
|
"BOSCAM A",
|
||||||
|
"BOSCAM B",
|
||||||
|
"BOSCAM E",
|
||||||
|
"FATSHARK",
|
||||||
|
"RACEBAND",
|
||||||
|
};
|
||||||
|
|
||||||
|
uint16_t vtx_freq[] =
|
||||||
|
{
|
||||||
|
5865, 5845, 5825, 5805, 5785, 5765, 5745, 5725,
|
||||||
|
5733, 5752, 5771, 5790, 5809, 5828, 5847, 5866,
|
||||||
|
5705, 5685, 5665, 5645, 5885, 5905, 5925, 5945,
|
||||||
|
5740, 5760, 5780, 5800, 5820, 5840, 5860, 5880,
|
||||||
|
5658, 5695, 5732, 5769, 5806, 5843, 5880, 5917,
|
||||||
|
};
|
||||||
|
|
||||||
|
uint16_t current_vtx_channel;
|
||||||
|
|
||||||
|
void rtc6705_init(void) {
|
||||||
|
gpio_config_t gpio;
|
||||||
|
|
||||||
|
#ifdef STM32F303
|
||||||
|
#ifdef RTC6705_SPICLK_PERIPHERAL
|
||||||
|
RCC_AHBPeriphClockCmd(RTC6705_SPICLK_PERIPHERAL, ENABLE);
|
||||||
|
#endif
|
||||||
|
#ifdef RTC6705_SPILE_PERIPHERAL
|
||||||
|
RCC_AHBPeriphClockCmd(RTC6705_SPILE_PERIPHERAL, ENABLE);
|
||||||
|
#endif
|
||||||
|
#ifdef RTC6705_SPIDATA_PERIPHERAL
|
||||||
|
RCC_AHBPeriphClockCmd(RTC6705_SPIDATA_PERIPHERAL, ENABLE);
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
#ifdef STM32F10X
|
||||||
|
#ifdef RTC6705_SPICLK_PERIPHERAL
|
||||||
|
RCC_APB2PeriphClockCmd(RTC6705_SPICLK_PERIPHERAL, ENABLE);
|
||||||
|
#endif
|
||||||
|
#ifdef RTC6705_SPILE_PERIPHERAL
|
||||||
|
RCC_APB2PeriphClockCmd(RTC6705_SPILE_PERIPHERAL, ENABLE);
|
||||||
|
#endif
|
||||||
|
#ifdef RTC6705_SPIDATA_PERIPHERAL
|
||||||
|
RCC_APB2PeriphClockCmd(RTC6705_SPIDATA_PERIPHERAL, ENABLE);
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
gpio.pin = RTC6705_SPICLK_PIN;
|
||||||
|
gpio.speed = Speed_50MHz;
|
||||||
|
gpio.mode = Mode_Out_PP;
|
||||||
|
gpioInit(RTC6705_SPICLK_GPIO, &gpio);
|
||||||
|
|
||||||
|
gpio.pin = RTC6705_SPILE_PIN;
|
||||||
|
gpio.speed = Speed_50MHz;
|
||||||
|
gpio.mode = Mode_Out_PP;
|
||||||
|
gpioInit(RTC6705_SPILE_GPIO, &gpio);
|
||||||
|
|
||||||
|
gpio.pin = RTC6705_SPIDATA_PIN;
|
||||||
|
gpio.speed = Speed_50MHz;
|
||||||
|
gpio.mode = Mode_Out_PP;
|
||||||
|
gpioInit(RTC6705_SPIDATA_GPIO, &gpio);
|
||||||
|
}
|
||||||
|
|
||||||
|
void rtc6705_write_register(uint8_t addr, uint32_t data) {
|
||||||
|
uint8_t i;
|
||||||
|
|
||||||
|
RTC6705_SPILE_OFF;
|
||||||
|
delay(1);
|
||||||
|
// send address
|
||||||
|
for (i=0; i<4; i++) {
|
||||||
|
if ((addr >> i) & 1)
|
||||||
|
RTC6705_SPIDATA_ON;
|
||||||
|
else
|
||||||
|
RTC6705_SPIDATA_OFF;
|
||||||
|
|
||||||
|
RTC6705_SPICLK_ON;
|
||||||
|
delay(1);
|
||||||
|
RTC6705_SPICLK_OFF;
|
||||||
|
delay(1);
|
||||||
|
}
|
||||||
|
// Write bit
|
||||||
|
|
||||||
|
RTC6705_SPIDATA_ON;
|
||||||
|
RTC6705_SPICLK_ON;
|
||||||
|
delay(1);
|
||||||
|
RTC6705_SPICLK_OFF;
|
||||||
|
delay(1);
|
||||||
|
for (i=0; i<20; i++) {
|
||||||
|
if ((data >> i) & 1)
|
||||||
|
RTC6705_SPIDATA_ON;
|
||||||
|
else
|
||||||
|
RTC6705_SPIDATA_OFF;
|
||||||
|
RTC6705_SPICLK_ON;
|
||||||
|
delay(1);
|
||||||
|
RTC6705_SPICLK_OFF;
|
||||||
|
delay(1);
|
||||||
|
}
|
||||||
|
RTC6705_SPILE_ON;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
void rtc6705_set_channel(uint16_t channel_freq) {
|
||||||
|
|
||||||
|
uint32_t freq = (uint32_t)channel_freq * 1000;
|
||||||
|
uint32_t N, A;
|
||||||
|
|
||||||
|
freq /= 40; // TODO check all channels for the R value
|
||||||
|
N = freq / 64;
|
||||||
|
A = freq % 64;
|
||||||
|
rtc6705_write_register(0, 400);
|
||||||
|
rtc6705_write_register(1, (N << 7) | A);
|
||||||
|
}
|
||||||
|
#endif
|
25
src/main/drivers/rtc6705.h
Normal file
25
src/main/drivers/rtc6705.h
Normal file
|
@ -0,0 +1,25 @@
|
||||||
|
/*
|
||||||
|
* 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 <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
extern char* vtx_bands[];
|
||||||
|
extern uint16_t vtx_freq[];
|
||||||
|
extern uint16_t current_vtx_channel;
|
||||||
|
|
||||||
|
void rtc6705_init(void);
|
||||||
|
void rtc6705_set_channel(uint16_t channel_freq);
|
|
@ -278,6 +278,26 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if defined(SIRINFPV)
|
||||||
|
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||||
|
|
||||||
|
{ TIM4, GPIOB, Pin_6, TIM_Channel_1, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource6, GPIO_AF_2}, // PWM1 - PB6
|
||||||
|
{ TIM4, GPIOB, Pin_7, TIM_Channel_2, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource7, GPIO_AF_2}, // PWM2 - PB6
|
||||||
|
{ TIM4, GPIOB, Pin_8, TIM_Channel_3, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource8, GPIO_AF_2}, // PWM3 - PB8
|
||||||
|
{ TIM4, GPIOB, Pin_9, TIM_Channel_4, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource9, GPIO_AF_2}, // PWM4 - PB9
|
||||||
|
|
||||||
|
{ TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_2}, // PWM5 - PB0 - *TIM3_CH3
|
||||||
|
{ TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_2}, // PWM6 - PB1 - *TIM3_CH4
|
||||||
|
|
||||||
|
};
|
||||||
|
|
||||||
|
#define USED_TIMERS (TIM_N(3) | TIM_N(4))
|
||||||
|
|
||||||
|
#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4)
|
||||||
|
#define TIMER_AHB_PERIPHERALS (RCC_AHBPeriph_GPIOB)
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
#if defined(MOTOLAB)
|
#if defined(MOTOLAB)
|
||||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||||
{ TIM3, GPIOA, Pin_4, TIM_Channel_2, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource4, GPIO_AF_2}, // PWM1 - PA4 - *TIM3_CH2
|
{ TIM3, GPIOA, Pin_4, TIM_Channel_2, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource4, GPIO_AF_2}, // PWM1 - PA4 - *TIM3_CH2
|
||||||
|
|
|
@ -189,9 +189,10 @@ extern int16_t servo[MAX_SUPPORTED_SERVOS];
|
||||||
bool isMixerUsingServos(void);
|
bool isMixerUsingServos(void);
|
||||||
void writeServos(void);
|
void writeServos(void);
|
||||||
void filterServos(void);
|
void filterServos(void);
|
||||||
bool motorLimitReached;
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
bool motorLimitReached;
|
||||||
|
|
||||||
extern int16_t motor[MAX_SUPPORTED_MOTORS];
|
extern int16_t motor[MAX_SUPPORTED_MOTORS];
|
||||||
extern int16_t motor_disarmed[MAX_SUPPORTED_MOTORS];
|
extern int16_t motor_disarmed[MAX_SUPPORTED_MOTORS];
|
||||||
|
|
||||||
|
|
671
src/main/io/osd.c
Normal file
671
src/main/io/osd.c
Normal file
|
@ -0,0 +1,671 @@
|
||||||
|
/*
|
||||||
|
* 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 <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <stdbool.h>
|
||||||
|
#include <stdint.h>
|
||||||
|
#include <stdlib.h>
|
||||||
|
#include <string.h>
|
||||||
|
#include <math.h>
|
||||||
|
|
||||||
|
#include "platform.h"
|
||||||
|
#include "scheduler.h"
|
||||||
|
|
||||||
|
#include "common/axis.h"
|
||||||
|
#include "common/color.h"
|
||||||
|
#include "common/atomic.h"
|
||||||
|
#include "common/maths.h"
|
||||||
|
#include "common/typeconversion.h"
|
||||||
|
|
||||||
|
#include "drivers/nvic.h"
|
||||||
|
|
||||||
|
#include "drivers/sensor.h"
|
||||||
|
#include "drivers/system.h"
|
||||||
|
#include "drivers/gpio.h"
|
||||||
|
#include "drivers/light_led.h"
|
||||||
|
#include "drivers/sound_beeper.h"
|
||||||
|
#include "drivers/timer.h"
|
||||||
|
#include "drivers/serial.h"
|
||||||
|
#include "drivers/serial_softserial.h"
|
||||||
|
#include "drivers/serial_uart.h"
|
||||||
|
#include "drivers/accgyro.h"
|
||||||
|
#include "drivers/compass.h"
|
||||||
|
#include "drivers/pwm_mapping.h"
|
||||||
|
#include "drivers/pwm_rx.h"
|
||||||
|
#include "drivers/adc.h"
|
||||||
|
#include "drivers/bus_i2c.h"
|
||||||
|
#include "drivers/bus_bst.h"
|
||||||
|
#include "drivers/bus_spi.h"
|
||||||
|
#include "drivers/inverter.h"
|
||||||
|
#include "drivers/flash_m25p16.h"
|
||||||
|
#include "drivers/sonar_hcsr04.h"
|
||||||
|
#include "drivers/gyro_sync.h"
|
||||||
|
#include "drivers/usb_io.h"
|
||||||
|
#include "drivers/transponder_ir.h"
|
||||||
|
#include "drivers/sdcard.h"
|
||||||
|
|
||||||
|
#include "rx/rx.h"
|
||||||
|
|
||||||
|
#include "io/beeper.h"
|
||||||
|
#include "io/serial.h"
|
||||||
|
#include "io/flashfs.h"
|
||||||
|
#include "io/gps.h"
|
||||||
|
#include "io/escservo.h"
|
||||||
|
#include "io/rc_controls.h"
|
||||||
|
#include "io/gimbal.h"
|
||||||
|
#include "io/ledstrip.h"
|
||||||
|
#include "io/display.h"
|
||||||
|
#include "io/asyncfatfs/asyncfatfs.h"
|
||||||
|
#include "io/transponder_ir.h"
|
||||||
|
|
||||||
|
#include "sensors/sensors.h"
|
||||||
|
#include "sensors/sonar.h"
|
||||||
|
#include "sensors/barometer.h"
|
||||||
|
#include "sensors/compass.h"
|
||||||
|
#include "sensors/acceleration.h"
|
||||||
|
#include "sensors/gyro.h"
|
||||||
|
#include "sensors/battery.h"
|
||||||
|
#include "sensors/boardalignment.h"
|
||||||
|
#include "sensors/initialisation.h"
|
||||||
|
|
||||||
|
#include "telemetry/telemetry.h"
|
||||||
|
#include "blackbox/blackbox.h"
|
||||||
|
|
||||||
|
#include "flight/pid.h"
|
||||||
|
#include "flight/imu.h"
|
||||||
|
#include "flight/mixer.h"
|
||||||
|
#include "flight/failsafe.h"
|
||||||
|
#include "flight/navigation.h"
|
||||||
|
|
||||||
|
#include "config/runtime_config.h"
|
||||||
|
#include "config/config.h"
|
||||||
|
#include "config/config_profile.h"
|
||||||
|
#include "config/config_master.h"
|
||||||
|
|
||||||
|
#ifdef USE_HARDWARE_REVISION_DETECTION
|
||||||
|
#include "hardware_revision.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include "build_config.h"
|
||||||
|
#include "debug.h"
|
||||||
|
|
||||||
|
#ifdef OSD
|
||||||
|
|
||||||
|
#include "io/osd.h"
|
||||||
|
#include "drivers/max7456.h"
|
||||||
|
#include "drivers/rtc6705.h"
|
||||||
|
#include "scheduler.h"
|
||||||
|
#include "common/printf.h"
|
||||||
|
|
||||||
|
#define MICROSECONDS_IN_A_SECOND (1000 * 1000)
|
||||||
|
|
||||||
|
#define OSD_UPDATE_FREQUENCY (MICROSECONDS_IN_A_SECOND / 5)
|
||||||
|
#define OSD_LINE_LENGTH 30
|
||||||
|
|
||||||
|
static uint32_t next_osd_update_at = 0;
|
||||||
|
static uint32_t armed_seconds = 0;
|
||||||
|
static uint32_t armed_at = 0;
|
||||||
|
static bool armed = false;
|
||||||
|
|
||||||
|
static uint8_t current_page = 0;
|
||||||
|
static uint8_t sticks[] = {0,0,0,0};
|
||||||
|
char string_buffer[30];
|
||||||
|
uint8_t cursor_row = 255;
|
||||||
|
uint8_t cursor_col = 0;
|
||||||
|
bool in_menu = false;
|
||||||
|
|
||||||
|
#ifdef USE_RTC6705
|
||||||
|
void update_vtx_band(bool increase, uint8_t col) {
|
||||||
|
(void)col;
|
||||||
|
if (increase) {
|
||||||
|
if (current_vtx_channel < 32)
|
||||||
|
current_vtx_channel += 8;
|
||||||
|
} else {
|
||||||
|
if (current_vtx_channel > 7)
|
||||||
|
current_vtx_channel -= 8;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void print_vtx_band(uint16_t pos, uint8_t col) {
|
||||||
|
(void)col;
|
||||||
|
sprintf(string_buffer, "%s", vtx_bands[current_vtx_channel / 8]);
|
||||||
|
max7456_write_string(string_buffer, pos);
|
||||||
|
}
|
||||||
|
|
||||||
|
void update_vtx_channel(bool increase, uint8_t col) {
|
||||||
|
(void)col;
|
||||||
|
if (increase) {
|
||||||
|
if ((current_vtx_channel % 8) < 7)
|
||||||
|
current_vtx_channel++;
|
||||||
|
} else {
|
||||||
|
if ((current_vtx_channel % 8) > 0)
|
||||||
|
current_vtx_channel--;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void print_vtx_channel(uint16_t pos, uint8_t col) {
|
||||||
|
(void)col;
|
||||||
|
sprintf(string_buffer, "%d", current_vtx_channel % 8 + 1);
|
||||||
|
max7456_write_string(string_buffer, pos);
|
||||||
|
}
|
||||||
|
|
||||||
|
void print_vtx_freq(uint16_t pos, uint8_t col) {
|
||||||
|
(void)col;
|
||||||
|
sprintf(string_buffer, "%d M", vtx_freq[current_vtx_channel]);
|
||||||
|
max7456_write_string(string_buffer, pos);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
void print_pid(uint16_t pos, uint8_t col, int pid_term) {
|
||||||
|
switch(col) {
|
||||||
|
case 0:
|
||||||
|
if (IS_PID_CONTROLLER_FP_BASED(currentProfile->pidProfile.pidController))
|
||||||
|
sprintf(string_buffer, "%d", (int)(currentProfile->pidProfile.P_f[pid_term] * 10.0));
|
||||||
|
else
|
||||||
|
sprintf(string_buffer, "%d", currentProfile->pidProfile.P8[pid_term]);
|
||||||
|
break;
|
||||||
|
case 1:
|
||||||
|
if (IS_PID_CONTROLLER_FP_BASED(currentProfile->pidProfile.pidController))
|
||||||
|
sprintf(string_buffer, "%d", (int)(currentProfile->pidProfile.I_f[pid_term] * 100.0));
|
||||||
|
else
|
||||||
|
sprintf(string_buffer, "%d", currentProfile->pidProfile.I8[pid_term]);
|
||||||
|
break;
|
||||||
|
case 2:
|
||||||
|
if (IS_PID_CONTROLLER_FP_BASED(currentProfile->pidProfile.pidController))
|
||||||
|
sprintf(string_buffer, "%d", (int)(currentProfile->pidProfile.D_f[pid_term] * 1000.0));
|
||||||
|
else
|
||||||
|
sprintf(string_buffer, "%d", currentProfile->pidProfile.D8[pid_term]);
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
max7456_write_string(string_buffer, pos);
|
||||||
|
}
|
||||||
|
|
||||||
|
void print_roll_pid(uint16_t pos, uint8_t col) {
|
||||||
|
print_pid(pos, col, ROLL);
|
||||||
|
}
|
||||||
|
|
||||||
|
void print_pitch_pid(uint16_t pos, uint8_t col) {
|
||||||
|
print_pid(pos, col, PITCH);
|
||||||
|
}
|
||||||
|
|
||||||
|
void print_yaw_pid(uint16_t pos, uint8_t col) {
|
||||||
|
print_pid(pos, col, YAW);
|
||||||
|
}
|
||||||
|
|
||||||
|
void print_roll_rate(uint16_t pos, uint8_t col) {
|
||||||
|
if (col == 0) {
|
||||||
|
sprintf(string_buffer, "%d", currentControlRateProfile->rates[FD_ROLL]);
|
||||||
|
max7456_write_string(string_buffer, pos);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void print_pitch_rate(uint16_t pos, uint8_t col) {
|
||||||
|
if (col == 0) {
|
||||||
|
sprintf(string_buffer, "%d", currentControlRateProfile->rates[FD_PITCH]);
|
||||||
|
max7456_write_string(string_buffer, pos);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void print_yaw_rate(uint16_t pos, uint8_t col) {
|
||||||
|
if (col == 0) {
|
||||||
|
sprintf(string_buffer, "%d", currentControlRateProfile->rates[FD_YAW]);
|
||||||
|
max7456_write_string(string_buffer, pos);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void update_int_pid(bool inc, uint8_t col, int pid_term) {
|
||||||
|
void* ptr;
|
||||||
|
switch(col) {
|
||||||
|
case 0:
|
||||||
|
ptr = ¤tProfile->pidProfile.P8[pid_term];
|
||||||
|
break;
|
||||||
|
case 1:
|
||||||
|
ptr = ¤tProfile->pidProfile.I8[pid_term];
|
||||||
|
break;
|
||||||
|
case 2:
|
||||||
|
ptr = ¤tProfile->pidProfile.D8[pid_term];
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (inc) {
|
||||||
|
if (*(uint8_t*)ptr < 200)
|
||||||
|
*(uint8_t*)ptr += 1;
|
||||||
|
} else {
|
||||||
|
if (*(uint8_t*)ptr > 0)
|
||||||
|
*(uint8_t*)ptr -= 1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void update_float_pid(bool inc, uint8_t col, int pid_term) {
|
||||||
|
void* ptr;
|
||||||
|
float diff;
|
||||||
|
|
||||||
|
switch(col) {
|
||||||
|
case 0:
|
||||||
|
ptr = ¤tProfile->pidProfile.P_f[pid_term];
|
||||||
|
diff = 0.1;
|
||||||
|
break;
|
||||||
|
case 1:
|
||||||
|
ptr = ¤tProfile->pidProfile.I_f[pid_term];
|
||||||
|
diff = 0.01;
|
||||||
|
break;
|
||||||
|
case 2:
|
||||||
|
ptr = ¤tProfile->pidProfile.D_f[pid_term];
|
||||||
|
diff = 0.001;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (inc) {
|
||||||
|
if (*(float*)ptr < 100.0)
|
||||||
|
*(float*)ptr += diff;
|
||||||
|
} else {
|
||||||
|
if (*(float*)ptr > 0.0)
|
||||||
|
*(float*)ptr -= diff;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void update_roll_pid(bool inc, uint8_t col) {
|
||||||
|
if (IS_PID_CONTROLLER_FP_BASED(currentProfile->pidProfile.pidController))
|
||||||
|
update_float_pid(inc, col, ROLL);
|
||||||
|
else
|
||||||
|
update_int_pid(inc, col, ROLL);
|
||||||
|
}
|
||||||
|
|
||||||
|
void update_pitch_pid(bool inc, uint8_t col) {
|
||||||
|
if (IS_PID_CONTROLLER_FP_BASED(currentProfile->pidProfile.pidController))
|
||||||
|
update_float_pid(inc, col, PITCH);
|
||||||
|
else
|
||||||
|
update_int_pid(inc, col, PITCH);
|
||||||
|
}
|
||||||
|
|
||||||
|
void update_yaw_pid(bool inc, uint8_t col) {
|
||||||
|
if (IS_PID_CONTROLLER_FP_BASED(currentProfile->pidProfile.pidController))
|
||||||
|
update_float_pid(inc, col, YAW);
|
||||||
|
else
|
||||||
|
update_int_pid(inc, col, YAW);
|
||||||
|
}
|
||||||
|
|
||||||
|
void update_roll_rate(bool inc, uint8_t col) {
|
||||||
|
(void)col;
|
||||||
|
if (inc) {
|
||||||
|
if (currentControlRateProfile->rates[FD_ROLL] < CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX)
|
||||||
|
currentControlRateProfile->rates[FD_ROLL]++;
|
||||||
|
} else {
|
||||||
|
if (currentControlRateProfile->rates[FD_ROLL] > 0)
|
||||||
|
currentControlRateProfile->rates[FD_ROLL]--;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void update_pitch_rate(bool increase, uint8_t col) {
|
||||||
|
(void)col;
|
||||||
|
if (increase) {
|
||||||
|
if (currentControlRateProfile->rates[FD_PITCH] < CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX)
|
||||||
|
currentControlRateProfile->rates[FD_PITCH]++;
|
||||||
|
} else {
|
||||||
|
if (currentControlRateProfile->rates[FD_PITCH] > 0)
|
||||||
|
currentControlRateProfile->rates[FD_PITCH]--;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void update_yaw_rate(bool increase, uint8_t col) {
|
||||||
|
(void)col;
|
||||||
|
if (increase) {
|
||||||
|
if (currentControlRateProfile->rates[FD_YAW] < CONTROL_RATE_CONFIG_YAW_RATE_MAX)
|
||||||
|
currentControlRateProfile->rates[FD_YAW]++;
|
||||||
|
} else {
|
||||||
|
if (currentControlRateProfile->rates[FD_YAW] > 0)
|
||||||
|
currentControlRateProfile->rates[FD_YAW]--;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void print_average_system_load(uint16_t pos, uint8_t col) {
|
||||||
|
(void)col;
|
||||||
|
sprintf(string_buffer, "%d", averageSystemLoadPercent);
|
||||||
|
max7456_write_string(string_buffer, pos);
|
||||||
|
}
|
||||||
|
|
||||||
|
void print_batt_voltage(uint16_t pos, uint8_t col) {
|
||||||
|
(void)col;
|
||||||
|
sprintf(string_buffer, "%d.%1d", vbat / 10, vbat % 10);
|
||||||
|
max7456_write_string(string_buffer, pos);
|
||||||
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
TODO: add this to menu
|
||||||
|
{ "rc_rate", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].rcRate8, .config.minmax = { 0, 250 } },
|
||||||
|
{ "rc_expo", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].rcExpo8, .config.minmax = { 0, 100 } },
|
||||||
|
{ "rc_yaw_expo", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].rcYawExpo8, .config.minmax = { 0, 100 } },
|
||||||
|
{ "thr_mid", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].thrMid8, .config.minmax = { 0, 100 } },
|
||||||
|
{ "thr_expo", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].thrExpo8, .config.minmax = { 0, 100 } },
|
||||||
|
{ "tpa_rate", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].dynThrPID, .config.minmax = { 0, CONTROL_RATE_CONFIG_TPA_MAX} },
|
||||||
|
{ "tpa_breakpoint", VAR_UINT16 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].tpa_breakpoint, .config.minmax = { PWM_RANGE_MIN, PWM_RANGE_MAX} },
|
||||||
|
{ "acro_plus_factor", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.acroPlusFactor, .config.minmax = {1, 100 } },
|
||||||
|
{ "acro_plus_offset", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.acroPlusOffset, .config.minmax = {1, 90 } },
|
||||||
|
*/
|
||||||
|
|
||||||
|
page_t menu_pages[] = {
|
||||||
|
{
|
||||||
|
.title = "STATUS",
|
||||||
|
.cols_number = 1,
|
||||||
|
.rows_number = 2,
|
||||||
|
.cols = {
|
||||||
|
{
|
||||||
|
.title = NULL,
|
||||||
|
.x_pos = 15
|
||||||
|
}
|
||||||
|
},
|
||||||
|
.rows = {
|
||||||
|
{
|
||||||
|
.title = "AVG LOAD",
|
||||||
|
.y_pos = 0,
|
||||||
|
.update = NULL,
|
||||||
|
.print = print_average_system_load
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.title = "BATT",
|
||||||
|
.y_pos = 1,
|
||||||
|
.update = NULL,
|
||||||
|
.print = print_batt_voltage
|
||||||
|
},
|
||||||
|
}
|
||||||
|
},
|
||||||
|
#ifdef USE_RTC6705
|
||||||
|
{
|
||||||
|
.title = "VTX SETTINGS",
|
||||||
|
.cols_number = 1,
|
||||||
|
.rows_number = 3,
|
||||||
|
.cols = {
|
||||||
|
{
|
||||||
|
.title = NULL,
|
||||||
|
.x_pos = 15
|
||||||
|
}
|
||||||
|
},
|
||||||
|
.rows = {
|
||||||
|
{
|
||||||
|
.title = "BAND",
|
||||||
|
.y_pos = 0,
|
||||||
|
.update = update_vtx_band,
|
||||||
|
.print = print_vtx_band
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.title = "CHANNEL",
|
||||||
|
.y_pos = 1,
|
||||||
|
.update = update_vtx_channel,
|
||||||
|
.print = print_vtx_channel
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.title = "FREQUENCY",
|
||||||
|
.y_pos = 2,
|
||||||
|
.update = NULL,
|
||||||
|
.print = print_vtx_freq
|
||||||
|
}
|
||||||
|
}
|
||||||
|
},
|
||||||
|
#endif
|
||||||
|
{
|
||||||
|
.title = "PID SETTINGS",
|
||||||
|
.cols_number = 3,
|
||||||
|
.rows_number = 6,
|
||||||
|
.cols = {
|
||||||
|
{
|
||||||
|
.title = "P",
|
||||||
|
.x_pos = 13
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.title = "I",
|
||||||
|
.x_pos = 19
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.title = "D",
|
||||||
|
.x_pos = 25
|
||||||
|
}
|
||||||
|
},
|
||||||
|
.rows = {
|
||||||
|
{
|
||||||
|
.title = "ROLL",
|
||||||
|
.y_pos = 0,
|
||||||
|
.update = update_roll_pid,
|
||||||
|
.print = print_roll_pid
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.title = "PITCH",
|
||||||
|
.y_pos = 1,
|
||||||
|
.update = update_pitch_pid,
|
||||||
|
.print = print_pitch_pid
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.title = "YAW",
|
||||||
|
.y_pos = 2,
|
||||||
|
.update = update_yaw_pid,
|
||||||
|
.print = print_yaw_pid
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.title = "ROLL_RATE",
|
||||||
|
.y_pos = 3,
|
||||||
|
.update = update_roll_rate,
|
||||||
|
.print = print_roll_rate
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.title = "PITCH_RATE",
|
||||||
|
.y_pos = 4,
|
||||||
|
.update = update_pitch_rate,
|
||||||
|
.print = print_pitch_rate
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.title = "YAW_RATE",
|
||||||
|
.y_pos = 5,
|
||||||
|
.update = update_yaw_rate,
|
||||||
|
.print = print_yaw_rate
|
||||||
|
},
|
||||||
|
}
|
||||||
|
},
|
||||||
|
};
|
||||||
|
|
||||||
|
void show_menu(void) {
|
||||||
|
uint8_t line = 1;
|
||||||
|
uint16_t pos;
|
||||||
|
col_t *col;
|
||||||
|
row_t *row;
|
||||||
|
uint16_t cursor_x, cursor_y;
|
||||||
|
|
||||||
|
sprintf(string_buffer, "EXIT SAVE+EXIT PAGE");
|
||||||
|
max7456_write_string(string_buffer, 12 * OSD_LINE_LENGTH + 1);
|
||||||
|
|
||||||
|
pos = (OSD_LINE_LENGTH - strlen(menu_pages[current_page].title)) / 2 + line * OSD_LINE_LENGTH;
|
||||||
|
sprintf(string_buffer, "%s", menu_pages[current_page].title);
|
||||||
|
max7456_write_string(string_buffer, pos);
|
||||||
|
|
||||||
|
line += 2;
|
||||||
|
|
||||||
|
for (int i = 0; i < menu_pages[current_page].cols_number; i++){
|
||||||
|
col = &menu_pages[current_page].cols[i];
|
||||||
|
if (cursor_col == i)
|
||||||
|
cursor_x = col->x_pos - 1;
|
||||||
|
|
||||||
|
if (col->title) {
|
||||||
|
sprintf(string_buffer, "%s", col->title);
|
||||||
|
max7456_write_string(string_buffer, line * OSD_LINE_LENGTH + col->x_pos);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
line++;
|
||||||
|
for (int i = 0; i < menu_pages[current_page].rows_number; i++) {
|
||||||
|
row = &menu_pages[current_page].rows[i];
|
||||||
|
if (cursor_row == i)
|
||||||
|
cursor_y = line + row->y_pos;
|
||||||
|
|
||||||
|
sprintf(string_buffer, "%s", row->title);
|
||||||
|
max7456_write_string(string_buffer, (line + row->y_pos) * OSD_LINE_LENGTH + 1);
|
||||||
|
for (int j = 0; j < menu_pages[current_page].cols_number; j++) {
|
||||||
|
col = &menu_pages[current_page].cols[j];
|
||||||
|
row->print((line + row->y_pos) * OSD_LINE_LENGTH + col->x_pos, j);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (sticks[YAW] > 90) {
|
||||||
|
if (cursor_row > MAX_MENU_ROWS) {
|
||||||
|
switch(cursor_col) {
|
||||||
|
case 0:
|
||||||
|
in_menu = false;
|
||||||
|
break;
|
||||||
|
case 1:
|
||||||
|
in_menu = false;
|
||||||
|
#ifdef USE_RTC6705
|
||||||
|
if (masterConfig.vtx_channel != current_vtx_channel) {
|
||||||
|
masterConfig.vtx_channel = current_vtx_channel;
|
||||||
|
rtc6705_set_channel(vtx_freq[current_vtx_channel]);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
writeEEPROM();
|
||||||
|
break;
|
||||||
|
case 2:
|
||||||
|
if (current_page < (sizeof(menu_pages) / sizeof(page_t) - 1))
|
||||||
|
current_page++;
|
||||||
|
else
|
||||||
|
current_page = 0;
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
if (menu_pages[current_page].rows[cursor_row].update)
|
||||||
|
menu_pages[current_page].rows[cursor_row].update(true, cursor_col);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (sticks[YAW] < 10) {
|
||||||
|
if (cursor_row > MAX_MENU_ROWS) {
|
||||||
|
if (cursor_col == 2 && current_page > 0) {
|
||||||
|
current_page--;
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
if (menu_pages[current_page].rows[cursor_row].update)
|
||||||
|
menu_pages[current_page].rows[cursor_row].update(false, cursor_col);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (sticks[PITCH] > 90) {
|
||||||
|
if (cursor_row > MAX_MENU_ROWS) {
|
||||||
|
cursor_row = menu_pages[current_page].rows_number - 1;
|
||||||
|
cursor_col = 0;
|
||||||
|
} else {
|
||||||
|
if (cursor_row > 0)
|
||||||
|
cursor_row--;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
if (sticks[PITCH] < 10) {
|
||||||
|
if (cursor_row < (menu_pages[current_page].rows_number - 1))
|
||||||
|
cursor_row++;
|
||||||
|
else
|
||||||
|
cursor_row = 255;
|
||||||
|
}
|
||||||
|
if (sticks[ROLL] > 90) {
|
||||||
|
if (cursor_row > MAX_MENU_ROWS) {
|
||||||
|
if (cursor_col < 2)
|
||||||
|
cursor_col++;
|
||||||
|
} else {
|
||||||
|
if (cursor_col < (menu_pages[current_page].cols_number - 1))
|
||||||
|
cursor_col++;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
if (sticks[ROLL] < 10) {
|
||||||
|
if (cursor_col > 0)
|
||||||
|
cursor_col--;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (cursor_row > MAX_MENU_ROWS) {
|
||||||
|
cursor_row = 255;
|
||||||
|
cursor_y = 12;
|
||||||
|
switch(cursor_col) {
|
||||||
|
case 0:
|
||||||
|
cursor_x = 0;
|
||||||
|
break;
|
||||||
|
case 1:
|
||||||
|
cursor_x = 9;
|
||||||
|
break;
|
||||||
|
case 2:
|
||||||
|
cursor_x = 23;
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
cursor_x = 0;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
max7456_write_string(">", cursor_x + cursor_y * OSD_LINE_LENGTH);
|
||||||
|
}
|
||||||
|
|
||||||
|
void updateOsd(void)
|
||||||
|
{
|
||||||
|
uint32_t seconds;
|
||||||
|
char line[30];
|
||||||
|
uint32_t now = micros();
|
||||||
|
|
||||||
|
bool updateNow = (int32_t)(now - next_osd_update_at) >= 0L;
|
||||||
|
if (!updateNow) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
next_osd_update_at = now + OSD_UPDATE_FREQUENCY;
|
||||||
|
if ((now / 1000000) & 1) {
|
||||||
|
if (ARMING_FLAG(ARMED)) {
|
||||||
|
if (!armed) {
|
||||||
|
armed = true;
|
||||||
|
armed_at = now;
|
||||||
|
in_menu = false;
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
if (armed) {
|
||||||
|
armed = false;
|
||||||
|
armed_seconds += (now - armed_at) / 1000000;
|
||||||
|
}
|
||||||
|
for (uint8_t channelIndex = 0; channelIndex < 4; channelIndex++) {
|
||||||
|
sticks[channelIndex] = (constrain(rcData[channelIndex], PWM_RANGE_MIN, PWM_RANGE_MAX) - PWM_RANGE_MIN) * 100 / (PWM_RANGE_MAX - PWM_RANGE_MIN);
|
||||||
|
}
|
||||||
|
if (!in_menu && sticks[YAW] > 90 && sticks[THROTTLE] > 90 && sticks[ROLL] < 10 && sticks[PITCH] > 90) {
|
||||||
|
in_menu = true;
|
||||||
|
cursor_row = 255;
|
||||||
|
cursor_col = 2;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
if (in_menu) {
|
||||||
|
show_menu();
|
||||||
|
} else {
|
||||||
|
sprintf(line, "\x97%d.%1d", vbat / 10, vbat % 10);
|
||||||
|
max7456_write_string(line, 361);
|
||||||
|
sprintf(line, "\x7e%3d", (constrain(rcData[THROTTLE], PWM_RANGE_MIN, PWM_RANGE_MAX) - PWM_RANGE_MIN) * 100 / (PWM_RANGE_MAX - PWM_RANGE_MIN));
|
||||||
|
max7456_write_string(line, 381);
|
||||||
|
seconds = (now - armed_at) / 1000000 + armed_seconds;
|
||||||
|
sprintf(line, "\x9C %02d:%02d", seconds / 60, seconds % 60);
|
||||||
|
max7456_write_string(line, 351);
|
||||||
|
print_average_system_load(26, 0);
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
max7456_draw_screen_fast();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
void osdInit(void)
|
||||||
|
{
|
||||||
|
#ifdef USE_RTC6705
|
||||||
|
rtc6705_init();
|
||||||
|
current_vtx_channel = masterConfig.vtx_channel;
|
||||||
|
rtc6705_set_channel(vtx_freq[current_vtx_channel]);
|
||||||
|
#endif
|
||||||
|
max7456_init();
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif
|
42
src/main/io/osd.h
Normal file
42
src/main/io/osd.h
Normal file
|
@ -0,0 +1,42 @@
|
||||||
|
/*
|
||||||
|
* 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 <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#define MAX_MENU_ROWS 8
|
||||||
|
#define MAX_MENU_COLS 3
|
||||||
|
|
||||||
|
typedef struct {
|
||||||
|
const char* title;
|
||||||
|
uint8_t x_pos;
|
||||||
|
} col_t;
|
||||||
|
|
||||||
|
typedef struct {
|
||||||
|
const char* title;
|
||||||
|
uint8_t y_pos;
|
||||||
|
void (*update)(bool increase, uint8_t col);
|
||||||
|
void (*print)(uint16_t pos, uint8_t col);
|
||||||
|
} row_t;
|
||||||
|
|
||||||
|
typedef struct {
|
||||||
|
const char* title;
|
||||||
|
uint8_t cols_number;
|
||||||
|
uint8_t rows_number;
|
||||||
|
col_t cols[MAX_MENU_COLS];
|
||||||
|
row_t rows[MAX_MENU_ROWS];
|
||||||
|
} page_t;
|
||||||
|
|
||||||
|
void updateOsd(void);
|
||||||
|
void osdInit(void);
|
|
@ -768,6 +768,9 @@ const clivalue_t valueTable[] = {
|
||||||
{ "magzero_x", VAR_INT16 | MASTER_VALUE, &masterConfig.magZero.raw[X], .config.minmax = { -32768, 32767 } },
|
{ "magzero_x", VAR_INT16 | MASTER_VALUE, &masterConfig.magZero.raw[X], .config.minmax = { -32768, 32767 } },
|
||||||
{ "magzero_y", VAR_INT16 | MASTER_VALUE, &masterConfig.magZero.raw[Y], .config.minmax = { -32768, 32767 } },
|
{ "magzero_y", VAR_INT16 | MASTER_VALUE, &masterConfig.magZero.raw[Y], .config.minmax = { -32768, 32767 } },
|
||||||
{ "magzero_z", VAR_INT16 | MASTER_VALUE, &masterConfig.magZero.raw[Z], .config.minmax = { -32768, 32767 } },
|
{ "magzero_z", VAR_INT16 | MASTER_VALUE, &masterConfig.magZero.raw[Z], .config.minmax = { -32768, 32767 } },
|
||||||
|
#ifdef USE_RTC6705
|
||||||
|
{ "vtx_channel", VAR_INT16 | MASTER_VALUE, &masterConfig.vtx_channel, .config.minmax = { 0, 39 } },
|
||||||
|
#endif
|
||||||
};
|
};
|
||||||
|
|
||||||
#define VALUE_COUNT (sizeof(valueTable) / sizeof(clivalue_t))
|
#define VALUE_COUNT (sizeof(valueTable) / sizeof(clivalue_t))
|
||||||
|
|
|
@ -44,6 +44,8 @@
|
||||||
#include "drivers/gyro_sync.h"
|
#include "drivers/gyro_sync.h"
|
||||||
#include "drivers/sdcard.h"
|
#include "drivers/sdcard.h"
|
||||||
#include "drivers/buf_writer.h"
|
#include "drivers/buf_writer.h"
|
||||||
|
#include "drivers/max7456.h"
|
||||||
|
#include "drivers/rtc6705.h"
|
||||||
#include "rx/rx.h"
|
#include "rx/rx.h"
|
||||||
#include "rx/msp.h"
|
#include "rx/msp.h"
|
||||||
|
|
||||||
|
@ -1279,7 +1281,9 @@ static bool processInCommand(void)
|
||||||
uint8_t wp_no;
|
uint8_t wp_no;
|
||||||
int32_t lat = 0, lon = 0, alt = 0;
|
int32_t lat = 0, lon = 0, alt = 0;
|
||||||
#endif
|
#endif
|
||||||
|
#ifdef OSD
|
||||||
|
uint8_t addr, font_data[64];
|
||||||
|
#endif
|
||||||
switch (currentPort->cmdMSP) {
|
switch (currentPort->cmdMSP) {
|
||||||
case MSP_SELECT_SETTING:
|
case MSP_SELECT_SETTING:
|
||||||
if (!ARMING_FLAG(ARMED)) {
|
if (!ARMING_FLAG(ARMED)) {
|
||||||
|
@ -1559,6 +1563,29 @@ static bool processInCommand(void)
|
||||||
transponderUpdateData(masterConfig.transponderData);
|
transponderUpdateData(masterConfig.transponderData);
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
#ifdef OSD
|
||||||
|
case MSP_SET_OSD_CONFIG:
|
||||||
|
break;
|
||||||
|
case MSP_OSD_CHAR_WRITE:
|
||||||
|
addr = read8();
|
||||||
|
for (i = 0; i < 54; i++) {
|
||||||
|
font_data[i] = read8();
|
||||||
|
}
|
||||||
|
max7456_write_nvm(addr, font_data);
|
||||||
|
break;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_RTC6705
|
||||||
|
case MSP_SET_VTX_CONFIG:
|
||||||
|
tmp = read16();
|
||||||
|
if (tmp < 40)
|
||||||
|
masterConfig.vtx_channel = tmp;
|
||||||
|
if (current_vtx_channel != masterConfig.vtx_channel) {
|
||||||
|
current_vtx_channel = masterConfig.vtx_channel;
|
||||||
|
rtc6705_set_channel(vtx_freq[current_vtx_channel]);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifdef USE_FLASHFS
|
#ifdef USE_FLASHFS
|
||||||
case MSP_DATAFLASH_ERASE:
|
case MSP_DATAFLASH_ERASE:
|
||||||
|
|
|
@ -168,6 +168,15 @@ static const char * const boardIdentifier = TARGET_BOARD_IDENTIFIER;
|
||||||
#define MSP_TRANSPONDER_CONFIG 82 //in message Get transponder settings
|
#define MSP_TRANSPONDER_CONFIG 82 //in message Get transponder settings
|
||||||
#define MSP_SET_TRANSPONDER_CONFIG 83 //out message Set transponder settings
|
#define MSP_SET_TRANSPONDER_CONFIG 83 //out message Set transponder settings
|
||||||
|
|
||||||
|
#define MSP_OSD_CONFIG 84 //in message Get osd settings
|
||||||
|
#define MSP_SET_OSD_CONFIG 85 //out message Set osd settings
|
||||||
|
|
||||||
|
#define MSP_OSD_CHAR_READ 86 //in message Get osd settings
|
||||||
|
#define MSP_OSD_CHAR_WRITE 87 //out message Set osd settings
|
||||||
|
|
||||||
|
#define MSP_VTX_CONFIG 88 //in message Get vtx settings
|
||||||
|
#define MSP_SET_VTX_CONFIG 89 //out message Set vtx settings
|
||||||
|
|
||||||
//
|
//
|
||||||
// Baseflight MSP commands (if enabled they exist in Cleanflight)
|
// Baseflight MSP commands (if enabled they exist in Cleanflight)
|
||||||
//
|
//
|
||||||
|
|
|
@ -131,6 +131,7 @@ void spektrumBind(rxConfig_t *rxConfig);
|
||||||
const sonarHardware_t *sonarGetHardwareConfiguration(batteryConfig_t *batteryConfig);
|
const sonarHardware_t *sonarGetHardwareConfiguration(batteryConfig_t *batteryConfig);
|
||||||
void sonarInit(const sonarHardware_t *sonarHardware);
|
void sonarInit(const sonarHardware_t *sonarHardware);
|
||||||
void transponderInit(uint8_t* transponderCode);
|
void transponderInit(uint8_t* transponderCode);
|
||||||
|
void osdInit(void);
|
||||||
//void usbCableDetectInit(void);
|
//void usbCableDetectInit(void);
|
||||||
|
|
||||||
#ifdef STM32F303xC
|
#ifdef STM32F303xC
|
||||||
|
@ -464,6 +465,12 @@ void init(void)
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifdef OSD
|
||||||
|
if (feature(FEATURE_OSD)) {
|
||||||
|
osdInit();
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
if (!sensorsAutodetect(&masterConfig.sensorAlignmentConfig,masterConfig.acc_hardware, masterConfig.mag_hardware, masterConfig.baro_hardware, masterConfig.mag_declination, masterConfig.gyro_lpf, masterConfig.gyro_sync_denom)) {
|
if (!sensorsAutodetect(&masterConfig.sensorAlignmentConfig,masterConfig.acc_hardware, masterConfig.mag_hardware, masterConfig.baro_hardware, masterConfig.mag_declination, masterConfig.gyro_lpf, masterConfig.gyro_sync_denom)) {
|
||||||
// if gyro was not detected due to whatever reason, we give up now.
|
// if gyro was not detected due to whatever reason, we give up now.
|
||||||
failureMode(FAILURE_MISSING_ACC);
|
failureMode(FAILURE_MISSING_ACC);
|
||||||
|
@ -724,6 +731,9 @@ int main(void) {
|
||||||
#ifdef TRANSPONDER
|
#ifdef TRANSPONDER
|
||||||
setTaskEnabled(TASK_TRANSPONDER, feature(FEATURE_TRANSPONDER));
|
setTaskEnabled(TASK_TRANSPONDER, feature(FEATURE_TRANSPONDER));
|
||||||
#endif
|
#endif
|
||||||
|
#ifdef OSD
|
||||||
|
setTaskEnabled(TASK_OSD, feature(FEATURE_OSD));
|
||||||
|
#endif
|
||||||
#ifdef USE_BST
|
#ifdef USE_BST
|
||||||
setTaskEnabled(TASK_BST_READ_WRITE, true);
|
setTaskEnabled(TASK_BST_READ_WRITE, true);
|
||||||
setTaskEnabled(TASK_BST_MASTER_PROCESS, true);
|
setTaskEnabled(TASK_BST_MASTER_PROCESS, true);
|
||||||
|
|
|
@ -65,6 +65,7 @@
|
||||||
#include "io/statusindicator.h"
|
#include "io/statusindicator.h"
|
||||||
#include "io/asyncfatfs/asyncfatfs.h"
|
#include "io/asyncfatfs/asyncfatfs.h"
|
||||||
#include "io/transponder_ir.h"
|
#include "io/transponder_ir.h"
|
||||||
|
#include "io/osd.h"
|
||||||
|
|
||||||
|
|
||||||
#include "rx/rx.h"
|
#include "rx/rx.h"
|
||||||
|
@ -966,3 +967,12 @@ void taskTransponder(void)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifdef OSD
|
||||||
|
void taskUpdateOsd(void)
|
||||||
|
{
|
||||||
|
if (feature(FEATURE_OSD)) {
|
||||||
|
updateOsd();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
|
@ -79,7 +79,9 @@ typedef enum {
|
||||||
#ifdef TRANSPONDER
|
#ifdef TRANSPONDER
|
||||||
TASK_TRANSPONDER,
|
TASK_TRANSPONDER,
|
||||||
#endif
|
#endif
|
||||||
|
#ifdef OSD
|
||||||
|
TASK_OSD,
|
||||||
|
#endif
|
||||||
#ifdef USE_BST
|
#ifdef USE_BST
|
||||||
TASK_BST_READ_WRITE,
|
TASK_BST_READ_WRITE,
|
||||||
TASK_BST_MASTER_PROCESS,
|
TASK_BST_MASTER_PROCESS,
|
||||||
|
|
|
@ -40,6 +40,9 @@ void taskTelemetry(void);
|
||||||
void taskLedStrip(void);
|
void taskLedStrip(void);
|
||||||
void taskTransponder(void);
|
void taskTransponder(void);
|
||||||
void taskSystem(void);
|
void taskSystem(void);
|
||||||
|
#ifdef OSD
|
||||||
|
void taskUpdateOsd(void);
|
||||||
|
#endif
|
||||||
#ifdef USE_BST
|
#ifdef USE_BST
|
||||||
void taskBstReadWrite(void);
|
void taskBstReadWrite(void);
|
||||||
void taskBstMasterProcess(void);
|
void taskBstMasterProcess(void);
|
||||||
|
@ -168,7 +171,14 @@ cfTask_t cfTasks[TASK_COUNT] = {
|
||||||
.staticPriority = TASK_PRIORITY_LOW,
|
.staticPriority = TASK_PRIORITY_LOW,
|
||||||
},
|
},
|
||||||
#endif
|
#endif
|
||||||
|
#ifdef OSD
|
||||||
|
[TASK_OSD] = {
|
||||||
|
.taskName = "OSD",
|
||||||
|
.taskFunc = taskUpdateOsd,
|
||||||
|
.desiredPeriod = 1000000 / 60, // 60 Hz
|
||||||
|
.staticPriority = TASK_PRIORITY_LOW,
|
||||||
|
},
|
||||||
|
#endif
|
||||||
#ifdef TELEMETRY
|
#ifdef TELEMETRY
|
||||||
[TASK_TELEMETRY] = {
|
[TASK_TELEMETRY] = {
|
||||||
.taskName = "TELEMETRY",
|
.taskName = "TELEMETRY",
|
||||||
|
|
|
@ -130,6 +130,19 @@ const extiConfig_t *selectMPUIntExtiConfig(void)
|
||||||
return &spRacingF3MPUIntExtiConfig;
|
return &spRacingF3MPUIntExtiConfig;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if defined(SIRINFPV)
|
||||||
|
static const extiConfig_t fpvRacerMPUIntExtiConfig = {
|
||||||
|
.gpioAHBPeripherals = RCC_AHBPeriph_GPIOA,
|
||||||
|
.gpioPort = GPIOA,
|
||||||
|
.gpioPin = Pin_8,
|
||||||
|
.exti_port_source = EXTI_PortSourceGPIOA,
|
||||||
|
.exti_pin_source = EXTI_PinSource8,
|
||||||
|
.exti_line = EXTI_Line8,
|
||||||
|
.exti_irqn = EXTI15_10_IRQn
|
||||||
|
};
|
||||||
|
return &fpvRacerMPUIntExtiConfig;
|
||||||
|
#endif
|
||||||
|
|
||||||
#if defined(CC3D)
|
#if defined(CC3D)
|
||||||
static const extiConfig_t cc3dMPUIntExtiConfig = {
|
static const extiConfig_t cc3dMPUIntExtiConfig = {
|
||||||
.gpioAPB2Peripherals = RCC_APB2Periph_GPIOA,
|
.gpioAPB2Peripherals = RCC_APB2Periph_GPIOA,
|
||||||
|
|
371
src/main/target/FPVRACER/system_stm32f30x.c
Normal file
371
src/main/target/FPVRACER/system_stm32f30x.c
Normal file
|
@ -0,0 +1,371 @@
|
||||||
|
/**
|
||||||
|
******************************************************************************
|
||||||
|
* @file system_stm32f30x.c
|
||||||
|
* @author MCD Application Team
|
||||||
|
* @version V1.1.1
|
||||||
|
* @date 28-March-2014
|
||||||
|
* @brief CMSIS Cortex-M4 Device Peripheral Access Layer System Source File.
|
||||||
|
* This file contains the system clock configuration for STM32F30x devices,
|
||||||
|
* and is generated by the clock configuration tool
|
||||||
|
* stm32f30x_Clock_Configuration_V1.0.0.xls
|
||||||
|
*
|
||||||
|
* 1. This file provides two functions and one global variable to be called from
|
||||||
|
* user application:
|
||||||
|
* - SystemInit(): Setups the system clock (System clock source, PLL Multiplier
|
||||||
|
* and Divider factors, AHB/APBx prescalers and Flash settings),
|
||||||
|
* depending on the configuration made in the clock xls tool.
|
||||||
|
* This function is called at startup just after reset and
|
||||||
|
* before branch to main program. This call is made inside
|
||||||
|
* the "startup_stm32f30x.s" file.
|
||||||
|
*
|
||||||
|
* - SystemCoreClock variable: Contains the core clock (HCLK), it can be used
|
||||||
|
* by the user application to setup the SysTick
|
||||||
|
* timer or configure other parameters.
|
||||||
|
*
|
||||||
|
* - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must
|
||||||
|
* be called whenever the core clock is changed
|
||||||
|
* during program execution.
|
||||||
|
*
|
||||||
|
* 2. After each device reset the HSI (8 MHz) is used as system clock source.
|
||||||
|
* Then SystemInit() function is called, in "startup_stm32f30x.s" file, to
|
||||||
|
* configure the system clock before to branch to main program.
|
||||||
|
*
|
||||||
|
* 3. If the system clock source selected by user fails to startup, the SystemInit()
|
||||||
|
* function will do nothing and HSI still used as system clock source. User can
|
||||||
|
* add some code to deal with this issue inside the SetSysClock() function.
|
||||||
|
*
|
||||||
|
* 4. The default value of HSE crystal is set to 8MHz, refer to "HSE_VALUE" define
|
||||||
|
* in "stm32f30x.h" file. When HSE is used as system clock source, directly or
|
||||||
|
* through PLL, and you are using different crystal you have to adapt the HSE
|
||||||
|
* value to your own configuration.
|
||||||
|
*
|
||||||
|
* 5. This file configures the system clock as follows:
|
||||||
|
*=============================================================================
|
||||||
|
* Supported STM32F30x device
|
||||||
|
*-----------------------------------------------------------------------------
|
||||||
|
* System Clock source | PLL (HSE)
|
||||||
|
*-----------------------------------------------------------------------------
|
||||||
|
* SYSCLK(Hz) | 72000000
|
||||||
|
*-----------------------------------------------------------------------------
|
||||||
|
* HCLK(Hz) | 72000000
|
||||||
|
*-----------------------------------------------------------------------------
|
||||||
|
* AHB Prescaler | 1
|
||||||
|
*-----------------------------------------------------------------------------
|
||||||
|
* APB2 Prescaler | 2
|
||||||
|
*-----------------------------------------------------------------------------
|
||||||
|
* APB1 Prescaler | 2
|
||||||
|
*-----------------------------------------------------------------------------
|
||||||
|
* HSE Frequency(Hz) | 8000000
|
||||||
|
*----------------------------------------------------------------------------
|
||||||
|
* PLLMUL | 9
|
||||||
|
*-----------------------------------------------------------------------------
|
||||||
|
* PREDIV | 1
|
||||||
|
*-----------------------------------------------------------------------------
|
||||||
|
* USB Clock | ENABLE
|
||||||
|
*-----------------------------------------------------------------------------
|
||||||
|
* Flash Latency(WS) | 2
|
||||||
|
*-----------------------------------------------------------------------------
|
||||||
|
* Prefetch Buffer | ON
|
||||||
|
*-----------------------------------------------------------------------------
|
||||||
|
*=============================================================================
|
||||||
|
******************************************************************************
|
||||||
|
* @attention
|
||||||
|
*
|
||||||
|
* <h2><center>© COPYRIGHT 2014 STMicroelectronics</center></h2>
|
||||||
|
*
|
||||||
|
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||||
|
* You may not use this file except in compliance with the License.
|
||||||
|
* You may obtain a copy of the License at:
|
||||||
|
*
|
||||||
|
* http://www.st.com/software_license_agreement_liberty_v2
|
||||||
|
*
|
||||||
|
* Unless required by applicable law or agreed to in writing, software
|
||||||
|
* distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
* See the License for the specific language governing permissions and
|
||||||
|
* limitations under the License.
|
||||||
|
*
|
||||||
|
******************************************************************************
|
||||||
|
*/
|
||||||
|
/** @addtogroup CMSIS
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
|
||||||
|
/** @addtogroup stm32f30x_system
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
|
||||||
|
/** @addtogroup STM32F30x_System_Private_Includes
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include "stm32f30x.h"
|
||||||
|
|
||||||
|
uint32_t hse_value = HSE_VALUE;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @}
|
||||||
|
*/
|
||||||
|
|
||||||
|
/* Private typedef -----------------------------------------------------------*/
|
||||||
|
|
||||||
|
/** @addtogroup STM32F30x_System_Private_Defines
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
/*!< Uncomment the following line if you need to relocate your vector Table in
|
||||||
|
Internal SRAM. */
|
||||||
|
/* #define VECT_TAB_SRAM */
|
||||||
|
#define VECT_TAB_OFFSET 0x0 /*!< Vector Table base offset field.
|
||||||
|
This value must be a multiple of 0x200. */
|
||||||
|
/**
|
||||||
|
* @}
|
||||||
|
*/
|
||||||
|
|
||||||
|
/* Private macro -------------------------------------------------------------*/
|
||||||
|
|
||||||
|
/** @addtogroup STM32F30x_System_Private_Variables
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
|
||||||
|
uint32_t SystemCoreClock = 72000000;
|
||||||
|
|
||||||
|
__I uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9};
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @}
|
||||||
|
*/
|
||||||
|
|
||||||
|
/** @addtogroup STM32F30x_System_Private_FunctionPrototypes
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
|
||||||
|
void SetSysClock(void);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @}
|
||||||
|
*/
|
||||||
|
|
||||||
|
/** @addtogroup STM32F30x_System_Private_Functions
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Setup the microcontroller system
|
||||||
|
* Initialize the Embedded Flash Interface, the PLL and update the
|
||||||
|
* SystemFrequency variable.
|
||||||
|
* @param None
|
||||||
|
* @retval None
|
||||||
|
*/
|
||||||
|
void SystemInit(void)
|
||||||
|
{
|
||||||
|
/* FPU settings ------------------------------------------------------------*/
|
||||||
|
#if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
|
||||||
|
SCB->CPACR |= ((3UL << 10*2)|(3UL << 11*2)); /* set CP10 and CP11 Full Access */
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/* Reset the RCC clock configuration to the default reset state ------------*/
|
||||||
|
/* Set HSION bit */
|
||||||
|
RCC->CR |= (uint32_t)0x00000001;
|
||||||
|
|
||||||
|
/* Reset CFGR register */
|
||||||
|
RCC->CFGR &= 0xF87FC00C;
|
||||||
|
|
||||||
|
/* Reset HSEON, CSSON and PLLON bits */
|
||||||
|
RCC->CR &= (uint32_t)0xFEF6FFFF;
|
||||||
|
|
||||||
|
/* Reset HSEBYP bit */
|
||||||
|
RCC->CR &= (uint32_t)0xFFFBFFFF;
|
||||||
|
|
||||||
|
/* Reset PLLSRC, PLLXTPRE, PLLMUL and USBPRE bits */
|
||||||
|
RCC->CFGR &= (uint32_t)0xFF80FFFF;
|
||||||
|
|
||||||
|
/* Reset PREDIV1[3:0] bits */
|
||||||
|
RCC->CFGR2 &= (uint32_t)0xFFFFFFF0;
|
||||||
|
|
||||||
|
/* Reset USARTSW[1:0], I2CSW and TIMs bits */
|
||||||
|
RCC->CFGR3 &= (uint32_t)0xFF00FCCC;
|
||||||
|
|
||||||
|
/* Disable all interrupts */
|
||||||
|
RCC->CIR = 0x00000000;
|
||||||
|
|
||||||
|
/* Configure the System clock source, PLL Multiplier and Divider factors,
|
||||||
|
AHB/APBx prescalers and Flash settings ----------------------------------*/
|
||||||
|
//SetSysClock(); // called from main()
|
||||||
|
|
||||||
|
#ifdef VECT_TAB_SRAM
|
||||||
|
SCB->VTOR = SRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM. */
|
||||||
|
#else
|
||||||
|
SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH. */
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Update SystemCoreClock variable according to Clock Register Values.
|
||||||
|
* The SystemCoreClock variable contains the core clock (HCLK), it can
|
||||||
|
* be used by the user application to setup the SysTick timer or configure
|
||||||
|
* other parameters.
|
||||||
|
*
|
||||||
|
* @note Each time the core clock (HCLK) changes, this function must be called
|
||||||
|
* to update SystemCoreClock variable value. Otherwise, any configuration
|
||||||
|
* based on this variable will be incorrect.
|
||||||
|
*
|
||||||
|
* @note - The system frequency computed by this function is not the real
|
||||||
|
* frequency in the chip. It is calculated based on the predefined
|
||||||
|
* constant and the selected clock source:
|
||||||
|
*
|
||||||
|
* - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*)
|
||||||
|
*
|
||||||
|
* - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**)
|
||||||
|
*
|
||||||
|
* - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**)
|
||||||
|
* or HSI_VALUE(*) multiplied/divided by the PLL factors.
|
||||||
|
*
|
||||||
|
* (*) HSI_VALUE is a constant defined in stm32f30x.h file (default value
|
||||||
|
* 8 MHz) but the real value may vary depending on the variations
|
||||||
|
* in voltage and temperature.
|
||||||
|
*
|
||||||
|
* (**) HSE_VALUE is a constant defined in stm32f30x.h file (default value
|
||||||
|
* 8 MHz), user has to ensure that HSE_VALUE is same as the real
|
||||||
|
* frequency of the crystal used. Otherwise, this function may
|
||||||
|
* have wrong result.
|
||||||
|
*
|
||||||
|
* - The result of this function could be not correct when using fractional
|
||||||
|
* value for HSE crystal.
|
||||||
|
*
|
||||||
|
* @param None
|
||||||
|
* @retval None
|
||||||
|
*/
|
||||||
|
void SystemCoreClockUpdate (void)
|
||||||
|
{
|
||||||
|
uint32_t tmp = 0, pllmull = 0, pllsource = 0, prediv1factor = 0;
|
||||||
|
|
||||||
|
/* Get SYSCLK source -------------------------------------------------------*/
|
||||||
|
tmp = RCC->CFGR & RCC_CFGR_SWS;
|
||||||
|
|
||||||
|
switch (tmp)
|
||||||
|
{
|
||||||
|
case 0x00: /* HSI used as system clock */
|
||||||
|
SystemCoreClock = HSI_VALUE;
|
||||||
|
break;
|
||||||
|
case 0x04: /* HSE used as system clock */
|
||||||
|
SystemCoreClock = HSE_VALUE;
|
||||||
|
break;
|
||||||
|
case 0x08: /* PLL used as system clock */
|
||||||
|
/* Get PLL clock source and multiplication factor ----------------------*/
|
||||||
|
pllmull = RCC->CFGR & RCC_CFGR_PLLMULL;
|
||||||
|
pllsource = RCC->CFGR & RCC_CFGR_PLLSRC;
|
||||||
|
pllmull = ( pllmull >> 18) + 2;
|
||||||
|
|
||||||
|
if (pllsource == 0x00)
|
||||||
|
{
|
||||||
|
/* HSI oscillator clock divided by 2 selected as PLL clock entry */
|
||||||
|
SystemCoreClock = (HSI_VALUE >> 1) * pllmull;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
prediv1factor = (RCC->CFGR2 & RCC_CFGR2_PREDIV1) + 1;
|
||||||
|
/* HSE oscillator clock selected as PREDIV1 clock entry */
|
||||||
|
SystemCoreClock = (HSE_VALUE / prediv1factor) * pllmull;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
default: /* HSI used as system clock */
|
||||||
|
SystemCoreClock = HSI_VALUE;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
/* Compute HCLK clock frequency ----------------*/
|
||||||
|
/* Get HCLK prescaler */
|
||||||
|
tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)];
|
||||||
|
/* HCLK clock frequency */
|
||||||
|
SystemCoreClock >>= tmp;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Configures the System clock source, PLL Multiplier and Divider factors,
|
||||||
|
* AHB/APBx prescalers and Flash settings
|
||||||
|
* @note This function should be called only once the RCC clock configuration
|
||||||
|
* is reset to the default reset state (done in SystemInit() function).
|
||||||
|
* @param None
|
||||||
|
* @retval None
|
||||||
|
*/
|
||||||
|
void SetSysClock(void)
|
||||||
|
{
|
||||||
|
__IO uint32_t StartUpCounter = 0, HSEStatus = 0;
|
||||||
|
|
||||||
|
/******************************************************************************/
|
||||||
|
/* PLL (clocked by HSE) used as System clock source */
|
||||||
|
/******************************************************************************/
|
||||||
|
|
||||||
|
/* SYSCLK, HCLK, PCLK2 and PCLK1 configuration -----------*/
|
||||||
|
/* Enable HSE */
|
||||||
|
RCC->CR |= ((uint32_t)RCC_CR_HSEON);
|
||||||
|
|
||||||
|
/* Wait till HSE is ready and if Time out is reached exit */
|
||||||
|
do
|
||||||
|
{
|
||||||
|
HSEStatus = RCC->CR & RCC_CR_HSERDY;
|
||||||
|
StartUpCounter++;
|
||||||
|
} while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
|
||||||
|
|
||||||
|
if ((RCC->CR & RCC_CR_HSERDY) != RESET)
|
||||||
|
{
|
||||||
|
HSEStatus = (uint32_t)0x01;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
HSEStatus = (uint32_t)0x00;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (HSEStatus == (uint32_t)0x01)
|
||||||
|
{
|
||||||
|
/* Enable Prefetch Buffer and set Flash Latency */
|
||||||
|
FLASH->ACR = FLASH_ACR_PRFTBE | (uint32_t)FLASH_ACR_LATENCY_1;
|
||||||
|
|
||||||
|
/* HCLK = SYSCLK / 1 */
|
||||||
|
RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1;
|
||||||
|
|
||||||
|
/* PCLK2 = HCLK / 1 */
|
||||||
|
RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1;
|
||||||
|
|
||||||
|
/* PCLK1 = HCLK / 2 */
|
||||||
|
RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV2;
|
||||||
|
|
||||||
|
/* PLL configuration */
|
||||||
|
RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLMULL));
|
||||||
|
RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_PREDIV1 | RCC_CFGR_PLLXTPRE_PREDIV1 | RCC_CFGR_PLLMULL9);
|
||||||
|
|
||||||
|
/* Enable PLL */
|
||||||
|
RCC->CR |= RCC_CR_PLLON;
|
||||||
|
|
||||||
|
/* Wait till PLL is ready */
|
||||||
|
while((RCC->CR & RCC_CR_PLLRDY) == 0)
|
||||||
|
{
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Select PLL as system clock source */
|
||||||
|
RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
|
||||||
|
RCC->CFGR |= (uint32_t)RCC_CFGR_SW_PLL;
|
||||||
|
|
||||||
|
/* Wait till PLL is used as system clock source */
|
||||||
|
while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)RCC_CFGR_SWS_PLL)
|
||||||
|
{
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{ /* If HSE fails to start-up, the application will have wrong clock
|
||||||
|
configuration. User can add here some code to deal with this error */
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @}
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @}
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @}
|
||||||
|
*/
|
||||||
|
|
||||||
|
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
76
src/main/target/FPVRACER/system_stm32f30x.h
Normal file
76
src/main/target/FPVRACER/system_stm32f30x.h
Normal file
|
@ -0,0 +1,76 @@
|
||||||
|
/**
|
||||||
|
******************************************************************************
|
||||||
|
* @file system_stm32f30x.h
|
||||||
|
* @author MCD Application Team
|
||||||
|
* @version V1.1.1
|
||||||
|
* @date 28-March-2014
|
||||||
|
* @brief CMSIS Cortex-M4 Device System Source File for STM32F30x devices.
|
||||||
|
******************************************************************************
|
||||||
|
* @attention
|
||||||
|
*
|
||||||
|
* <h2><center>© COPYRIGHT 2014 STMicroelectronics</center></h2>
|
||||||
|
*
|
||||||
|
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
|
||||||
|
* You may not use this file except in compliance with the License.
|
||||||
|
* You may obtain a copy of the License at:
|
||||||
|
*
|
||||||
|
* http://www.st.com/software_license_agreement_liberty_v2
|
||||||
|
*
|
||||||
|
* Unless required by applicable law or agreed to in writing, software
|
||||||
|
* distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
* See the License for the specific language governing permissions and
|
||||||
|
* limitations under the License.
|
||||||
|
*
|
||||||
|
******************************************************************************
|
||||||
|
*/
|
||||||
|
|
||||||
|
/** @addtogroup CMSIS
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
|
||||||
|
/** @addtogroup stm32f30x_system
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Define to prevent recursive inclusion
|
||||||
|
*/
|
||||||
|
#ifndef __SYSTEM_STM32F30X_H
|
||||||
|
#define __SYSTEM_STM32F30X_H
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/* Exported types ------------------------------------------------------------*/
|
||||||
|
extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */
|
||||||
|
/* Exported constants --------------------------------------------------------*/
|
||||||
|
/* Exported macro ------------------------------------------------------------*/
|
||||||
|
/* Exported functions ------------------------------------------------------- */
|
||||||
|
|
||||||
|
/** @addtogroup STM32F30x_System_Exported_Functions
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
|
||||||
|
extern void SystemInit(void);
|
||||||
|
extern void SystemCoreClockUpdate(void);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @}
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif /*__SYSTEM_STM32F30X_H */
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @}
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @}
|
||||||
|
*/
|
||||||
|
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
206
src/main/target/FPVRACER/target.h
Normal file
206
src/main/target/FPVRACER/target.h
Normal file
|
@ -0,0 +1,206 @@
|
||||||
|
/*
|
||||||
|
* 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 <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#define TARGET_BOARD_IDENTIFIER "FPVR"
|
||||||
|
|
||||||
|
#define BEEP_GPIO GPIOA
|
||||||
|
#define BEEP_PIN Pin_1
|
||||||
|
#define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOA
|
||||||
|
|
||||||
|
#define USABLE_TIMER_CHANNEL_COUNT 6
|
||||||
|
|
||||||
|
#define EXTI15_10_CALLBACK_HANDLER_COUNT 2 // MPU_INT, SDCardDetect
|
||||||
|
|
||||||
|
#define USE_MPU_DATA_READY_SIGNAL
|
||||||
|
#define ENSURE_MPU_DATA_READY_IS_LOW
|
||||||
|
|
||||||
|
#define GYRO
|
||||||
|
#define USE_GYRO_SPI_MPU6000
|
||||||
|
//#define USE_GYRO_SPI_MPU6500
|
||||||
|
|
||||||
|
#define ACC
|
||||||
|
#define USE_ACC_SPI_MPU6000
|
||||||
|
//#define USE_ACC_SPI_MPU6500
|
||||||
|
|
||||||
|
// MPU6000
|
||||||
|
#define ACC_MPU6000_ALIGN CW180_DEG
|
||||||
|
#define GYRO_MPU6000_ALIGN CW180_DEG
|
||||||
|
|
||||||
|
#define MPU6000_CS_GPIO GPIOA
|
||||||
|
#define MPU6000_CS_PIN GPIO_Pin_4
|
||||||
|
#define MPU6000_SPI_INSTANCE SPI1
|
||||||
|
|
||||||
|
// MPU6500
|
||||||
|
#define ACC_MPU6500_ALIGN CW180_DEG
|
||||||
|
#define GYRO_MPU6500_ALIGN CW180_DEG
|
||||||
|
|
||||||
|
#define MPU6500_CS_GPIO GPIOA
|
||||||
|
#define MPU6500_CS_PIN GPIO_Pin_4
|
||||||
|
#define MPU6500_SPI_INSTANCE SPI1
|
||||||
|
#define MPU6500_CS_GPIO_CLK_PERIPHERAL RCC_AHBPeriph_GPIOA
|
||||||
|
|
||||||
|
|
||||||
|
#define BEEPER
|
||||||
|
|
||||||
|
#define USB_IO
|
||||||
|
#define USB_CABLE_DETECTION
|
||||||
|
|
||||||
|
#define USB_DETECT_PIN GPIO_Pin_2
|
||||||
|
#define USB_DETECT_GPIO_PORT GPIOB
|
||||||
|
#define USB_DETECT_GPIO_CLK RCC_AHBPeriph_GPIOB
|
||||||
|
|
||||||
|
#define USE_VCP
|
||||||
|
#define USE_USART1
|
||||||
|
#define USE_USART2
|
||||||
|
#define USE_USART3
|
||||||
|
#define SERIAL_PORT_COUNT 4
|
||||||
|
|
||||||
|
#ifndef UART1_GPIO
|
||||||
|
#define UART1_TX_PIN GPIO_Pin_9 // PA9
|
||||||
|
#define UART1_RX_PIN GPIO_Pin_10 // PA10
|
||||||
|
#define UART1_GPIO GPIOA
|
||||||
|
#define UART1_GPIO_AF GPIO_AF_7
|
||||||
|
#define UART1_TX_PINSOURCE GPIO_PinSource9
|
||||||
|
#define UART1_RX_PINSOURCE GPIO_PinSource10
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define UART2_TX_PIN GPIO_Pin_2 // PA14 / SWCLK
|
||||||
|
#define UART2_RX_PIN GPIO_Pin_3 // PA15
|
||||||
|
#define UART2_GPIO GPIOA
|
||||||
|
#define UART2_GPIO_AF GPIO_AF_7
|
||||||
|
#define UART2_TX_PINSOURCE GPIO_PinSource2
|
||||||
|
#define UART2_RX_PINSOURCE GPIO_PinSource3
|
||||||
|
|
||||||
|
#ifndef UART3_GPIO
|
||||||
|
#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7)
|
||||||
|
#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7)
|
||||||
|
#define UART3_GPIO_AF GPIO_AF_7
|
||||||
|
#define UART3_GPIO GPIOB
|
||||||
|
#define UART3_TX_PINSOURCE GPIO_PinSource10
|
||||||
|
#define UART3_RX_PINSOURCE GPIO_PinSource11
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
#define USE_SPI
|
||||||
|
#define USE_SPI_DEVICE_1
|
||||||
|
#define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5
|
||||||
|
#define USE_SPI_DEVICE_3
|
||||||
|
|
||||||
|
#define SPI1_GPIO GPIOA
|
||||||
|
#define SPI1_GPIO_PERIPHERAL RCC_AHBPeriph_GPIOA
|
||||||
|
#define SPI1_NSS_PIN Pin_4
|
||||||
|
#define SPI1_NSS_PIN_SOURCE GPIO_PinSource4
|
||||||
|
#define SPI1_SCK_PIN Pin_5
|
||||||
|
#define SPI1_SCK_PIN_SOURCE GPIO_PinSource5
|
||||||
|
#define SPI1_MISO_PIN Pin_6
|
||||||
|
#define SPI1_MISO_PIN_SOURCE GPIO_PinSource6
|
||||||
|
#define SPI1_MOSI_PIN Pin_7
|
||||||
|
#define SPI1_MOSI_PIN_SOURCE GPIO_PinSource7
|
||||||
|
|
||||||
|
#define SPI2_GPIO GPIOB
|
||||||
|
#define SPI2_GPIO_PERIPHERAL RCC_AHBPeriph_GPIOB
|
||||||
|
#define SPI2_NSS_PIN Pin_12
|
||||||
|
#define SPI2_NSS_PIN_SOURCE GPIO_PinSource12
|
||||||
|
#define SPI2_SCK_PIN Pin_13
|
||||||
|
#define SPI2_SCK_PIN_SOURCE GPIO_PinSource13
|
||||||
|
#define SPI2_MISO_PIN Pin_14
|
||||||
|
#define SPI2_MISO_PIN_SOURCE GPIO_PinSource14
|
||||||
|
#define SPI2_MOSI_PIN Pin_15
|
||||||
|
#define SPI2_MOSI_PIN_SOURCE GPIO_PinSource15
|
||||||
|
|
||||||
|
#define SPI3_GPIO GPIOB
|
||||||
|
#define SPI3_GPIO_PERIPHERAL RCC_AHBPeriph_GPIOB
|
||||||
|
#define SPI3_NSS_GPIO GPIOA
|
||||||
|
#define SPI3_NSS_PERIPHERAL RCC_AHBPeriph_GPIOA
|
||||||
|
#define SPI3_NSS_PIN GPIO_Pin_15
|
||||||
|
#define SPI3_NSS_PIN_SOURCE GPIO_PinSource15
|
||||||
|
#define SPI3_SCK_PIN GPIO_Pin_3
|
||||||
|
#define SPI3_SCK_PIN_SOURCE GPIO_PinSource3
|
||||||
|
#define SPI3_MISO_PIN GPIO_Pin_4
|
||||||
|
#define SPI3_MISO_PIN_SOURCE GPIO_PinSource4
|
||||||
|
#define SPI3_MOSI_PIN GPIO_Pin_5
|
||||||
|
#define SPI3_MOSI_PIN_SOURCE GPIO_PinSource5
|
||||||
|
|
||||||
|
#define USE_MAX7456
|
||||||
|
#define MAX7456_CS_GPIO GPIOA
|
||||||
|
#define MAX7456_CS_PIN GPIO_Pin_15
|
||||||
|
#define MAX7456_SPI_INSTANCE SPI3
|
||||||
|
|
||||||
|
#define USE_RTC6705
|
||||||
|
#define RTC6705_SPIDATA_GPIO GPIOC
|
||||||
|
#define RTC6705_SPIDATA_PIN Pin_15
|
||||||
|
#define RTC6705_SPIDATA_PERIPHERAL RCC_AHBPeriph_GPIOC
|
||||||
|
#define RTC6705_SPILE_GPIO GPIOC
|
||||||
|
#define RTC6705_SPILE_PIN Pin_14
|
||||||
|
#define RTC6705_SPILE_PERIPHERAL RCC_AHBPeriph_GPIOC
|
||||||
|
#define RTC6705_SPICLK_GPIO GPIOC
|
||||||
|
#define RTC6705_SPICLK_PIN Pin_13
|
||||||
|
#define RTC6705_SPICLK_PERIPHERAL RCC_AHBPeriph_GPIOC
|
||||||
|
|
||||||
|
#define USE_SDCARD
|
||||||
|
#define USE_SDCARD_SPI2
|
||||||
|
|
||||||
|
#define SDCARD_SPI_INSTANCE SPI2
|
||||||
|
#define SDCARD_SPI_CS_GPIO SPI2_GPIO
|
||||||
|
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
|
||||||
|
|
||||||
|
// SPI2 is on the APB1 bus whose clock runs at 36MHz. Divide to under 400kHz for init:
|
||||||
|
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 128
|
||||||
|
// Divide to under 25MHz for normal operation:
|
||||||
|
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 2
|
||||||
|
|
||||||
|
// Note, this is the same DMA channel as USART1_RX. Luckily we don't use DMA for USART Rx.
|
||||||
|
#define SDCARD_DMA_CHANNEL_TX DMA1_Channel5
|
||||||
|
#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA1_FLAG_TC5
|
||||||
|
|
||||||
|
// Performance logging for SD card operations:
|
||||||
|
// #define AFATFS_USE_INTROSPECTIVE_LOGGING
|
||||||
|
|
||||||
|
#define USE_ADC
|
||||||
|
#define BOARD_HAS_VOLTAGE_DIVIDER
|
||||||
|
|
||||||
|
|
||||||
|
#define ADC_INSTANCE ADC1
|
||||||
|
#define ADC_DMA_CHANNEL DMA1_Channel1
|
||||||
|
#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA1
|
||||||
|
|
||||||
|
#define VBAT_ADC_GPIO GPIOA
|
||||||
|
#define VBAT_ADC_GPIO_PIN GPIO_Pin_0
|
||||||
|
#define VBAT_ADC_CHANNEL ADC_Channel_1
|
||||||
|
|
||||||
|
#define USE_QUAD_MIXER_ONLY
|
||||||
|
#define BLACKBOX
|
||||||
|
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
|
||||||
|
#define TELEMETRY
|
||||||
|
#define SERIAL_RX
|
||||||
|
#define GTUNE
|
||||||
|
#define USE_CLI
|
||||||
|
#define OSD
|
||||||
|
|
||||||
|
//#define SPEKTRUM_BIND
|
||||||
|
// USART3,
|
||||||
|
//#define BIND_PORT GPIOB
|
||||||
|
//#define BIND_PIN Pin_11
|
||||||
|
|
||||||
|
#define USE_SERIAL_1WIRE
|
||||||
|
|
||||||
|
#define S1W_TX_GPIO UART1_GPIO
|
||||||
|
#define S1W_TX_PIN UART1_TX_PIN
|
||||||
|
#define S1W_RX_GPIO UART1_GPIO
|
||||||
|
#define S1W_RX_PIN UART1_RX_PIN
|
Loading…
Add table
Add a link
Reference in a new issue