1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-16 21:05:35 +03:00

Rebased onto super-abstracted msp

This commit is contained in:
jflyper 2016-10-20 23:21:32 +09:00
parent 01eab00fd7
commit 0249443862
8 changed files with 71 additions and 49 deletions

View file

@ -102,15 +102,6 @@
#include "config/config_master.h" #include "config/config_master.h"
#include "config/feature.h" #include "config/feature.h"
#ifdef USE_DPRINTF
#include "common/printf.h"
#define DPRINTF_SERIAL_PORT SERIAL_PORT_USART3
extern serialPort_t *debugSerialPort;
#define dprintf(x) if (debugSerialPort) printf x
#else
#define dprintf(x)
#endif
#ifdef USE_HARDWARE_REVISION_DETECTION #ifdef USE_HARDWARE_REVISION_DETECTION
#include "hardware_revision.h" #include "hardware_revision.h"
#endif #endif
@ -1946,16 +1937,7 @@ mspResult_e mspFcProcessCommand(mspPort_t *mspPort, mspPostProcessFnPtr *mspPost
return ret; return ret;
} }
/* void mspServerPush(mspPort_t *mspPort, uint8_t cmd, uint8_t *data, int len)
* Return a pointer to the process command function
*/
mspProcessCommandFnPtr mspFcInit(void)
{
initActiveBoxIds();
return mspFcProcessCommand;
}
void mspServerPush(mspPort_t *mspPort, int cmd, uint8_t *data, int len)
{ {
currentPort = mspPort; currentPort = mspPort;
mspPort->cmdMSP = cmd; mspPort->cmdMSP = cmd;
@ -1968,3 +1950,17 @@ void mspServerPush(mspPort_t *mspPort, int cmd, uint8_t *data, int len)
tailSerialReply(); tailSerialReply();
} }
/*
* Return a pointer to the process command function
*/
mspProcessCommandFnPtr mspFcInit(void)
{
initActiveBoxIds();
return mspFcProcessCommand;
}
mspPushCommandFnPtr mspFcPushInit(void)
{
return mspServerPush;
}

View file

@ -20,3 +20,4 @@
#include "msp/msp.h" #include "msp/msp.h"
mspProcessCommandFnPtr mspFcInit(void); mspProcessCommandFnPtr mspFcInit(void);
mspPushCommandFnPtr mspFcPushInit(void);

View file

@ -1 +1,2 @@
void cmsInit(void);
void cmsHandler(uint32_t); void cmsHandler(uint32_t);

View file

@ -98,8 +98,9 @@ void osdResetAlarms(void);
// specific functions; max7456XXX(), canvasXXX(), oledXXX(), ... // specific functions; max7456XXX(), canvasXXX(), oledXXX(), ...
// //
#include "io/serial_msp.h" #include "fc/fc_msp.h"
#include "msp/msp_protocol.h" #include "msp/msp_protocol.h"
#include "msp/msp_serial.h"
void canvasBegin(void) void canvasBegin(void)
{ {
@ -146,6 +147,12 @@ void canvasWrite(int col, int row, char *string)
mspSerialPush(MSP_CANVAS, (uint8_t *)buf, len + 4); mspSerialPush(MSP_CANVAS, (uint8_t *)buf, len + 4);
} }
// Called once at startup to initialize push function in msp
void canvasInit(void)
{
mspSerialPushInit(mspFcPushInit());
}
#endif #endif
// Force draw all elements if true // Force draw all elements if true
@ -226,6 +233,13 @@ void cmsScreenResync(void)
#endif #endif
} }
void cmsScreenInit(void)
{
#ifdef CANVAS
canvasInit();
#endif
}
// //
// Lots of things not separated yet. // Lots of things not separated yet.
// //
@ -1348,6 +1362,11 @@ void cmsHandler(uint32_t currentTime)
} }
void cmsInit(void)
{
cmsScreenInit();
}
// Does this belong here? // Does this belong here?
#ifdef USE_FLASHFS #ifdef USE_FLASHFS

View file

@ -88,6 +88,7 @@
#include "io/transponder_ir.h" #include "io/transponder_ir.h"
#include "io/osd.h" #include "io/osd.h"
#include "io/vtx.h" #include "io/vtx.h"
#include "io/cms.h"
#include "scheduler/scheduler.h" #include "scheduler/scheduler.h"
@ -424,6 +425,10 @@ void init(void)
} }
#endif #endif
#ifdef CMS
cmsInit();
#endif
if (!sensorsAutodetect(&masterConfig.sensorAlignmentConfig, if (!sensorsAutodetect(&masterConfig.sensorAlignmentConfig,
masterConfig.acc_hardware, masterConfig.acc_hardware,
masterConfig.mag_hardware, masterConfig.mag_hardware,

View file

@ -29,3 +29,4 @@ struct serialPort_s;
typedef void (*mspPostProcessFnPtr)(struct serialPort_s *port); // msp post process function, used for gracefully handling reboots, etc. typedef void (*mspPostProcessFnPtr)(struct serialPort_s *port); // msp post process function, used for gracefully handling reboots, etc.
struct mspPort_s; struct mspPort_s;
typedef mspResult_e (*mspProcessCommandFnPtr)(struct mspPort_s *mspPort, mspPostProcessFnPtr *mspPostProcessFn); typedef mspResult_e (*mspProcessCommandFnPtr)(struct mspPort_s *mspPort, mspPostProcessFnPtr *mspPostProcessFn);
typedef void (*mspPushCommandFnPtr)(struct mspPort_s *, uint8_t, uint8_t *, int);

View file

@ -35,6 +35,7 @@
static mspProcessCommandFnPtr mspProcessCommandFn; static mspProcessCommandFnPtr mspProcessCommandFn;
static mspPushCommandFnPtr mspPushCommandFn;
static mspPort_t mspPorts[MAX_MSP_PORT_COUNT]; static mspPort_t mspPorts[MAX_MSP_PORT_COUNT];
bufWriter_t *writer; bufWriter_t *writer;
@ -128,34 +129,6 @@ static mspPostProcessFnPtr mspSerialProcessReceivedCommand(mspPort_t *mspPort)
return mspPostProcessFn; return mspPostProcessFn;
} }
#ifdef USE_DPRINTF
#include "common/printf.h"
#define DPRINTF_SERIAL_PORT SERIAL_PORT_USART3
extern serialPort_t *debugSerialPort;
#define dprintf(x) if (debugSerialPort) printf x
#else
#define dprintf(x)
#endif
void mspSerialPush(int cmd, uint8_t *data, int buflen)
{
for (uint8_t portIndex = 0; portIndex < MAX_MSP_PORT_COUNT; portIndex++) {
mspPort_t * const mspPort = &mspPorts[portIndex];
if (!mspPort->port) {
continue;
}
// Big enough for a OSD line
uint8_t buf[sizeof(bufWriter_t) + 30];
writer = bufWriterInit(buf, sizeof(buf), (bufWrite_t)serialWriteBufShim, mspPort->port);
mspServerPush(mspPort, cmd, data, buflen);
bufWriterFlush(writer);
}
}
/* /*
* Process MSP commands from serial ports configured as MSP ports. * Process MSP commands from serial ports configured as MSP ports.
* *
@ -204,3 +177,27 @@ void mspSerialInit(mspProcessCommandFnPtr mspProcessCommandFnToUse)
memset(mspPorts, 0, sizeof(mspPorts)); memset(mspPorts, 0, sizeof(mspPorts));
mspSerialAllocatePorts(); mspSerialAllocatePorts();
} }
void mspSerialPush(uint8_t cmd, uint8_t *data, int buflen)
{
for (uint8_t portIndex = 0; portIndex < MAX_MSP_PORT_COUNT; portIndex++) {
mspPort_t * const mspPort = &mspPorts[portIndex];
if (!mspPort->port) {
continue;
}
// Big enough for a OSD line
uint8_t buf[sizeof(bufWriter_t) + 30];
writer = bufWriterInit(buf, sizeof(buf), (bufWrite_t)serialWriteBufShim, mspPort->port);
mspPushCommandFn(mspPort, cmd, data, buflen);
bufWriterFlush(writer);
}
}
void mspSerialPushInit(mspPushCommandFnPtr mspPushCommandFnToUse)
{
mspPushCommandFn = mspPushCommandFnToUse;
}

View file

@ -60,4 +60,6 @@ void mspSerialInit(mspProcessCommandFnPtr mspProcessCommandFn);
void mspSerialProcess(mspEvaluateNonMspData_e evaluateNonMspData); void mspSerialProcess(mspEvaluateNonMspData_e evaluateNonMspData);
void mspSerialAllocatePorts(void); void mspSerialAllocatePorts(void);
void mspSerialReleasePortIfAllocated(struct serialPort_s *serialPort); void mspSerialReleasePortIfAllocated(struct serialPort_s *serialPort);
void mspSerialPush(int, uint8_t *, int);
void mspSerialPushInit(mspPushCommandFnPtr mspPushCommandFn);
void mspSerialPush(uint8_t, uint8_t *, int);