1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-17 13:25:30 +03:00

Improved MSP initialisation and independence from serial code

This commit is contained in:
Martin Budden 2016-10-24 18:49:08 +01:00
parent bc370c78c6
commit 6aa40846fe
6 changed files with 13 additions and 13 deletions

View file

@ -1782,8 +1782,7 @@ mspResult_e mspFcProcessCommand(mspPacket_t *cmd, mspPacket_t *reply, mspPostPro
/* /*
* Return a pointer to the process command function * Return a pointer to the process command function
*/ */
mspProcessCommandFnPtr mspFcInit(void) void mspFcInit(void)
{ {
initActiveBoxIds(); initActiveBoxIds();
return mspFcProcessCommand;
} }

View file

@ -19,4 +19,5 @@
#include "msp/msp.h" #include "msp/msp.h"
mspProcessCommandFnPtr mspFcInit(void); void mspFcInit(void);
mspResult_e mspFcProcessCommand(mspPacket_t *cmd, mspPacket_t *reply, mspPostProcessFnPtr *mspPostProcessFn);

View file

@ -31,6 +31,7 @@
#include "drivers/serial.h" #include "drivers/serial.h"
#include "fc/config.h" #include "fc/config.h"
#include "fc/fc_msp.h"
#include "fc/fc_tasks.h" #include "fc/fc_tasks.h"
#include "fc/mw.h" #include "fc/mw.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
@ -97,7 +98,7 @@ static void taskHandleSerial(uint32_t currentTime)
return; return;
} }
#endif #endif
mspSerialProcess(ARMING_FLAG(ARMED) ? MSP_SKIP_NON_MSP_DATA : MSP_EVALUATE_NON_MSP_DATA); mspSerialProcess(ARMING_FLAG(ARMED) ? MSP_SKIP_NON_MSP_DATA : MSP_EVALUATE_NON_MSP_DATA, mspFcProcessCommand);
} }
#ifdef BEEPER #ifdef BEEPER

View file

@ -449,7 +449,8 @@ void init(void)
imuInit(); imuInit();
mspSerialInit(mspFcInit()); mspFcInit();
mspSerialInit();
#ifdef USE_CLI #ifdef USE_CLI
cliInit(&masterConfig.serialConfig); cliInit(&masterConfig.serialConfig);

View file

@ -31,7 +31,6 @@
#include "msp/msp.h" #include "msp/msp.h"
#include "msp/msp_serial.h" #include "msp/msp_serial.h"
static mspProcessCommandFnPtr mspProcessCommandFn;
static mspPort_t mspPorts[MAX_MSP_PORT_COUNT]; static mspPort_t mspPorts[MAX_MSP_PORT_COUNT];
@ -145,7 +144,7 @@ static void mspSerialEncode(mspPort_t *msp, mspPacket_t *packet)
serialEndWrite(msp->port); serialEndWrite(msp->port);
} }
static mspPostProcessFnPtr mspSerialProcessReceivedCommand(mspPort_t *msp) static mspPostProcessFnPtr mspSerialProcessReceivedCommand(mspPort_t *msp, mspProcessCommandFnPtr mspProcessCommandFn)
{ {
static uint8_t outBuf[MSP_PORT_OUTBUF_SIZE]; static uint8_t outBuf[MSP_PORT_OUTBUF_SIZE];
@ -179,7 +178,7 @@ static mspPostProcessFnPtr mspSerialProcessReceivedCommand(mspPort_t *msp)
* *
* Called periodically by the scheduler. * Called periodically by the scheduler.
*/ */
void mspSerialProcess(mspEvaluateNonMspData_e evaluateNonMspData) void mspSerialProcess(mspEvaluateNonMspData_e evaluateNonMspData, mspProcessCommandFnPtr mspProcessCommandFn)
{ {
for (uint8_t portIndex = 0; portIndex < MAX_MSP_PORT_COUNT; portIndex++) { for (uint8_t portIndex = 0; portIndex < MAX_MSP_PORT_COUNT; portIndex++) {
mspPort_t * const mspPort = &mspPorts[portIndex]; mspPort_t * const mspPort = &mspPorts[portIndex];
@ -197,7 +196,7 @@ void mspSerialProcess(mspEvaluateNonMspData_e evaluateNonMspData)
} }
if (mspPort->c_state == MSP_COMMAND_RECEIVED) { if (mspPort->c_state == MSP_COMMAND_RECEIVED) {
mspPostProcessFn = mspSerialProcessReceivedCommand(mspPort); mspPostProcessFn = mspSerialProcessReceivedCommand(mspPort, mspProcessCommandFn);
break; // process one command at a time so as not to block. break; // process one command at a time so as not to block.
} }
} }
@ -208,9 +207,8 @@ void mspSerialProcess(mspEvaluateNonMspData_e evaluateNonMspData)
} }
} }
void mspSerialInit(mspProcessCommandFnPtr mspProcessCommandFnToUse) void mspSerialInit(void)
{ {
mspProcessCommandFn = mspProcessCommandFnToUse;
memset(mspPorts, 0, sizeof(mspPorts)); memset(mspPorts, 0, sizeof(mspPorts));
mspSerialAllocatePorts(); mspSerialAllocatePorts();
} }

View file

@ -62,7 +62,7 @@ typedef struct mspPort_s {
} mspPort_t; } mspPort_t;
void mspSerialInit(mspProcessCommandFnPtr mspProcessCommandFn); void mspSerialInit(void);
void mspSerialProcess(mspEvaluateNonMspData_e evaluateNonMspData); void mspSerialProcess(mspEvaluateNonMspData_e evaluateNonMspData, mspProcessCommandFnPtr mspProcessCommandFn);
void mspSerialAllocatePorts(void); void mspSerialAllocatePorts(void);
void mspSerialReleasePortIfAllocated(struct serialPort_s *serialPort); void mspSerialReleasePortIfAllocated(struct serialPort_s *serialPort);