Split off serial parts from MSP
This commit is contained in:
parent
5253c72625
commit
5fec66b639
1
Makefile
1
Makefile
|
@ -439,6 +439,7 @@ COMMON_SRC = \
|
||||||
io/serial_4way_avrootloader.c \
|
io/serial_4way_avrootloader.c \
|
||||||
io/serial_4way_stk500v2.c \
|
io/serial_4way_stk500v2.c \
|
||||||
io/serial_cli.c \
|
io/serial_cli.c \
|
||||||
|
io/serial_msp.c \
|
||||||
io/statusindicator.c \
|
io/statusindicator.c \
|
||||||
msp/msp_server_fc.c \
|
msp/msp_server_fc.c \
|
||||||
rx/ibus.c \
|
rx/ibus.c \
|
||||||
|
|
|
@ -0,0 +1,149 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight.
|
||||||
|
*
|
||||||
|
* Cleanflight is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <stdbool.h>
|
||||||
|
#include <stdint.h>
|
||||||
|
#include <string.h>
|
||||||
|
|
||||||
|
#include "platform.h"
|
||||||
|
|
||||||
|
#include "common/utils.h"
|
||||||
|
|
||||||
|
#include "drivers/buf_writer.h"
|
||||||
|
#include "drivers/serial.h"
|
||||||
|
#include "drivers/system.h"
|
||||||
|
|
||||||
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
|
#include "flight/mixer.h"
|
||||||
|
|
||||||
|
#include "io/serial.h"
|
||||||
|
#include "io/serial_msp.h"
|
||||||
|
|
||||||
|
#include "msp/msp.h"
|
||||||
|
|
||||||
|
|
||||||
|
static mspPort_t mspPorts[MAX_MSP_PORT_COUNT];
|
||||||
|
serialPort_t *mspSerialPort;
|
||||||
|
mspPort_t *currentPort;
|
||||||
|
bufWriter_t *writer;
|
||||||
|
|
||||||
|
|
||||||
|
static void resetMspPort(mspPort_t *mspPortToReset, serialPort_t *serialPort)
|
||||||
|
{
|
||||||
|
memset(mspPortToReset, 0, sizeof(mspPort_t));
|
||||||
|
|
||||||
|
mspPortToReset->port = serialPort;
|
||||||
|
}
|
||||||
|
|
||||||
|
void mspSerialAllocatePorts(serialConfig_t *serialConfig)
|
||||||
|
{
|
||||||
|
UNUSED(serialConfig);
|
||||||
|
|
||||||
|
serialPort_t *serialPort;
|
||||||
|
|
||||||
|
uint8_t portIndex = 0;
|
||||||
|
|
||||||
|
serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_MSP);
|
||||||
|
|
||||||
|
while (portConfig && portIndex < MAX_MSP_PORT_COUNT) {
|
||||||
|
mspPort_t *mspPort = &mspPorts[portIndex];
|
||||||
|
if (mspPort->port) {
|
||||||
|
portIndex++;
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
|
||||||
|
serialPort = openSerialPort(portConfig->identifier, FUNCTION_MSP, NULL, baudRates[portConfig->msp_baudrateIndex], MODE_RXTX, SERIAL_NOT_INVERTED);
|
||||||
|
if (serialPort) {
|
||||||
|
resetMspPort(mspPort, serialPort);
|
||||||
|
portIndex++;
|
||||||
|
}
|
||||||
|
|
||||||
|
portConfig = findNextSerialPortConfig(FUNCTION_MSP);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void mspSerialReleasePortIfAllocated(serialPort_t *serialPort)
|
||||||
|
{
|
||||||
|
uint8_t portIndex;
|
||||||
|
for (portIndex = 0; portIndex < MAX_MSP_PORT_COUNT; portIndex++) {
|
||||||
|
mspPort_t *candidateMspPort = &mspPorts[portIndex];
|
||||||
|
if (candidateMspPort->port == serialPort) {
|
||||||
|
closeSerialPort(serialPort);
|
||||||
|
memset(candidateMspPort, 0, sizeof(mspPort_t));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void mspSerialInit(serialConfig_t *serialConfig)
|
||||||
|
{
|
||||||
|
mspInit();
|
||||||
|
memset(mspPorts, 0x00, sizeof(mspPorts));
|
||||||
|
mspSerialAllocatePorts(serialConfig);
|
||||||
|
}
|
||||||
|
|
||||||
|
static void setCurrentPort(mspPort_t *port)
|
||||||
|
{
|
||||||
|
currentPort = port;
|
||||||
|
mspSerialPort = currentPort->port;
|
||||||
|
}
|
||||||
|
|
||||||
|
void mspSerialProcess(void)
|
||||||
|
{
|
||||||
|
uint8_t portIndex;
|
||||||
|
mspPort_t *candidatePort;
|
||||||
|
|
||||||
|
for (portIndex = 0; portIndex < MAX_MSP_PORT_COUNT; portIndex++) {
|
||||||
|
candidatePort = &mspPorts[portIndex];
|
||||||
|
if (!candidatePort->port) {
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
|
||||||
|
setCurrentPort(candidatePort);
|
||||||
|
// Big enough to fit a MSP_STATUS in one write.
|
||||||
|
uint8_t buf[sizeof(bufWriter_t) + 20];
|
||||||
|
writer = bufWriterInit(buf, sizeof(buf),
|
||||||
|
(bufWrite_t)serialWriteBufShim, currentPort->port);
|
||||||
|
|
||||||
|
while (serialRxBytesWaiting(mspSerialPort)) {
|
||||||
|
|
||||||
|
uint8_t c = serialRead(mspSerialPort);
|
||||||
|
bool consumed = mspProcessReceivedData(c);
|
||||||
|
|
||||||
|
if (!consumed && !ARMING_FLAG(ARMED)) {
|
||||||
|
evaluateOtherData(mspSerialPort, c);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (currentPort->c_state == COMMAND_RECEIVED) {
|
||||||
|
mspProcessReceivedCommand();
|
||||||
|
break; // process one command at a time so as not to block.
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
bufWriterFlush(writer);
|
||||||
|
|
||||||
|
if (isRebootScheduled) {
|
||||||
|
waitForSerialPortToFinishTransmitting(candidatePort->port);
|
||||||
|
stopPwmAllMotors();
|
||||||
|
// On real flight controllers, systemReset() will do a soft reset of the device,
|
||||||
|
// reloading the program. But to support offline testing this flag needs to be
|
||||||
|
// cleared so that the software doesn't continuously attempt to reboot itself.
|
||||||
|
isRebootScheduled = false;
|
||||||
|
systemReset();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
|
@ -44,6 +44,16 @@ typedef struct mspPort_s {
|
||||||
uint8_t cmdMSP;
|
uint8_t cmdMSP;
|
||||||
} mspPort_t;
|
} mspPort_t;
|
||||||
|
|
||||||
|
|
||||||
|
extern struct serialPort_s *mspSerialPort;
|
||||||
|
extern mspPort_t *currentPort;
|
||||||
|
|
||||||
|
struct bufWriter_s;
|
||||||
|
extern struct bufWriter_s *writer;
|
||||||
|
|
||||||
|
extern bool isRebootScheduled;
|
||||||
|
|
||||||
|
|
||||||
struct serialConfig_s;
|
struct serialConfig_s;
|
||||||
void mspSerialInit(struct serialConfig_s *serialConfig);
|
void mspSerialInit(struct serialConfig_s *serialConfig);
|
||||||
void mspSerialProcess(void);
|
void mspSerialProcess(void);
|
||||||
|
|
|
@ -0,0 +1,23 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight.
|
||||||
|
*
|
||||||
|
* Cleanflight is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
|
||||||
|
void mspInit(void);
|
||||||
|
bool mspProcessReceivedData(uint8_t c);
|
||||||
|
void mspProcessReceivedCommand(void);
|
|
@ -107,8 +107,6 @@
|
||||||
|
|
||||||
#include "io/serial_4way.h"
|
#include "io/serial_4way.h"
|
||||||
|
|
||||||
static serialPort_t *mspSerialPort;
|
|
||||||
|
|
||||||
extern uint16_t cycleTime; // FIXME dependency on mw.c
|
extern uint16_t cycleTime; // FIXME dependency on mw.c
|
||||||
extern uint16_t rssi; // FIXME dependency on mw.c
|
extern uint16_t rssi; // FIXME dependency on mw.c
|
||||||
extern void resetProfile(profile_t *profile);
|
extern void resetProfile(profile_t *profile);
|
||||||
|
@ -168,10 +166,7 @@ static uint8_t activeBoxIdCount = 0;
|
||||||
extern int16_t motor_disarmed[MAX_SUPPORTED_MOTORS];
|
extern int16_t motor_disarmed[MAX_SUPPORTED_MOTORS];
|
||||||
|
|
||||||
// cause reboot after MSP processing complete
|
// cause reboot after MSP processing complete
|
||||||
static bool isRebootScheduled = false;
|
bool isRebootScheduled = false;
|
||||||
STATIC_UNIT_TESTED mspPort_t mspPorts[MAX_MSP_PORT_COUNT];
|
|
||||||
STATIC_UNIT_TESTED mspPort_t *currentPort;
|
|
||||||
STATIC_UNIT_TESTED bufWriter_t *writer;
|
|
||||||
|
|
||||||
|
|
||||||
static const char pidnames[] =
|
static const char pidnames[] =
|
||||||
|
@ -448,53 +443,7 @@ static void serializeDataflashReadReply(uint32_t address, uint16_t size, bool us
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
static void resetMspPort(mspPort_t *mspPortToReset, serialPort_t *serialPort)
|
void mspInit(void)
|
||||||
{
|
|
||||||
memset(mspPortToReset, 0, sizeof(mspPort_t));
|
|
||||||
|
|
||||||
mspPortToReset->port = serialPort;
|
|
||||||
}
|
|
||||||
|
|
||||||
void mspSerialAllocatePorts(serialConfig_t *serialConfig)
|
|
||||||
{
|
|
||||||
UNUSED(serialConfig);
|
|
||||||
|
|
||||||
serialPort_t *serialPort;
|
|
||||||
|
|
||||||
uint8_t portIndex = 0;
|
|
||||||
|
|
||||||
serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_MSP);
|
|
||||||
|
|
||||||
while (portConfig && portIndex < MAX_MSP_PORT_COUNT) {
|
|
||||||
mspPort_t *mspPort = &mspPorts[portIndex];
|
|
||||||
if (mspPort->port) {
|
|
||||||
portIndex++;
|
|
||||||
continue;
|
|
||||||
}
|
|
||||||
|
|
||||||
serialPort = openSerialPort(portConfig->identifier, FUNCTION_MSP, NULL, baudRates[portConfig->msp_baudrateIndex], MODE_RXTX, SERIAL_NOT_INVERTED);
|
|
||||||
if (serialPort) {
|
|
||||||
resetMspPort(mspPort, serialPort);
|
|
||||||
portIndex++;
|
|
||||||
}
|
|
||||||
|
|
||||||
portConfig = findNextSerialPortConfig(FUNCTION_MSP);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
void mspSerialReleasePortIfAllocated(serialPort_t *serialPort)
|
|
||||||
{
|
|
||||||
uint8_t portIndex;
|
|
||||||
for (portIndex = 0; portIndex < MAX_MSP_PORT_COUNT; portIndex++) {
|
|
||||||
mspPort_t *candidateMspPort = &mspPorts[portIndex];
|
|
||||||
if (candidateMspPort->port == serialPort) {
|
|
||||||
closeSerialPort(serialPort);
|
|
||||||
memset(candidateMspPort, 0, sizeof(mspPort_t));
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
static void mspInit(void)
|
|
||||||
{
|
{
|
||||||
// calculate used boxes based on features and fill availableBoxes[] array
|
// calculate used boxes based on features and fill availableBoxes[] array
|
||||||
memset(activeBoxIds, 0xFF, sizeof(activeBoxIds));
|
memset(activeBoxIds, 0xFF, sizeof(activeBoxIds));
|
||||||
|
@ -593,13 +542,6 @@ static void mspInit(void)
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
void mspSerialInit(serialConfig_t *serialConfig)
|
|
||||||
{
|
|
||||||
mspInit();
|
|
||||||
memset(mspPorts, 0x00, sizeof(mspPorts));
|
|
||||||
mspSerialAllocatePorts(serialConfig);
|
|
||||||
}
|
|
||||||
|
|
||||||
#define IS_ENABLED(mask) (mask == 0 ? 0 : 1)
|
#define IS_ENABLED(mask) (mask == 0 ? 0 : 1)
|
||||||
|
|
||||||
static uint32_t packFlightModeFlags(void)
|
static uint32_t packFlightModeFlags(void)
|
||||||
|
@ -1956,7 +1898,8 @@ static bool processInCommand(void)
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
STATIC_UNIT_TESTED void mspProcessReceivedCommand() {
|
void mspProcessReceivedCommand()
|
||||||
|
{
|
||||||
if (!(processOutCommand(currentPort->cmdMSP) || processInCommand())) {
|
if (!(processOutCommand(currentPort->cmdMSP) || processInCommand())) {
|
||||||
headSerialError(0);
|
headSerialError(0);
|
||||||
}
|
}
|
||||||
|
@ -1964,7 +1907,7 @@ STATIC_UNIT_TESTED void mspProcessReceivedCommand() {
|
||||||
currentPort->c_state = IDLE;
|
currentPort->c_state = IDLE;
|
||||||
}
|
}
|
||||||
|
|
||||||
static bool mspProcessReceivedData(uint8_t c)
|
bool mspProcessReceivedData(uint8_t c)
|
||||||
{
|
{
|
||||||
if (currentPort->c_state == IDLE) {
|
if (currentPort->c_state == IDLE) {
|
||||||
if (c == '$') {
|
if (c == '$') {
|
||||||
|
@ -2005,54 +1948,3 @@ static bool mspProcessReceivedData(uint8_t c)
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
STATIC_UNIT_TESTED void setCurrentPort(mspPort_t *port)
|
|
||||||
{
|
|
||||||
currentPort = port;
|
|
||||||
mspSerialPort = currentPort->port;
|
|
||||||
}
|
|
||||||
|
|
||||||
void mspSerialProcess(void)
|
|
||||||
{
|
|
||||||
uint8_t portIndex;
|
|
||||||
mspPort_t *candidatePort;
|
|
||||||
|
|
||||||
for (portIndex = 0; portIndex < MAX_MSP_PORT_COUNT; portIndex++) {
|
|
||||||
candidatePort = &mspPorts[portIndex];
|
|
||||||
if (!candidatePort->port) {
|
|
||||||
continue;
|
|
||||||
}
|
|
||||||
|
|
||||||
setCurrentPort(candidatePort);
|
|
||||||
// Big enough to fit a MSP_STATUS in one write.
|
|
||||||
uint8_t buf[sizeof(bufWriter_t) + 20];
|
|
||||||
writer = bufWriterInit(buf, sizeof(buf),
|
|
||||||
(bufWrite_t)serialWriteBufShim, currentPort->port);
|
|
||||||
|
|
||||||
while (serialRxBytesWaiting(mspSerialPort)) {
|
|
||||||
|
|
||||||
uint8_t c = serialRead(mspSerialPort);
|
|
||||||
bool consumed = mspProcessReceivedData(c);
|
|
||||||
|
|
||||||
if (!consumed && !ARMING_FLAG(ARMED)) {
|
|
||||||
evaluateOtherData(mspSerialPort, c);
|
|
||||||
}
|
|
||||||
|
|
||||||
if (currentPort->c_state == COMMAND_RECEIVED) {
|
|
||||||
mspProcessReceivedCommand();
|
|
||||||
break; // process one command at a time so as not to block.
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
bufWriterFlush(writer);
|
|
||||||
|
|
||||||
if (isRebootScheduled) {
|
|
||||||
waitForSerialPortToFinishTransmitting(candidatePort->port);
|
|
||||||
stopPwmAllMotors();
|
|
||||||
// On real flight controllers, systemReset() will do a soft reset of the device,
|
|
||||||
// reloading the program. But to support offline testing this flag needs to be
|
|
||||||
// cleared so that the software doesn't continuously attempt to reboot itself.
|
|
||||||
isRebootScheduled = false;
|
|
||||||
systemReset();
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
Loading…
Reference in New Issue