1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-26 01:35:41 +03:00
This commit is contained in:
U-DESKTOP-12PPI61\boris.bozic 2017-05-23 13:31:15 +02:00
commit e6b49247f0
15 changed files with 107 additions and 76 deletions

View file

@ -36,6 +36,8 @@ addons:
# We use cpp for unit tests, and c for the main project. # We use cpp for unit tests, and c for the main project.
language: cpp language: cpp
compiler: clang compiler: clang
dist: trusty
before_install: before_install:
- pip install --user cpp-coveralls - pip install --user cpp-coveralls
@ -48,6 +50,7 @@ before_script:
- tools/gcc-arm-none-eabi-6-2017-q1-update/bin/arm-none-eabi-gcc --version - tools/gcc-arm-none-eabi-6-2017-q1-update/bin/arm-none-eabi-gcc --version
- clang --version - clang --version
- clang++ --version - clang++ --version
- gcc --version
script: ./.travis.sh script: ./.travis.sh

View file

@ -1008,6 +1008,11 @@ SITLEXCLUDES = \
drivers/system.c \ drivers/system.c \
drivers/rcc.c \ drivers/rcc.c \
drivers/serial_uart.c \ drivers/serial_uart.c \
drivers/rx_xn297.c \
drivers/display_ug2864hsweg01.c \
telemetry/crsf.c \
telemetry/srxl.c \
io/displayport_oled.c
# check if target.mk supplied # check if target.mk supplied
@ -1138,7 +1143,7 @@ CC_SPEED_OPTIMISATION := $(OPTIMISATION_BASE) $(OPTIMISE_SPEED)
CC_SIZE_OPTIMISATION := $(OPTIMISATION_BASE) $(OPTIMISE_SIZE) CC_SIZE_OPTIMISATION := $(OPTIMISATION_BASE) $(OPTIMISE_SIZE)
else #DEBUG else #DEBUG
OPTIMISE_DEFAULT := -O0 OPTIMISE_DEFAULT := -Og
CC_DEBUG_OPTIMISATION := $(OPTIMISE_DEFAULT) CC_DEBUG_OPTIMISATION := $(OPTIMISE_DEFAULT)

View file

@ -105,7 +105,8 @@
#define PG_VCD_CONFIG 514 #define PG_VCD_CONFIG 514
#define PG_VTX_CONFIG 515 #define PG_VTX_CONFIG 515
#define PG_SONAR_CONFIG 516 #define PG_SONAR_CONFIG 516
#define PG_BETAFLIGHT_END 516 #define PG_ESC_SENSOR_CONFIG 517
#define PG_BETAFLIGHT_END 517
// OSD configuration (subject to change) // OSD configuration (subject to change)

View file

@ -37,9 +37,9 @@
#define BASE_PORT 5760 #define BASE_PORT 5760
const struct serialPortVTable uartVTable[]; // Forward static const struct serialPortVTable tcpVTable; // Forward
static tcpPort_t tcpSerialPorts[SERIAL_PORT_COUNT]; static tcpPort_t tcpSerialPorts[SERIAL_PORT_COUNT];
static bool portInited[SERIAL_PORT_COUNT]; static bool tcpPortInitialized[SERIAL_PORT_COUNT];
static bool tcpStart = false; static bool tcpStart = false;
bool tcpIsStart(void) { bool tcpIsStart(void) {
return tcpStart; return tcpStart;
@ -76,8 +76,8 @@ static void onAccept(dyad_Event *e) {
} }
static tcpPort_t* tcpReconfigure(tcpPort_t *s, int id) static tcpPort_t* tcpReconfigure(tcpPort_t *s, int id)
{ {
if(portInited[id]) { if(tcpPortInitialized[id]) {
fprintf(stderr, "port had initialed!!\n"); fprintf(stderr, "port is already initialized!\n");
return s; return s;
} }
@ -93,7 +93,7 @@ static tcpPort_t* tcpReconfigure(tcpPort_t *s, int id)
} }
tcpStart = true; tcpStart = true;
portInited[id] = true; tcpPortInitialized[id] = true;
s->connected = false; s->connected = false;
s->clientCount = 0; s->clientCount = 0;
@ -104,25 +104,26 @@ static tcpPort_t* tcpReconfigure(tcpPort_t *s, int id)
dyad_addListener(s->serv, DYAD_EVENT_ACCEPT, onAccept, s); dyad_addListener(s->serv, DYAD_EVENT_ACCEPT, onAccept, s);
if(dyad_listenEx(s->serv, NULL, BASE_PORT + id + 1, 10) == 0) { if(dyad_listenEx(s->serv, NULL, BASE_PORT + id + 1, 10) == 0) {
fprintf(stderr, "bind port %u for UART%u\n", (unsigned)BASE_PORT + id + 1, (unsigned)id+1); fprintf(stderr, "bind port %u for UART%u\n", (unsigned)BASE_PORT + id + 1, (unsigned)id + 1);
} else { } else {
fprintf(stderr, "bind port %u for UART%u failed!!\n", (unsigned)BASE_PORT + id + 1, (unsigned)id+1); fprintf(stderr, "bind port %u for UART%u failed!!\n", (unsigned)BASE_PORT + id + 1, (unsigned)id + 1);
} }
return s; return s;
} }
serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr rxCallback, uint32_t baudRate, portMode_t mode, portOptions_t options) serialPort_t *serTcpOpen(int id, serialReceiveCallbackPtr rxCallback, uint32_t baudRate, portMode_t mode, portOptions_t options)
{ {
tcpPort_t *s = NULL; tcpPort_t *s = NULL;
#if defined(USE_UART1) || defined(USE_UART2) || defined(USE_UART3) || defined(USE_UART4) || defined(USE_UART5) || defined(USE_UART6) || defined(USE_UART7) || defined(USE_UART8) #if defined(USE_UART1) || defined(USE_UART2) || defined(USE_UART3) || defined(USE_UART4) || defined(USE_UART5) || defined(USE_UART6) || defined(USE_UART7) || defined(USE_UART8)
uintptr_t id = ((uintptr_t)USARTx - 1); if(id >= 0 && id < SERIAL_PORT_COUNT) {
s = tcpReconfigure(&tcpSerialPorts[id], id); s = tcpReconfigure(&tcpSerialPorts[id], id);
#else }
return (serialPort_t *)s;
#endif #endif
if(!s)
return NULL;
s->port.vTable = uartVTable; s->port.vTable = &tcpVTable;
// common serial initialisation code should move to serialPort::init() // common serial initialisation code should move to serialPort::init()
s->port.rxBufferHead = s->port.rxBufferTail = 0; s->port.rxBufferHead = s->port.rxBufferTail = 0;
@ -167,10 +168,10 @@ uint32_t tcpTotalTxBytesFree(const serialPort_t *instance)
} else { } else {
bytesUsed = s->port.txBufferSize + s->port.txBufferHead - s->port.txBufferTail; bytesUsed = s->port.txBufferSize + s->port.txBufferHead - s->port.txBufferTail;
} }
bytesUsed = (s->port.txBufferSize - 1) - bytesUsed; uint32_t bytesFree = (s->port.txBufferSize - 1) - bytesUsed;
pthread_mutex_unlock(&s->txLock); pthread_mutex_unlock(&s->txLock);
return bytesUsed; return bytesFree;
} }
bool isTcpTransmitBufferEmpty(const serialPort_t *instance) bool isTcpTransmitBufferEmpty(const serialPort_t *instance)
@ -217,18 +218,19 @@ void tcpWrite(serialPort_t *instance, uint8_t ch)
void tcpDataOut(tcpPort_t *instance) void tcpDataOut(tcpPort_t *instance)
{ {
uint32_t bytesUsed;
tcpPort_t *s = (tcpPort_t *)instance; tcpPort_t *s = (tcpPort_t *)instance;
if(s->conn == NULL) return; if(s->conn == NULL) return;
pthread_mutex_lock(&s->txLock); pthread_mutex_lock(&s->txLock);
if (s->port.txBufferHead < s->port.txBufferTail) { if (s->port.txBufferHead < s->port.txBufferTail) {
bytesUsed = s->port.txBufferSize + s->port.txBufferHead - s->port.txBufferTail; // send data till end of buffer
dyad_write(s->conn, (const void *)(s->port.txBuffer + s->port.txBufferTail), s->port.txBufferSize - s->port.txBufferTail); int chunk = s->port.txBufferSize - s->port.txBufferTail;
dyad_write(s->conn, (const void *)&s->port.txBuffer[s->port.txBufferTail], chunk);
s->port.txBufferTail = 0; s->port.txBufferTail = 0;
} }
bytesUsed = s->port.txBufferHead - s->port.txBufferTail; int chunk = s->port.txBufferHead - s->port.txBufferTail;
dyad_write(s->conn, (const void *)(&(s->port.txBuffer[s->port.txBufferTail])), bytesUsed); if(chunk)
dyad_write(s->conn, (const void*)&s->port.txBuffer[s->port.txBufferTail], chunk);
s->port.txBufferTail = s->port.txBufferHead; s->port.txBufferTail = s->port.txBufferHead;
pthread_mutex_unlock(&s->txLock); pthread_mutex_unlock(&s->txLock);
@ -252,8 +254,7 @@ void tcpDataIn(tcpPort_t *instance, uint8_t* ch, int size)
// printf("\n"); // printf("\n");
} }
const struct serialPortVTable uartVTable[] = { static const struct serialPortVTable tcpVTable = {
{
.serialWrite = tcpWrite, .serialWrite = tcpWrite,
.serialTotalRxWaiting = tcpTotalRxBytesWaiting, .serialTotalRxWaiting = tcpTotalRxBytesWaiting,
.serialTotalTxFree = tcpTotalTxBytesFree, .serialTotalTxFree = tcpTotalTxBytesFree,
@ -264,5 +265,4 @@ const struct serialPortVTable uartVTable[] = {
.writeBuf = NULL, .writeBuf = NULL,
.beginWrite = NULL, .beginWrite = NULL,
.endWrite = NULL, .endWrite = NULL,
}
}; };

View file

@ -20,19 +20,14 @@
#include <netinet/in.h> #include <netinet/in.h>
#include <pthread.h> #include <pthread.h>
#include "dyad.h" #include "dyad.h"
// Since serial ports can be used for any function these buffer sizes should be equal
// The two largest things that need to be sent are: 1, MSP responses, 2, UBLOX SVINFO packet.
// Size must be a power of two due to various optimizations which use 'and' instead of 'mod'
// Various serial routines return the buffer occupied size as uint8_t which would need to be extended in order to
// increase size further.
#define RX_BUFFER_SIZE 1400 #define RX_BUFFER_SIZE 1400
#define TX_BUFFER_SIZE 1400 #define TX_BUFFER_SIZE 1400
typedef struct { typedef struct {
serialPort_t port; serialPort_t port;
volatile uint8_t rxBuffer[RX_BUFFER_SIZE]; uint8_t rxBuffer[RX_BUFFER_SIZE];
volatile uint8_t txBuffer[TX_BUFFER_SIZE]; uint8_t txBuffer[TX_BUFFER_SIZE];
dyad_Stream *serv; dyad_Stream *serv;
dyad_Stream *conn; dyad_Stream *conn;
@ -43,16 +38,11 @@ typedef struct {
uint8_t id; uint8_t id;
} tcpPort_t; } tcpPort_t;
serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr rxCallback, uint32_t baudRate, portMode_t mode, portOptions_t options); serialPort_t *serTcpOpen(int id, serialReceiveCallbackPtr rxCallback, uint32_t baudRate, portMode_t mode, portOptions_t options);
// tcpPort API // tcpPort API
void tcpWrite(serialPort_t *instance, uint8_t ch);
void tcpDataIn(tcpPort_t *instance, uint8_t* ch, int size); void tcpDataIn(tcpPort_t *instance, uint8_t* ch, int size);
uint32_t tcpTotalRxBytesWaiting(const serialPort_t *instance);
uint32_t tcpTotalTxBytesFree(const serialPort_t *instance);
uint8_t tcpRead(serialPort_t *instance);
void tcpDataOut(tcpPort_t *instance); void tcpDataOut(tcpPort_t *instance);
bool isTcpTransmitBufferEmpty(const serialPort_t *s);
bool tcpIsStart(void); bool tcpIsStart(void);
bool* tcpGetUsed(void); bool* tcpGetUsed(void);

View file

@ -32,6 +32,7 @@
#include "config/parameter_group.h" #include "config/parameter_group.h"
#include "config/parameter_group_ids.h" #include "config/parameter_group_ids.h"
#include "sensors/esc_sensor.h"
#include "sensors/gyro.h" #include "sensors/gyro.h"
#include "fc/settings.h" #include "fc/settings.h"
@ -689,6 +690,10 @@ const clivalue_t valueTable[] = {
{ "displayport_max7456_col_adjust", VAR_INT8| MASTER_VALUE, .config.minmax = { -6, 0 }, PG_DISPLAY_PORT_MSP_CONFIG, offsetof(displayPortProfile_t, colAdjust) }, { "displayport_max7456_col_adjust", VAR_INT8| MASTER_VALUE, .config.minmax = { -6, 0 }, PG_DISPLAY_PORT_MSP_CONFIG, offsetof(displayPortProfile_t, colAdjust) },
{ "displayport_max7456_row_adjust", VAR_INT8| MASTER_VALUE, .config.minmax = { -3, 0 }, PG_DISPLAY_PORT_MAX7456_CONFIG, offsetof(displayPortProfile_t, rowAdjust) }, { "displayport_max7456_row_adjust", VAR_INT8| MASTER_VALUE, .config.minmax = { -3, 0 }, PG_DISPLAY_PORT_MAX7456_CONFIG, offsetof(displayPortProfile_t, rowAdjust) },
#endif #endif
#ifdef USE_ESC_SENSOR
{ "esc_sensor_halfduplex", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_ESC_SENSOR_CONFIG, offsetof(escSensorConfig_t, halfDuplex) },
#endif
}; };
const uint16_t valueTableEntryCount = ARRAYLEN(valueTable); const uint16_t valueTableEntryCount = ARRAYLEN(valueTable);

View file

@ -152,7 +152,11 @@ static const uint8_t ubloxInit[] = {
// 31.21 CFG-SBAS (0x06 0x16), Page 142/210 // 31.21 CFG-SBAS (0x06 0x16), Page 142/210
// A.10 SBAS Configuration (UBX-CFG-SBAS), Page 198/210 - GPS.G6-SW-10018-F // A.10 SBAS Configuration (UBX-CFG-SBAS), Page 198/210 - GPS.G6-SW-10018-F
#define UBLOX_SBAS_MESSAGE_LENGTH 16 #define UBLOX_SBAS_PREFIX_LENGTH 10
static const uint8_t ubloxSbasPrefix[UBLOX_SBAS_PREFIX_LENGTH] = { 0xB5, 0x62, 0x06, 0x16, 0x08, 0x00, 0x03, 0x07, 0x03, 0x00 };
#define UBLOX_SBAS_MESSAGE_LENGTH 6
typedef struct ubloxSbas_s { typedef struct ubloxSbas_s {
sbasMode_e mode; sbasMode_e mode;
uint8_t message[UBLOX_SBAS_MESSAGE_LENGTH]; uint8_t message[UBLOX_SBAS_MESSAGE_LENGTH];
@ -163,11 +167,11 @@ typedef struct ubloxSbas_s {
// Note: these must be defined in the same order is sbasMode_e since no lookup table is used. // Note: these must be defined in the same order is sbasMode_e since no lookup table is used.
static const ubloxSbas_t ubloxSbas[] = { static const ubloxSbas_t ubloxSbas[] = {
// NOTE this could be optimized to save a few bytes of flash space since the same prefix is used for each command. // NOTE this could be optimized to save a few bytes of flash space since the same prefix is used for each command.
{ SBAS_AUTO, { 0xB5, 0x62, 0x06, 0x16, 0x08, 0x00, 0x03, 0x07, 0x03, 0x00, 0x00, 0x00, 0x00, 0x00, 0x31, 0xE5}}, { SBAS_AUTO, { 0x00, 0x00, 0x00, 0x00, 0x31, 0xE5}},
{ SBAS_EGNOS, { 0xB5, 0x62, 0x06, 0x16, 0x08, 0x00, 0x03, 0x07, 0x03, 0x00, 0x51, 0x08, 0x00, 0x00, 0x8A, 0x41}}, { SBAS_EGNOS, { 0x51, 0x08, 0x00, 0x00, 0x8A, 0x41}},
{ SBAS_WAAS, { 0xB5, 0x62, 0x06, 0x16, 0x08, 0x00, 0x03, 0x07, 0x03, 0x00, 0x04, 0xE0, 0x04, 0x00, 0x19, 0x9D}}, { SBAS_WAAS, { 0x04, 0xE0, 0x04, 0x00, 0x19, 0x9D}},
{ SBAS_MSAS, { 0xB5, 0x62, 0x06, 0x16, 0x08, 0x00, 0x03, 0x07, 0x03, 0x00, 0x00, 0x02, 0x02, 0x00, 0x35, 0xEF}}, { SBAS_MSAS, { 0x00, 0x02, 0x02, 0x00, 0x35, 0xEF}},
{ SBAS_GAGAN, { 0xB5, 0x62, 0x06, 0x16, 0x08, 0x00, 0x03, 0x07, 0x03, 0x00, 0x80, 0x01, 0x00, 0x00, 0xB2, 0xE8}} { SBAS_GAGAN, { 0x80, 0x01, 0x00, 0x00, 0xB2, 0xE8}}
}; };
@ -372,8 +376,11 @@ void gpsInitUblox(void)
} }
if (gpsData.messageState == GPS_MESSAGE_STATE_SBAS) { if (gpsData.messageState == GPS_MESSAGE_STATE_SBAS) {
if (gpsData.state_position < UBLOX_SBAS_MESSAGE_LENGTH) { if (gpsData.state_position < UBLOX_SBAS_PREFIX_LENGTH) {
serialWrite(gpsPort, ubloxSbas[gpsConfig()->sbasMode].message[gpsData.state_position]); serialWrite(gpsPort, ubloxSbasPrefix[gpsData.state_position]);
gpsData.state_position++;
} else if (gpsData.state_position < UBLOX_SBAS_PREFIX_LENGTH + UBLOX_SBAS_MESSAGE_LENGTH) {
serialWrite(gpsPort, ubloxSbas[gpsConfig()->sbasMode].message[gpsData.state_position - UBLOX_SBAS_PREFIX_LENGTH]);
gpsData.state_position++; gpsData.state_position++;
} else { } else {
gpsData.messageState++; gpsData.messageState++;

View file

@ -44,6 +44,10 @@
#include "drivers/serial_uart.h" #include "drivers/serial_uart.h"
#endif #endif
#ifdef SITL
#include "drivers/serial_tcp.h"
#endif
#include "drivers/light_led.h" #include "drivers/light_led.h"
#if defined(USE_VCP) #if defined(USE_VCP)
@ -379,7 +383,12 @@ serialPort_t *openSerialPort(
#ifdef USE_UART8 #ifdef USE_UART8
case SERIAL_PORT_USART8: case SERIAL_PORT_USART8:
#endif #endif
#ifdef SITL
// SITL emulates serial ports over TCP
serialPort = serTcpOpen(SERIAL_PORT_IDENTIFIER_TO_UARTDEV(identifier), rxCallback, baudRate, mode, options);
#else
serialPort = uartOpen(SERIAL_PORT_IDENTIFIER_TO_UARTDEV(identifier), rxCallback, baudRate, mode, options); serialPort = uartOpen(SERIAL_PORT_IDENTIFIER_TO_UARTDEV(identifier), rxCallback, baudRate, mode, options);
#endif
break; break;
#endif #endif

View file

@ -64,6 +64,12 @@ Byte 9: 8-bit CRC
*/ */
PG_REGISTER_WITH_RESET_TEMPLATE(escSensorConfig_t, escSensorConfig, PG_ESC_SENSOR_CONFIG, 0);
PG_RESET_TEMPLATE(escSensorConfig_t, escSensorConfig,
.halfDuplex = 0
);
/* /*
DEBUG INFORMATION DEBUG INFORMATION
----------------- -----------------
@ -183,7 +189,7 @@ bool escSensorInit(void)
return false; return false;
} }
portOptions_t options = (SERIAL_NOT_INVERTED); portOptions_t options = SERIAL_NOT_INVERTED | (escSensorConfig()->halfDuplex ? SERIAL_BIDIR : 0);
// Initialize serial port // Initialize serial port
escSensorPort = openSerialPort(portConfig->identifier, FUNCTION_ESC_SENSOR, escSensorDataReceive, ESC_SENSOR_BAUDRATE, MODE_RX, options); escSensorPort = openSerialPort(portConfig->identifier, FUNCTION_ESC_SENSOR, escSensorDataReceive, ESC_SENSOR_BAUDRATE, MODE_RX, options);

View file

@ -19,6 +19,12 @@
#include "common/time.h" #include "common/time.h"
typedef struct escSensorConfig_s {
uint8_t halfDuplex; // Set to false to listen on the TX pin for telemetry data
} escSensorConfig_t;
PG_DECLARE(escSensorConfig_t, escSensorConfig);
typedef struct { typedef struct {
uint8_t dataAge; uint8_t dataAge;
int8_t temperature; int8_t temperature;

View file

@ -25,8 +25,7 @@ INSERT AFTER .text;
__FLASH_CONFIG_Size = 0x2000; /* 8kB */ __FLASH_CONFIG_Size = 0x2000; /* 8kB */
SECTIONS { SECTIONS {
/* .FLASH_CONFIG BLOCK( DEFINED(__section_alignment__) ? __section_alignment__ : 4 ) : SUBALIGN(4)*/ .FLASH_CONFIG BLOCK( DEFINED(__section_alignment__) ? __section_alignment__ : 4 ) :
.FLASH_CONFIG :
{ {
PROVIDE_HIDDEN (__config_start = . ); PROVIDE_HIDDEN (__config_start = . );
. = . + __FLASH_CONFIG_Size; . = . + __FLASH_CONFIG_Size;

View file

@ -436,63 +436,58 @@ char _Min_Stack_Size;
// fake EEPROM // fake EEPROM
extern uint8_t __config_start; extern uint8_t __config_start;
extern uint8_t __config_end; extern uint8_t __config_end;
extern uint32_t __FLASH_CONFIG_Size;
static FILE *eepromFd = NULL; static FILE *eepromFd = NULL;
const char *EEPROM_FILE = EEPROM_FILENAME;
void FLASH_Unlock(void) { void FLASH_Unlock(void) {
uint8_t * const eeprom = &__config_start; uint8_t * const eeprom = &__config_start;
if(eepromFd != NULL) { if (eepromFd != NULL) {
printf("[FLASH_Unlock] eepromFd != NULL\n"); printf("[FLASH_Unlock] eepromFd != NULL\n");
return; return;
} }
// open or create // open or create
eepromFd = fopen(EEPROM_FILE,"r+"); eepromFd = fopen(EEPROM_FILENAME,"r+");
if(eepromFd != NULL) { if (eepromFd != NULL) {
long lSize;
int c;
// obtain file size: // obtain file size:
fseek(eepromFd , 0 , SEEK_END); fseek(eepromFd , 0 , SEEK_END);
lSize = ftell(eepromFd); long lSize = ftell(eepromFd);
rewind(eepromFd); rewind(eepromFd);
printf("[FLASH_Unlock]size = %ld, %ld\n", lSize, (uintptr_t)(&__config_end - &__config_start)); printf("[FLASH_Unlock]size = %ld, %ld\n", lSize, (uintptr_t)(&__config_end - &__config_start));
for(unsigned int i=0; i<(uintptr_t)(&__config_end - &__config_start); i++){ for (unsigned i = 0; i < (uintptr_t)(&__config_end - &__config_start); i++) {
c = fgetc(eepromFd); int c = fgetc(eepromFd);
if(c == EOF) break; if(c == EOF) break;
eeprom[i] = (uint8_t)c; eeprom[i] = (uint8_t)c;
} }
}else{ } else {
eepromFd = fopen(EEPROM_FILE, "w+"); eepromFd = fopen(EEPROM_FILENAME, "w+");
fwrite(eeprom, sizeof(uint8_t), (size_t)&__FLASH_CONFIG_Size, eepromFd); fwrite(eeprom, sizeof(uint8_t), &__config_end - &__config_start, eepromFd);
} }
} }
void FLASH_Lock(void) { void FLASH_Lock(void) {
// flush & close // flush & close
if(eepromFd != NULL) { if (eepromFd != NULL) {
const uint8_t *eeprom = &__config_start; const uint8_t *eeprom = &__config_start;
fseek(eepromFd, 0, SEEK_SET); fseek(eepromFd, 0, SEEK_SET);
fwrite(eeprom, sizeof(uint8_t), (size_t)&__FLASH_CONFIG_Size, eepromFd); fwrite(eeprom, 1, &__config_end - &__config_start, eepromFd);
fflush(eepromFd);
fclose(eepromFd); fclose(eepromFd);
eepromFd = NULL; eepromFd = NULL;
} }
} }
FLASH_Status FLASH_ErasePage(uint32_t Page_Address) { FLASH_Status FLASH_ErasePage(uintptr_t Page_Address) {
UNUSED(Page_Address); UNUSED(Page_Address);
// printf("[FLASH_ErasePage]%x\n", Page_Address); // printf("[FLASH_ErasePage]%x\n", Page_Address);
return FLASH_COMPLETE; return FLASH_COMPLETE;
} }
FLASH_Status FLASH_ProgramWord(uint32_t addr, uint32_t Data) { FLASH_Status FLASH_ProgramWord(uintptr_t addr, uint32_t Data) {
if((addr >= (uintptr_t)&__config_start)&&(addr < (uintptr_t)&__config_end)) { if ((addr >= (uintptr_t)&__config_start)&&(addr < (uintptr_t)&__config_end)) {
*((uint32_t*)(uintptr_t)addr) = Data; *((uint32_t*)addr) = Data;
// printf("[FLASH_ProgramWord]0x%x = %x\n", addr, *((uint32_t*)(uintptr_t)addr)); printf("[FLASH_ProgramWord]0x%p = %x\n", (void*)addr, *((uint32_t*)addr));
}else{ } else {
printf("[FLASH_ProgramWord]Out of Range!! 0x%x = %x\n", addr, *((uint32_t*)(uintptr_t)addr)); printf("[FLASH_ProgramWord]Out of Range! 0x%p\n", (void*)addr);
} }
return FLASH_COMPLETE; return FLASH_COMPLETE;
} }

View file

@ -233,8 +233,8 @@ typedef struct {
void FLASH_Unlock(void); void FLASH_Unlock(void);
void FLASH_Lock(void); void FLASH_Lock(void);
FLASH_Status FLASH_ErasePage(uint32_t Page_Address); FLASH_Status FLASH_ErasePage(uintptr_t Page_Address);
FLASH_Status FLASH_ProgramWord(uint32_t addr, uint32_t Data); FLASH_Status FLASH_ProgramWord(uintptr_t addr, uint32_t Data);
uint64_t nanos64_real(); uint64_t nanos64_real();
uint64_t micros64_real(); uint64_t micros64_real();

View file

@ -8,6 +8,7 @@
#include <string.h> #include <string.h>
#include <fcntl.h> #include <fcntl.h>
#include <sys/socket.h>
#include "udplink.h" #include "udplink.h"

View file

@ -21,6 +21,10 @@
// Targets with built-in vtx do not need external vtx // Targets with built-in vtx do not need external vtx
#if defined(VTX_RTC6705) && !defined(VTX_RTC6705_OPTIONAL) #if defined(VTX_RTC6705) && !defined(VTX_RTC6705_OPTIONAL)
# undef VTX_SMARTAUDIO #undef VTX_SMARTAUDIO
# undef VTX_TRAMP #undef VTX_TRAMP
#endif
#if defined(USE_QUAD_MIXER_ONLY) && defined(USE_SERVOS)
#undef USE_SERVOS
#endif #endif