mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-23 00:05:33 +03:00
Fixed whitespace
This commit is contained in:
parent
786343e2b2
commit
8dd4a584c1
53 changed files with 311 additions and 311 deletions
|
@ -42,73 +42,73 @@ static tcpPort_t tcpSerialPorts[SERIAL_PORT_COUNT];
|
||||||
static bool tcpPortInitialized[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;
|
||||||
}
|
}
|
||||||
static void onData(dyad_Event *e) {
|
static void onData(dyad_Event *e) {
|
||||||
tcpPort_t* s = (tcpPort_t*)(e->udata);
|
tcpPort_t* s = (tcpPort_t*)(e->udata);
|
||||||
tcpDataIn(s, (uint8_t*)e->data, e->size);
|
tcpDataIn(s, (uint8_t*)e->data, e->size);
|
||||||
}
|
}
|
||||||
static void onClose(dyad_Event *e) {
|
static void onClose(dyad_Event *e) {
|
||||||
tcpPort_t* s = (tcpPort_t*)(e->udata);
|
tcpPort_t* s = (tcpPort_t*)(e->udata);
|
||||||
s->clientCount--;
|
s->clientCount--;
|
||||||
s->conn = NULL;
|
s->conn = NULL;
|
||||||
fprintf(stderr, "[CLS]UART%u: %d,%d\n", s->id + 1, s->connected, s->clientCount);
|
fprintf(stderr, "[CLS]UART%u: %d,%d\n", s->id + 1, s->connected, s->clientCount);
|
||||||
if (s->clientCount == 0) {
|
if (s->clientCount == 0) {
|
||||||
s->connected = false;
|
s->connected = false;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
static void onAccept(dyad_Event *e) {
|
static void onAccept(dyad_Event *e) {
|
||||||
tcpPort_t* s = (tcpPort_t*)(e->udata);
|
tcpPort_t* s = (tcpPort_t*)(e->udata);
|
||||||
fprintf(stderr, "New connection on UART%u, %d\n", s->id + 1, s->clientCount);
|
fprintf(stderr, "New connection on UART%u, %d\n", s->id + 1, s->clientCount);
|
||||||
|
|
||||||
s->connected = true;
|
s->connected = true;
|
||||||
if (s->clientCount > 0) {
|
if (s->clientCount > 0) {
|
||||||
dyad_close(e->remote);
|
dyad_close(e->remote);
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
s->clientCount++;
|
s->clientCount++;
|
||||||
fprintf(stderr, "[NEW]UART%u: %d,%d\n", s->id + 1, s->connected, s->clientCount);
|
fprintf(stderr, "[NEW]UART%u: %d,%d\n", s->id + 1, s->connected, s->clientCount);
|
||||||
s->conn = e->remote;
|
s->conn = e->remote;
|
||||||
dyad_setNoDelay(e->remote, 1);
|
dyad_setNoDelay(e->remote, 1);
|
||||||
dyad_setTimeout(e->remote, 120);
|
dyad_setTimeout(e->remote, 120);
|
||||||
dyad_addListener(e->remote, DYAD_EVENT_DATA, onData, e->udata);
|
dyad_addListener(e->remote, DYAD_EVENT_DATA, onData, e->udata);
|
||||||
dyad_addListener(e->remote, DYAD_EVENT_CLOSE, onClose, e->udata);
|
dyad_addListener(e->remote, DYAD_EVENT_CLOSE, onClose, e->udata);
|
||||||
}
|
}
|
||||||
static tcpPort_t* tcpReconfigure(tcpPort_t *s, int id)
|
static tcpPort_t* tcpReconfigure(tcpPort_t *s, int id)
|
||||||
{
|
{
|
||||||
if (tcpPortInitialized[id]) {
|
if (tcpPortInitialized[id]) {
|
||||||
fprintf(stderr, "port is already initialized!\n");
|
fprintf(stderr, "port is already initialized!\n");
|
||||||
return s;
|
return s;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (pthread_mutex_init(&s->txLock, NULL) != 0) {
|
if (pthread_mutex_init(&s->txLock, NULL) != 0) {
|
||||||
fprintf(stderr, "TX mutex init failed - %d\n", errno);
|
fprintf(stderr, "TX mutex init failed - %d\n", errno);
|
||||||
// TODO: clean up & re-init
|
// TODO: clean up & re-init
|
||||||
return NULL;
|
return NULL;
|
||||||
}
|
}
|
||||||
if (pthread_mutex_init(&s->rxLock, NULL) != 0) {
|
if (pthread_mutex_init(&s->rxLock, NULL) != 0) {
|
||||||
fprintf(stderr, "RX mutex init failed - %d\n", errno);
|
fprintf(stderr, "RX mutex init failed - %d\n", errno);
|
||||||
// TODO: clean up & re-init
|
// TODO: clean up & re-init
|
||||||
return NULL;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
tcpStart = true;
|
tcpStart = true;
|
||||||
tcpPortInitialized[id] = true;
|
tcpPortInitialized[id] = true;
|
||||||
|
|
||||||
s->connected = false;
|
s->connected = false;
|
||||||
s->clientCount = 0;
|
s->clientCount = 0;
|
||||||
s->id = id;
|
s->id = id;
|
||||||
s->conn = NULL;
|
s->conn = NULL;
|
||||||
s->serv = dyad_newStream();
|
s->serv = dyad_newStream();
|
||||||
dyad_setNoDelay(s->serv, 1);
|
dyad_setNoDelay(s->serv, 1);
|
||||||
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 *serTcpOpen(int id, serialReceiveCallbackPtr rxCallback, uint32_t baudRate, portMode_e mode, portOptions_e options)
|
serialPort_t *serTcpOpen(int id, serialReceiveCallbackPtr rxCallback, uint32_t baudRate, portMode_e mode, portOptions_e options)
|
||||||
|
@ -117,7 +117,7 @@ serialPort_t *serTcpOpen(int id, serialReceiveCallbackPtr rxCallback, uint32_t b
|
||||||
|
|
||||||
#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)
|
||||||
if (id >= 0 && id < SERIAL_PORT_COUNT) {
|
if (id >= 0 && id < SERIAL_PORT_COUNT) {
|
||||||
s = tcpReconfigure(&tcpSerialPorts[id], id);
|
s = tcpReconfigure(&tcpSerialPorts[id], id);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
if (!s)
|
if (!s)
|
||||||
|
@ -128,10 +128,10 @@ serialPort_t *serTcpOpen(int id, serialReceiveCallbackPtr rxCallback, uint32_t b
|
||||||
// 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;
|
||||||
s->port.txBufferHead = s->port.txBufferTail = 0;
|
s->port.txBufferHead = s->port.txBufferTail = 0;
|
||||||
s->port.rxBufferSize = RX_BUFFER_SIZE;
|
s->port.rxBufferSize = RX_BUFFER_SIZE;
|
||||||
s->port.txBufferSize = TX_BUFFER_SIZE;
|
s->port.txBufferSize = TX_BUFFER_SIZE;
|
||||||
s->port.rxBuffer = s->rxBuffer;
|
s->port.rxBuffer = s->rxBuffer;
|
||||||
s->port.txBuffer = s->txBuffer;
|
s->port.txBuffer = s->txBuffer;
|
||||||
|
|
||||||
// callback works for IRQ-based RX ONLY
|
// callback works for IRQ-based RX ONLY
|
||||||
s->port.rxCallback = rxCallback;
|
s->port.rxCallback = rxCallback;
|
||||||
|
@ -239,19 +239,19 @@ void tcpDataOut(tcpPort_t *instance)
|
||||||
void tcpDataIn(tcpPort_t *instance, uint8_t* ch, int size)
|
void tcpDataIn(tcpPort_t *instance, uint8_t* ch, int size)
|
||||||
{
|
{
|
||||||
tcpPort_t *s = (tcpPort_t *)instance;
|
tcpPort_t *s = (tcpPort_t *)instance;
|
||||||
pthread_mutex_lock(&s->rxLock);
|
pthread_mutex_lock(&s->rxLock);
|
||||||
|
|
||||||
while (size--) {
|
while (size--) {
|
||||||
// printf("%c", *ch);
|
// printf("%c", *ch);
|
||||||
s->port.rxBuffer[s->port.rxBufferHead] = *(ch++);
|
s->port.rxBuffer[s->port.rxBufferHead] = *(ch++);
|
||||||
if (s->port.rxBufferHead + 1 >= s->port.rxBufferSize) {
|
if (s->port.rxBufferHead + 1 >= s->port.rxBufferSize) {
|
||||||
s->port.rxBufferHead = 0;
|
s->port.rxBufferHead = 0;
|
||||||
} else {
|
} else {
|
||||||
s->port.rxBufferHead++;
|
s->port.rxBufferHead++;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
pthread_mutex_unlock(&s->rxLock);
|
pthread_mutex_unlock(&s->rxLock);
|
||||||
// printf("\n");
|
// printf("\n");
|
||||||
}
|
}
|
||||||
|
|
||||||
static const struct serialPortVTable tcpVTable = {
|
static const struct serialPortVTable tcpVTable = {
|
||||||
|
|
|
@ -50,12 +50,12 @@
|
||||||
/*** ERLT ***/
|
/*** ERLT ***/
|
||||||
#define TRANSPONDER_DATA_LENGTH_ERLT 1
|
#define TRANSPONDER_DATA_LENGTH_ERLT 1
|
||||||
|
|
||||||
#define ERLTBitQuiet 0
|
#define ERLTBitQuiet 0
|
||||||
#define ERLTCyclesForOneBit 25
|
#define ERLTCyclesForOneBit 25
|
||||||
#define ERLTCyclesForZeroBit 10
|
#define ERLTCyclesForZeroBit 10
|
||||||
#define TRANSPONDER_DMA_BUFFER_SIZE_ERLT 200 // actually ERLT is variable length 91-196 depending on the ERLT id
|
#define TRANSPONDER_DMA_BUFFER_SIZE_ERLT 200 // actually ERLT is variable length 91-196 depending on the ERLT id
|
||||||
#define TRANSPONDER_TIMER_MHZ_ERLT 18
|
#define TRANSPONDER_TIMER_MHZ_ERLT 18
|
||||||
#define TRANSPONDER_CARRIER_HZ_ERLT 38000
|
#define TRANSPONDER_CARRIER_HZ_ERLT 38000
|
||||||
#define TRANSPONDER_TRANSMIT_DELAY_ERLT 22500
|
#define TRANSPONDER_TRANSMIT_DELAY_ERLT 22500
|
||||||
#define TRANSPONDER_TRANSMIT_JITTER_ERLT 5000
|
#define TRANSPONDER_TRANSMIT_JITTER_ERLT 5000
|
||||||
/*** ******** ***/
|
/*** ******** ***/
|
||||||
|
|
|
@ -36,40 +36,40 @@ void transponderIrInitERLT(transponder_t *transponder){
|
||||||
|
|
||||||
void addBitToBuffer(transponder_t *transponder, uint8_t cycles, uint8_t pulsewidth)
|
void addBitToBuffer(transponder_t *transponder, uint8_t cycles, uint8_t pulsewidth)
|
||||||
{
|
{
|
||||||
for (int i = 0; i < cycles; i++) {
|
for (int i = 0; i < cycles; i++) {
|
||||||
transponder->transponderIrDMABuffer.erlt[dmaBufferOffset++] = pulsewidth;
|
transponder->transponderIrDMABuffer.erlt[dmaBufferOffset++] = pulsewidth;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void updateTransponderDMABufferERLT(transponder_t *transponder, const uint8_t* transponderData)
|
void updateTransponderDMABufferERLT(transponder_t *transponder, const uint8_t* transponderData)
|
||||||
{
|
{
|
||||||
uint8_t byteToSend = ~(*transponderData); //transponderData is stored inverted, so invert before using
|
uint8_t byteToSend = ~(*transponderData); //transponderData is stored inverted, so invert before using
|
||||||
uint8_t paritysum = 0; //sum of one bits
|
uint8_t paritysum = 0; //sum of one bits
|
||||||
|
|
||||||
dmaBufferOffset = 0; //reset buffer count
|
dmaBufferOffset = 0; //reset buffer count
|
||||||
|
|
||||||
//start bit 1, always pulsed, bit value = 0
|
//start bit 1, always pulsed, bit value = 0
|
||||||
addBitToBuffer(transponder, ERLTCyclesForZeroBit, transponder->bitToggleOne);
|
addBitToBuffer(transponder, ERLTCyclesForZeroBit, transponder->bitToggleOne);
|
||||||
|
|
||||||
//start bit 2, always not pulsed, bit value = 0
|
//start bit 2, always not pulsed, bit value = 0
|
||||||
addBitToBuffer(transponder, ERLTCyclesForZeroBit, ERLTBitQuiet);
|
addBitToBuffer(transponder, ERLTCyclesForZeroBit, ERLTBitQuiet);
|
||||||
|
|
||||||
//add data bits, only the 6 LSB
|
//add data bits, only the 6 LSB
|
||||||
for (int i = 5; i >= 0; i--)
|
for (int i = 5; i >= 0; i--)
|
||||||
{
|
{
|
||||||
uint8_t bv = (byteToSend >> i) & 0x01;
|
uint8_t bv = (byteToSend >> i) & 0x01;
|
||||||
paritysum += bv;
|
paritysum += bv;
|
||||||
addBitToBuffer(transponder, (bv ? ERLTCyclesForOneBit : ERLTCyclesForZeroBit), ((i % 2) ? transponder->bitToggleOne : ERLTBitQuiet));
|
addBitToBuffer(transponder, (bv ? ERLTCyclesForOneBit : ERLTCyclesForZeroBit), ((i % 2) ? transponder->bitToggleOne : ERLTBitQuiet));
|
||||||
}
|
}
|
||||||
|
|
||||||
//parity bit, always pulsed, bit value is zero if sum is even, one if odd
|
//parity bit, always pulsed, bit value is zero if sum is even, one if odd
|
||||||
addBitToBuffer(transponder, ((paritysum % 2) ? ERLTCyclesForOneBit : ERLTCyclesForZeroBit), transponder->bitToggleOne);
|
addBitToBuffer(transponder, ((paritysum % 2) ? ERLTCyclesForOneBit : ERLTCyclesForZeroBit), transponder->bitToggleOne);
|
||||||
|
|
||||||
//add final zero after the pulsed parity bit to stop pulses until the next update
|
//add final zero after the pulsed parity bit to stop pulses until the next update
|
||||||
transponder->transponderIrDMABuffer.erlt[dmaBufferOffset++] = ERLTBitQuiet;
|
transponder->transponderIrDMABuffer.erlt[dmaBufferOffset++] = ERLTBitQuiet;
|
||||||
|
|
||||||
//reset buffer size to that required by this ERLT id
|
//reset buffer size to that required by this ERLT id
|
||||||
transponder->dma_buffer_size = dmaBufferOffset;
|
transponder->dma_buffer_size = dmaBufferOffset;
|
||||||
}
|
}
|
||||||
|
|
||||||
const struct transponderVTable erltTansponderVTable = {
|
const struct transponderVTable erltTansponderVTable = {
|
||||||
|
|
|
@ -2112,8 +2112,8 @@ static void cliBeeper(char *cmdline)
|
||||||
|
|
||||||
#ifdef FRSKY_BIND
|
#ifdef FRSKY_BIND
|
||||||
void cliFrSkyBind(char *cmdline){
|
void cliFrSkyBind(char *cmdline){
|
||||||
UNUSED(cmdline);
|
UNUSED(cmdline);
|
||||||
frSkyDBind();
|
frSkyDBind();
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -2391,7 +2391,7 @@ static void cliDshotProg(char *cmdline)
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
writeDshotCommand(escIndex, command);
|
writeDshotCommand(escIndex, command);
|
||||||
}
|
}
|
||||||
|
|
||||||
cliPrintLinef("Command %d written.", command);
|
cliPrintLinef("Command %d written.", command);
|
||||||
|
|
||||||
|
|
|
@ -512,7 +512,7 @@ void calculateThrottleAndCurrentMotorEndpoints(void)
|
||||||
if((rcCommand[THROTTLE] <= (rxConfig()->midrc - flight3DConfig()->deadband3d_throttle))) {
|
if((rcCommand[THROTTLE] <= (rxConfig()->midrc - flight3DConfig()->deadband3d_throttle))) {
|
||||||
motorOutputMax = deadbandMotor3dLow;
|
motorOutputMax = deadbandMotor3dLow;
|
||||||
motorOutputMin = motorOutputLow;
|
motorOutputMin = motorOutputLow;
|
||||||
throttlePrevious = rcCommand[THROTTLE]; //3D Mode Throttle Fix #3696
|
throttlePrevious = rcCommand[THROTTLE]; //3D Mode Throttle Fix #3696
|
||||||
throttle = rcCommand[THROTTLE] - rxConfig()->mincheck; //3D Mode Throttle Fix #3696
|
throttle = rcCommand[THROTTLE] - rxConfig()->mincheck; //3D Mode Throttle Fix #3696
|
||||||
currentThrottleInputRange = rcCommandThrottleRange3dLow;
|
currentThrottleInputRange = rcCommandThrottleRange3dLow;
|
||||||
if(isMotorProtocolDshot()) mixerInversion = true;
|
if(isMotorProtocolDshot()) mixerInversion = true;
|
||||||
|
|
|
@ -61,8 +61,8 @@ void targetConfiguration(void)
|
||||||
{
|
{
|
||||||
if (hardwareMotorType == MOTOR_BRUSHED) {
|
if (hardwareMotorType == MOTOR_BRUSHED) {
|
||||||
motorConfigMutable()->dev.motorPwmRate = BRUSHED_MOTORS_PWM_RATE;
|
motorConfigMutable()->dev.motorPwmRate = BRUSHED_MOTORS_PWM_RATE;
|
||||||
motorConfigMutable()->minthrottle = 1080;
|
motorConfigMutable()->minthrottle = 1080;
|
||||||
motorConfigMutable()->maxthrottle = 2000;
|
motorConfigMutable()->maxthrottle = 2000;
|
||||||
pidConfigMutable()->pid_process_denom = 1;
|
pidConfigMutable()->pid_process_denom = 1;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -26,16 +26,16 @@
|
||||||
|
|
||||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||||
|
|
||||||
DEF_TIM(TIM2, CH2, PA1, TIM_USE_PPM, TIMER_INPUT_ENABLED), // PPM
|
DEF_TIM(TIM2, CH2, PA1, TIM_USE_PPM, TIMER_INPUT_ENABLED), // PPM
|
||||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_PWM, TIMER_OUTPUT_ENABLED), // SS1Rx
|
DEF_TIM(TIM3, CH3, PB0, TIM_USE_PWM, TIMER_OUTPUT_ENABLED), // SS1Rx
|
||||||
DEF_TIM(TIM3, CH2, PB5, TIM_USE_PWM, TIMER_OUTPUT_ENABLED), // SS1Tx
|
DEF_TIM(TIM3, CH2, PB5, TIM_USE_PWM, TIMER_OUTPUT_ENABLED), // SS1Tx
|
||||||
|
|
||||||
DEF_TIM(TIM8, CH3, PB9, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), // S1
|
DEF_TIM(TIM8, CH3, PB9, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), // S1
|
||||||
DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), // S2
|
DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), // S2
|
||||||
DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), // S3
|
DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), // S3
|
||||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), // S4
|
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), // S4
|
||||||
DEF_TIM(TIM16, CH1, PB4, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), // S5
|
DEF_TIM(TIM16, CH1, PB4, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), // S5
|
||||||
|
|
||||||
DEF_TIM(TIM15, CH1, PA2, TIM_USE_LED, TIMER_OUTPUT_ENABLED), // LED_STRIP
|
DEF_TIM(TIM15, CH1, PA2, TIM_USE_LED, TIMER_OUTPUT_ENABLED), // LED_STRIP
|
||||||
DEF_TIM(TIM2, CH1, PA15, TIM_USE_ANY, TIMER_OUTPUT_ENABLED), // CAMERA CONTROL
|
DEF_TIM(TIM2, CH1, PA15, TIM_USE_ANY, TIMER_OUTPUT_ENABLED), // CAMERA CONTROL
|
||||||
};
|
};
|
||||||
|
|
|
@ -75,7 +75,7 @@
|
||||||
|
|
||||||
#define LED_STRIP
|
#define LED_STRIP
|
||||||
|
|
||||||
#define CAMERA_CONTROL_PIN PA15
|
#define CAMERA_CONTROL_PIN PA15
|
||||||
|
|
||||||
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
||||||
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
||||||
|
|
|
@ -233,7 +233,7 @@ typedef struct {
|
||||||
double position_xyz[3]; // meters, NED from origin
|
double position_xyz[3]; // meters, NED from origin
|
||||||
} fdm_packet;
|
} fdm_packet;
|
||||||
typedef struct {
|
typedef struct {
|
||||||
float motor_speed[4]; // normal: [0.0, 1.0], 3D: [-1.0, 1.0]
|
float motor_speed[4]; // normal: [0.0, 1.0], 3D: [-1.0, 1.0]
|
||||||
} servo_packet;
|
} servo_packet;
|
||||||
|
|
||||||
void FLASH_Unlock(void);
|
void FLASH_Unlock(void);
|
||||||
|
|
|
@ -20,12 +20,12 @@ extern "C" {
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
typedef struct {
|
typedef struct {
|
||||||
int fd;
|
int fd;
|
||||||
struct sockaddr_in si;
|
struct sockaddr_in si;
|
||||||
struct sockaddr_in recv;
|
struct sockaddr_in recv;
|
||||||
int port;
|
int port;
|
||||||
char* addr;
|
char* addr;
|
||||||
bool isServer;
|
bool isServer;
|
||||||
} udpLink_t;
|
} udpLink_t;
|
||||||
|
|
||||||
int udpInit(udpLink_t* link, const char* addr, int port, bool isServer);
|
int udpInit(udpLink_t* link, const char* addr, int port, bool isServer);
|
||||||
|
|
|
@ -183,15 +183,15 @@ void srxlFrameRpm(sbuf_t *dst)
|
||||||
/*
|
/*
|
||||||
typedef struct
|
typedef struct
|
||||||
{
|
{
|
||||||
UINT8 identifier; // Source device = 0x34
|
UINT8 identifier; // Source device = 0x34
|
||||||
UINT8 sID; // Secondary ID
|
UINT8 sID; // Secondary ID
|
||||||
INT16 current_A; // Instantaneous current, 0.1A (0-3276.8A)
|
INT16 current_A; // Instantaneous current, 0.1A (0-3276.8A)
|
||||||
INT16 chargeUsed_A; // Integrated mAh used, 1mAh (0-32.766Ah)
|
INT16 chargeUsed_A; // Integrated mAh used, 1mAh (0-32.766Ah)
|
||||||
UINT16 temp_A; // Temperature, 0.1C (0-150C, 0x7FFF indicates not populated)
|
UINT16 temp_A; // Temperature, 0.1C (0-150C, 0x7FFF indicates not populated)
|
||||||
INT16 current_B; // Instantaneous current, 0.1A (0-3276.8A)
|
INT16 current_B; // Instantaneous current, 0.1A (0-3276.8A)
|
||||||
INT16 chargeUsed_B; // Integrated mAh used, 1mAh (0-32.766Ah)
|
INT16 chargeUsed_B; // Integrated mAh used, 1mAh (0-32.766Ah)
|
||||||
UINT16 temp_B; // Temperature, 0.1C (0-150C, 0x7FFF indicates not populated)
|
UINT16 temp_B; // Temperature, 0.1C (0-150C, 0x7FFF indicates not populated)
|
||||||
UINT16 spare; // Not used
|
UINT16 spare; // Not used
|
||||||
} STRU_TELE_FP_MAH;
|
} STRU_TELE_FP_MAH;
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue