mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-16 04:45:24 +03:00
Merge remote-tracking branch 'upstream/master' into blackbox-flash
This commit is contained in:
commit
ebff1bdcd7
18 changed files with 290 additions and 84 deletions
|
@ -45,6 +45,8 @@
|
|||
#include "flight/mixer.h"
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/navigation.h"
|
||||
#include "flight/altitudehold.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
#include "rx/msp.h"
|
||||
#include "io/escservo.h"
|
||||
|
@ -55,9 +57,11 @@
|
|||
#include "io/ledstrip.h"
|
||||
#include "io/flashfs.h"
|
||||
#include "telemetry/telemetry.h"
|
||||
|
||||
#include "sensors/boardalignment.h"
|
||||
#include "sensors/sensors.h"
|
||||
#include "sensors/battery.h"
|
||||
#include "sensors/sonar.h"
|
||||
#include "sensors/acceleration.h"
|
||||
#include "sensors/barometer.h"
|
||||
#include "sensors/compass.h"
|
||||
|
@ -204,6 +208,10 @@ const char *boardIdentifier = TARGET_BOARD_IDENTIFIER;
|
|||
#define MSP_VOLTAGE_METER_CONFIG 56
|
||||
#define MSP_SET_VOLTAGE_METER_CONFIG 57
|
||||
|
||||
#define MSP_SONAR_ALTITUDE 58 //out message get sonar altitude [cm]
|
||||
|
||||
#define MSP_PID_CONTROLLER 59
|
||||
#define MSP_SET_PID_CONTROLLER 60
|
||||
//
|
||||
// Baseflight MSP commands (if enabled they exist in Cleanflight)
|
||||
//
|
||||
|
@ -373,7 +381,7 @@ static mspPort_t mspPorts[MAX_MSP_PORT_COUNT];
|
|||
|
||||
static mspPort_t *currentPort;
|
||||
|
||||
void serialize32(uint32_t a)
|
||||
static void serialize32(uint32_t a)
|
||||
{
|
||||
static uint8_t t;
|
||||
t = a;
|
||||
|
@ -390,7 +398,7 @@ void serialize32(uint32_t a)
|
|||
currentPort->checksum ^= t;
|
||||
}
|
||||
|
||||
void serialize16(int16_t a)
|
||||
static void serialize16(int16_t a)
|
||||
{
|
||||
static uint8_t t;
|
||||
t = a;
|
||||
|
@ -401,32 +409,32 @@ void serialize16(int16_t a)
|
|||
currentPort->checksum ^= t;
|
||||
}
|
||||
|
||||
void serialize8(uint8_t a)
|
||||
static void serialize8(uint8_t a)
|
||||
{
|
||||
serialWrite(mspSerialPort, a);
|
||||
currentPort->checksum ^= a;
|
||||
}
|
||||
|
||||
uint8_t read8(void)
|
||||
static uint8_t read8(void)
|
||||
{
|
||||
return currentPort->inBuf[currentPort->indRX++] & 0xff;
|
||||
}
|
||||
|
||||
uint16_t read16(void)
|
||||
static uint16_t read16(void)
|
||||
{
|
||||
uint16_t t = read8();
|
||||
t += (uint16_t)read8() << 8;
|
||||
return t;
|
||||
}
|
||||
|
||||
uint32_t read32(void)
|
||||
static uint32_t read32(void)
|
||||
{
|
||||
uint32_t t = read16();
|
||||
t += (uint32_t)read16() << 16;
|
||||
return t;
|
||||
}
|
||||
|
||||
void headSerialResponse(uint8_t err, uint8_t responseBodySize)
|
||||
static void headSerialResponse(uint8_t err, uint8_t responseBodySize)
|
||||
{
|
||||
serialize8('$');
|
||||
serialize8('M');
|
||||
|
@ -436,36 +444,36 @@ void headSerialResponse(uint8_t err, uint8_t responseBodySize)
|
|||
serialize8(currentPort->cmdMSP);
|
||||
}
|
||||
|
||||
void headSerialReply(uint8_t responseBodySize)
|
||||
static void headSerialReply(uint8_t responseBodySize)
|
||||
{
|
||||
headSerialResponse(0, responseBodySize);
|
||||
}
|
||||
|
||||
void headSerialError(uint8_t responseBodySize)
|
||||
static void headSerialError(uint8_t responseBodySize)
|
||||
{
|
||||
headSerialResponse(1, responseBodySize);
|
||||
}
|
||||
|
||||
void tailSerialReply(void)
|
||||
static void tailSerialReply(void)
|
||||
{
|
||||
serialize8(currentPort->checksum);
|
||||
}
|
||||
|
||||
void s_struct(uint8_t *cb, uint8_t siz)
|
||||
static void s_struct(uint8_t *cb, uint8_t siz)
|
||||
{
|
||||
headSerialReply(siz);
|
||||
while (siz--)
|
||||
serialize8(*cb++);
|
||||
}
|
||||
|
||||
void serializeNames(const char *s)
|
||||
static void serializeNames(const char *s)
|
||||
{
|
||||
const char *c;
|
||||
for (c = s; *c; c++)
|
||||
serialize8(*c);
|
||||
}
|
||||
|
||||
const box_t *findBoxByActiveBoxId(uint8_t activeBoxId)
|
||||
static const box_t *findBoxByActiveBoxId(uint8_t activeBoxId)
|
||||
{
|
||||
uint8_t boxIndex;
|
||||
const box_t *candidate;
|
||||
|
@ -478,7 +486,7 @@ const box_t *findBoxByActiveBoxId(uint8_t activeBoxId)
|
|||
return NULL;
|
||||
}
|
||||
|
||||
const box_t *findBoxByPermenantId(uint8_t permenantId)
|
||||
static const box_t *findBoxByPermenantId(uint8_t permenantId)
|
||||
{
|
||||
uint8_t boxIndex;
|
||||
const box_t *candidate;
|
||||
|
@ -491,7 +499,7 @@ const box_t *findBoxByPermenantId(uint8_t permenantId)
|
|||
return NULL;
|
||||
}
|
||||
|
||||
void serializeBoxNamesReply(void)
|
||||
static void serializeBoxNamesReply(void)
|
||||
{
|
||||
int i, activeBoxId, j, flag = 1, count = 0, len;
|
||||
const box_t *box;
|
||||
|
@ -523,7 +531,7 @@ reset:
|
|||
}
|
||||
}
|
||||
|
||||
void serializeDataflashSummaryReply(void)
|
||||
static void serializeDataflashSummaryReply(void)
|
||||
{
|
||||
#ifdef FLASHFS
|
||||
const flashGeometry_t *geometry = flashfsGetGeometry();
|
||||
|
@ -538,7 +546,7 @@ void serializeDataflashSummaryReply(void)
|
|||
}
|
||||
|
||||
#ifdef FLASHFS
|
||||
void serializeDataflashReadReply(uint32_t address, uint8_t size)
|
||||
static void serializeDataflashReadReply(uint32_t address, uint8_t size)
|
||||
{
|
||||
enum { DATAFLASH_READ_REPLY_CHUNK_SIZE = 128 };
|
||||
|
||||
|
@ -668,7 +676,7 @@ void mspInit(serialConfig_t *serialConfig)
|
|||
activeBoxIds[activeBoxIdCount++] = BOXLEDLOW;
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
if (feature(FEATURE_INFLIGHT_ACC_CAL))
|
||||
activeBoxIds[activeBoxIdCount++] = BOXCALIB;
|
||||
|
||||
|
@ -695,7 +703,6 @@ static bool processOutCommand(uint8_t cmdMSP)
|
|||
{
|
||||
uint32_t i, tmp, junk;
|
||||
|
||||
|
||||
#ifdef GPS
|
||||
uint8_t wp_no;
|
||||
int32_t lat = 0, lon = 0;
|
||||
|
@ -864,18 +871,30 @@ static bool processOutCommand(uint8_t cmdMSP)
|
|||
break;
|
||||
case MSP_ALTITUDE:
|
||||
headSerialReply(6);
|
||||
serialize32(EstAlt);
|
||||
#if defined(BARO) || defined(SONAR)
|
||||
serialize32(altitudeHoldGetEstimatedAltitude());
|
||||
#else
|
||||
serialize32(0);
|
||||
#endif
|
||||
serialize16(vario);
|
||||
break;
|
||||
case MSP_SONAR_ALTITUDE:
|
||||
headSerialReply(4);
|
||||
#if defined(SONAR)
|
||||
serialize32(sonarGetLatestAltitude());
|
||||
#else
|
||||
serialize32(0);
|
||||
#endif
|
||||
break;
|
||||
case MSP_ANALOG:
|
||||
headSerialReply(7);
|
||||
serialize8((uint8_t)constrain(vbat, 0, 255));
|
||||
serialize16((uint16_t)constrain(mAhDrawn, 0, 0xFFFF)); // milliamphours drawn from battery
|
||||
serialize16(rssi);
|
||||
if(masterConfig.batteryConfig.multiwiiCurrentMeterOutput) {
|
||||
serialize16((uint16_t)constrain((ABS(amperage) * 10), 0, 0xFFFF)); // send amperage in 0.001 A steps
|
||||
serialize16((uint16_t)constrain(amperage * 10, 0, 0xFFFF)); // send amperage in 0.001 A steps. Negative range is truncated to zero
|
||||
} else
|
||||
serialize16((uint16_t)constrain(ABS(amperage), 0, 0xFFFF)); // send amperage in 0.01 A steps
|
||||
serialize16((int16_t)constrain(amperage, -0x8000, 0x7FFF)); // send amperage in 0.01 A steps, range is -320A to 320A
|
||||
break;
|
||||
case MSP_RC_TUNING:
|
||||
headSerialReply(7);
|
||||
|
@ -918,6 +937,10 @@ static bool processOutCommand(uint8_t cmdMSP)
|
|||
headSerialReply(sizeof(pidnames) - 1);
|
||||
serializeNames(pidnames);
|
||||
break;
|
||||
case MSP_PID_CONTROLLER:
|
||||
headSerialReply(1);
|
||||
serialize8(currentProfile->pidController);
|
||||
break;
|
||||
case MSP_MODE_RANGES:
|
||||
headSerialReply(4 * MAX_MODE_ACTIVATION_CONDITION_COUNT);
|
||||
for (i = 0; i < MAX_MODE_ACTIVATION_CONDITION_COUNT; i++) {
|
||||
|
@ -1240,6 +1263,10 @@ static bool processInCommand(void)
|
|||
currentProfile->accelerometerTrims.values.pitch = read16();
|
||||
currentProfile->accelerometerTrims.values.roll = read16();
|
||||
break;
|
||||
case MSP_SET_PID_CONTROLLER:
|
||||
currentProfile->pidController = read8();
|
||||
setPIDController(currentProfile->pidController);
|
||||
break;
|
||||
case MSP_SET_PID:
|
||||
if (currentProfile->pidController == 2) {
|
||||
for (i = 0; i < 3; i++) {
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue