1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-20 14:55:21 +03:00

remove sirinfpv related stuff from config.c, rename rtc6705 to soft_spi_rtc6705, fix some minor bugs

This commit is contained in:
Evgeny Sychov 2016-06-14 01:05:51 -07:00
parent cbb09d5470
commit 067c02bbd6
9 changed files with 41 additions and 43 deletions

View file

@ -419,20 +419,8 @@ static void resetConf(void)
featureSet(DEFAULT_FEATURES); featureSet(DEFAULT_FEATURES);
#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.blackbox_device = 1;
masterConfig.blackbox_rate_num = 1;
masterConfig.blackbox_rate_denom = 1;
#endif
#ifdef OSD #ifdef OSD
masterConfig.vtx_channel = 19; featureSet(FEATURE_OSD);
masterConfig.osdProfile.system = 0; masterConfig.osdProfile.system = 0;
masterConfig.osdProfile.item_pos[OSD_MAIN_BATT_VOLTAGE] = -29; masterConfig.osdProfile.item_pos[OSD_MAIN_BATT_VOLTAGE] = -29;
masterConfig.osdProfile.item_pos[OSD_RSSI_VALUE] = -59; masterConfig.osdProfile.item_pos[OSD_RSSI_VALUE] = -59;
@ -445,6 +433,10 @@ static void resetConf(void)
masterConfig.osdProfile.item_pos[OSD_DISARMED] = -109; masterConfig.osdProfile.item_pos[OSD_DISARMED] = -109;
#endif #endif
#ifdef USE_RTC6705
masterConfig.vtx_channel = 19; // default to Boscam E channel 4
#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.

View file

@ -34,11 +34,15 @@
#define DISABLE_MAX7456 GPIO_SetBits(MAX7456_CS_GPIO, MAX7456_CS_PIN) #define DISABLE_MAX7456 GPIO_SetBits(MAX7456_CS_GPIO, MAX7456_CS_PIN)
#define ENABLE_MAX7456 GPIO_ResetBits(MAX7456_CS_GPIO, MAX7456_CS_PIN) #define ENABLE_MAX7456 GPIO_ResetBits(MAX7456_CS_GPIO, MAX7456_CS_PIN)
/** PAL or NTSC, value is number of chars total */
#define VIDEO_MODE_PIXELS_NTSC 390
#define VIDEO_MODE_PIXELS_PAL 480
uint16_t max_screen_size; uint16_t max_screen_size;
uint8_t video_signal_type = 0; uint8_t video_signal_type = 0;
uint8_t max7456_lock = 0; uint8_t max7456_lock = 0;
char screen[480]; char screen[VIDEO_MODE_PIXELS_PAL];
uint8_t max7456_send(uint8_t add, uint8_t data) { uint8_t max7456_send(uint8_t add, uint8_t data) {
@ -81,10 +85,10 @@ void max7456_init(uint8_t system) {
} }
if (video_signal_type) { //PAL if (video_signal_type) { //PAL
max_screen_size = 480; max_screen_size = VIDEO_MODE_PIXELS_PAL;
max_screen_rows = 16; max_screen_rows = 16;
} else { // NTSC } else { // NTSC
max_screen_size = 390; max_screen_size = VIDEO_MODE_PIXELS_NTSC;
max_screen_rows = 13; max_screen_rows = 13;
} }
@ -121,7 +125,7 @@ void max7456_write_string(const char *string, int16_t address) {
else else
dest = screen + (max_screen_size + address); dest = screen + (max_screen_size + address);
while(*string) while(*string && dest < (screen + max_screen_size))
*dest++ = *string++; *dest++ = *string++;
} }

View file

@ -27,7 +27,7 @@
#include "drivers/system.h" #include "drivers/system.h"
#include "drivers/gpio.h" #include "drivers/gpio.h"
#include "rtc6705.h" #include "vtx_soft_spi_rtc6705.h"
#define RTC6705_SPICLK_ON GPIO_SetBits(RTC6705_SPICLK_GPIO, RTC6705_SPICLK_PIN) #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_SPICLK_OFF GPIO_ResetBits(RTC6705_SPICLK_GPIO, RTC6705_SPICLK_PIN)
@ -57,7 +57,7 @@ uint16_t vtx_freq[] =
uint16_t current_vtx_channel; uint16_t current_vtx_channel;
void rtc6705_init(void) { void rtc6705_soft_spi_init(void) {
gpio_config_t gpio; gpio_config_t gpio;
#ifdef STM32F303 #ifdef STM32F303
@ -99,7 +99,7 @@ void rtc6705_init(void) {
gpioInit(RTC6705_SPIDATA_GPIO, &gpio); gpioInit(RTC6705_SPIDATA_GPIO, &gpio);
} }
void rtc6705_write_register(uint8_t addr, uint32_t data) { static void rtc6705_write_register(uint8_t addr, uint32_t data) {
uint8_t i; uint8_t i;
RTC6705_SPILE_OFF; RTC6705_SPILE_OFF;
@ -137,7 +137,7 @@ void rtc6705_write_register(uint8_t addr, uint32_t data) {
} }
void rtc6705_set_channel(uint16_t channel_freq) { void rtc6705_soft_spi_set_channel(uint16_t channel_freq) {
uint32_t freq = (uint32_t)channel_freq * 1000; uint32_t freq = (uint32_t)channel_freq * 1000;
uint32_t N, A; uint32_t N, A;

View file

@ -21,5 +21,5 @@ extern char* vtx_bands[];
extern uint16_t vtx_freq[]; extern uint16_t vtx_freq[];
extern uint16_t current_vtx_channel; extern uint16_t current_vtx_channel;
void rtc6705_init(void); void rtc6705_soft_spi_init(void);
void rtc6705_set_channel(uint16_t channel_freq); void rtc6705_soft_spi_set_channel(uint16_t channel_freq);

View file

@ -187,8 +187,6 @@ void writeServos(void);
void filterServos(void); void filterServos(void);
#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];
bool motorLimitReached; bool motorLimitReached;

View file

@ -106,7 +106,11 @@
#ifdef OSD #ifdef OSD
#include "drivers/max7456.h" #include "drivers/max7456.h"
#include "drivers/rtc6705.h"
#ifdef USE_RTC6705
#include "drivers/vtx_soft_spi_rtc6705.h"
#endif
#include "scheduler.h" #include "scheduler.h"
#include "common/printf.h" #include "common/printf.h"
@ -355,7 +359,7 @@ void print_batt_voltage(uint16_t pos, uint8_t col) {
{ "acro_plus_offset", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.acroPlusOffset, .config.minmax = {1, 90 } }, { "acro_plus_offset", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.acroPlusOffset, .config.minmax = {1, 90 } },
*/ */
page_t menu_pages[] = { osd_page_t menu_pages[] = {
{ {
.title = "STATUS", .title = "STATUS",
.cols_number = 1, .cols_number = 1,
@ -475,8 +479,8 @@ page_t menu_pages[] = {
void show_menu(void) { void show_menu(void) {
uint8_t line = 1; uint8_t line = 1;
uint16_t pos; uint16_t pos;
col_t *col; osd_col_t *col;
row_t *row; osd_row_t *row;
int16_t cursor_x = 0; int16_t cursor_x = 0;
int16_t cursor_y = 0; int16_t cursor_y = 0;
@ -498,13 +502,13 @@ void show_menu(void) {
#ifdef USE_RTC6705 #ifdef USE_RTC6705
if (masterConfig.vtx_channel != current_vtx_channel) { if (masterConfig.vtx_channel != current_vtx_channel) {
masterConfig.vtx_channel = current_vtx_channel; masterConfig.vtx_channel = current_vtx_channel;
rtc6705_set_channel(vtx_freq[current_vtx_channel]); rtc6705_soft_spi_set_channel(vtx_freq[current_vtx_channel]);
} }
#endif #endif
writeEEPROM(); writeEEPROM();
break; break;
case 2: case 2:
if (current_page < (sizeof(menu_pages) / sizeof(page_t) - 1)) if (current_page < (sizeof(menu_pages) / sizeof(osd_page_t) - 1))
current_page++; current_page++;
else else
current_page = 0; current_page = 0;
@ -700,9 +704,9 @@ void updateOsd(void)
void osdInit(void) void osdInit(void)
{ {
#ifdef USE_RTC6705 #ifdef USE_RTC6705
rtc6705_init(); rtc6705_soft_spi_init();
current_vtx_channel = masterConfig.vtx_channel; current_vtx_channel = masterConfig.vtx_channel;
rtc6705_set_channel(vtx_freq[current_vtx_channel]); rtc6705_soft_spi_set_channel(vtx_freq[current_vtx_channel]);
#endif #endif
max7456_init(masterConfig.osdProfile.system); max7456_init(masterConfig.osdProfile.system);

View file

@ -21,21 +21,21 @@
typedef struct { typedef struct {
const char* title; const char* title;
uint8_t x_pos; uint8_t x_pos;
} col_t; } osd_col_t;
typedef struct { typedef struct {
const char* title; const char* title;
void (*update)(bool increase, uint8_t col); void (*update)(bool increase, uint8_t col);
void (*print)(uint16_t pos, uint8_t col); void (*print)(uint16_t pos, uint8_t col);
} row_t; } osd_row_t;
typedef struct { typedef struct {
const char* title; const char* title;
uint8_t cols_number; uint8_t cols_number;
uint8_t rows_number; uint8_t rows_number;
col_t cols[MAX_MENU_COLS]; osd_col_t cols[MAX_MENU_COLS];
row_t rows[MAX_MENU_ROWS]; osd_row_t rows[MAX_MENU_ROWS];
} page_t; } osd_page_t;
typedef enum { typedef enum {
@ -49,7 +49,7 @@ typedef enum {
OSD_ARMED, OSD_ARMED,
OSD_DISARMED, OSD_DISARMED,
OSD_MAX_ITEMS, // MUST BE LAST OSD_MAX_ITEMS, // MUST BE LAST
} osd_items; } osd_items_t;
typedef struct { typedef struct {

View file

@ -45,7 +45,7 @@
#include "drivers/sdcard.h" #include "drivers/sdcard.h"
#include "drivers/buf_writer.h" #include "drivers/buf_writer.h"
#include "drivers/max7456.h" #include "drivers/max7456.h"
#include "drivers/rtc6705.h" #include "drivers/vtx_soft_spi_rtc6705.h"
#include "rx/rx.h" #include "rx/rx.h"
#include "rx/msp.h" #include "rx/msp.h"
@ -1543,7 +1543,7 @@ static bool processInCommand(void)
masterConfig.vtx_channel = tmp; masterConfig.vtx_channel = tmp;
if (current_vtx_channel != masterConfig.vtx_channel) { if (current_vtx_channel != masterConfig.vtx_channel) {
current_vtx_channel = masterConfig.vtx_channel; current_vtx_channel = masterConfig.vtx_channel;
rtc6705_set_channel(vtx_freq[current_vtx_channel]); rtc6705_soft_spi_set_channel(vtx_freq[current_vtx_channel]);
} }
break; break;
#endif #endif

View file

@ -1,5 +1,5 @@
FEATURES = VCP SDCARD MAX_OSD
F3_TARGETS += $(TARGET) F3_TARGETS += $(TARGET)
FEATURES = VCP SDCARD MAX_OSD
TARGET_SRC = \ TARGET_SRC = \
drivers/accgyro_mpu.c \ drivers/accgyro_mpu.c \
@ -12,5 +12,5 @@ TARGET_SRC = \
drivers/flash_m25p16.c \ drivers/flash_m25p16.c \
drivers/light_ws2811strip.c \ drivers/light_ws2811strip.c \
drivers/light_ws2811strip_stm32f30x.c \ drivers/light_ws2811strip_stm32f30x.c \
drivers/rtc6705.c drivers/vtx_soft_spi_rtc6705.c