mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-21 15:25:36 +03:00
Merge branch 'master-cleanflight-msptelemetry' of github.com:treymarc/baseflight into treymarc-master-cleanflight-msptelemetry
Conflicts: src/serial_msp.h src/telemetry_common.h
This commit is contained in:
commit
e5c5339306
7 changed files with 106 additions and 2 deletions
1
Makefile
1
Makefile
|
@ -129,6 +129,7 @@ COMMON_SRC = build_config.c \
|
||||||
telemetry_common.c \
|
telemetry_common.c \
|
||||||
telemetry_frsky.c \
|
telemetry_frsky.c \
|
||||||
telemetry_hott.c \
|
telemetry_hott.c \
|
||||||
|
telemetry_msp.c \
|
||||||
serial_common.c \
|
serial_common.c \
|
||||||
serial_cli.c \
|
serial_cli.c \
|
||||||
serial_msp.c \
|
serial_msp.c \
|
||||||
|
|
|
@ -801,3 +801,54 @@ void mspProcess(void)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void sendMspTelemetry(void)
|
||||||
|
{
|
||||||
|
static int state = -1;
|
||||||
|
|
||||||
|
switch (state) {
|
||||||
|
default:
|
||||||
|
cmdMSP = MSP_BOXNAMES;
|
||||||
|
evaluateCommand();
|
||||||
|
case 0:
|
||||||
|
cmdMSP = MSP_STATUS;
|
||||||
|
evaluateCommand();
|
||||||
|
cmdMSP = MSP_IDENT;
|
||||||
|
evaluateCommand();
|
||||||
|
state++;
|
||||||
|
break;
|
||||||
|
case 1:
|
||||||
|
cmdMSP = MSP_RAW_IMU;
|
||||||
|
evaluateCommand();
|
||||||
|
state++;
|
||||||
|
break;
|
||||||
|
case 2:
|
||||||
|
cmdMSP = MSP_DEBUG;
|
||||||
|
evaluateCommand();
|
||||||
|
cmdMSP = MSP_ALTITUDE;
|
||||||
|
evaluateCommand();
|
||||||
|
state++;
|
||||||
|
break;
|
||||||
|
case 3:
|
||||||
|
cmdMSP = MSP_RAW_GPS;
|
||||||
|
evaluateCommand();
|
||||||
|
cmdMSP = MSP_RC;
|
||||||
|
evaluateCommand();
|
||||||
|
state++;
|
||||||
|
break;
|
||||||
|
case 4:
|
||||||
|
cmdMSP = MSP_MOTOR_PINS;
|
||||||
|
evaluateCommand();
|
||||||
|
cmdMSP = MSP_ATTITUDE;
|
||||||
|
evaluateCommand();
|
||||||
|
state++;
|
||||||
|
break;
|
||||||
|
case 5:
|
||||||
|
cmdMSP = MSP_SERVO;
|
||||||
|
evaluateCommand();
|
||||||
|
state=0;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
|
|
|
@ -1,4 +1,4 @@
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
void mspProcess(void);
|
void mspProcess(void);
|
||||||
|
void sendMspTelemetry(void);
|
||||||
|
|
|
@ -16,6 +16,7 @@
|
||||||
#include "telemetry_common.h"
|
#include "telemetry_common.h"
|
||||||
#include "telemetry_frsky.h"
|
#include "telemetry_frsky.h"
|
||||||
#include "telemetry_hott.h"
|
#include "telemetry_hott.h"
|
||||||
|
#include "telemetry_msp.h"
|
||||||
|
|
||||||
|
|
||||||
static bool isTelemetryConfigurationValid = false; // flag used to avoid repeated configuration checks
|
static bool isTelemetryConfigurationValid = false; // flag used to avoid repeated configuration checks
|
||||||
|
@ -39,6 +40,11 @@ bool isTelemetryProviderHoTT(void)
|
||||||
return telemetryConfig->telemetry_provider == TELEMETRY_PROVIDER_HOTT;
|
return telemetryConfig->telemetry_provider == TELEMETRY_PROVIDER_HOTT;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool isTelemetryProviderMSP(void)
|
||||||
|
{
|
||||||
|
return telemetryConfig->telemetry_provider == TELEMETRY_PROVIDER_MSP;
|
||||||
|
}
|
||||||
|
|
||||||
bool canUseTelemetryWithCurrentConfiguration(void)
|
bool canUseTelemetryWithCurrentConfiguration(void)
|
||||||
{
|
{
|
||||||
if (!feature(FEATURE_TELEMETRY)) {
|
if (!feature(FEATURE_TELEMETRY)) {
|
||||||
|
@ -65,6 +71,10 @@ void initTelemetry()
|
||||||
initHoTTTelemetry(telemetryConfig);
|
initHoTTTelemetry(telemetryConfig);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (isTelemetryProviderMSP()) {
|
||||||
|
initMSPTelemetry(telemetryConfig);
|
||||||
|
}
|
||||||
|
|
||||||
checkTelemetryState();
|
checkTelemetryState();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -154,4 +164,8 @@ void handleTelemetry(void)
|
||||||
if (isTelemetryProviderHoTT()) {
|
if (isTelemetryProviderHoTT()) {
|
||||||
handleHoTTTelemetry();
|
handleHoTTTelemetry();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (isTelemetryProviderMSP()) {
|
||||||
|
handleMSPTelemetry();
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -11,7 +11,8 @@
|
||||||
typedef enum {
|
typedef enum {
|
||||||
TELEMETRY_PROVIDER_FRSKY = 0,
|
TELEMETRY_PROVIDER_FRSKY = 0,
|
||||||
TELEMETRY_PROVIDER_HOTT,
|
TELEMETRY_PROVIDER_HOTT,
|
||||||
TELEMETRY_PROVIDER_MAX = TELEMETRY_PROVIDER_HOTT
|
TELEMETRY_PROVIDER_MSP,
|
||||||
|
TELEMETRY_PROVIDER_MAX = TELEMETRY_PROVIDER_MSP
|
||||||
} telemetryProvider_e;
|
} telemetryProvider_e;
|
||||||
|
|
||||||
typedef struct telemetryConfig_s {
|
typedef struct telemetryConfig_s {
|
||||||
|
|
22
src/telemetry_msp.c
Normal file
22
src/telemetry_msp.c
Normal file
|
@ -0,0 +1,22 @@
|
||||||
|
/*
|
||||||
|
* telemetry_MSP.c
|
||||||
|
*
|
||||||
|
* Created on: 22 Apr 2014
|
||||||
|
* Author: trey marc
|
||||||
|
*/
|
||||||
|
#include <stdbool.h>
|
||||||
|
#include <stdint.h>
|
||||||
|
#include <string.h>
|
||||||
|
|
||||||
|
#include "drivers/serial_common.h"
|
||||||
|
#include "telemetry_common.h"
|
||||||
|
#include "serial_msp.h"
|
||||||
|
|
||||||
|
void initMSPTelemetry(telemetryConfig_t *initialTelemetryConfig)
|
||||||
|
{
|
||||||
|
}
|
||||||
|
|
||||||
|
void handleMSPTelemetry(void)
|
||||||
|
{
|
||||||
|
sendMspTelemetry();
|
||||||
|
}
|
15
src/telemetry_msp.h
Normal file
15
src/telemetry_msp.h
Normal file
|
@ -0,0 +1,15 @@
|
||||||
|
/*
|
||||||
|
* telemetry_MSP.h
|
||||||
|
*
|
||||||
|
* Created on: 22 Apr 2014
|
||||||
|
* Author: trey marc
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef TELEMETRY_MSP_H_
|
||||||
|
#define TELEMETRY_MSP_H_
|
||||||
|
|
||||||
|
void initMSPTelemetry(telemetryConfig_t *initialTelemetryConfig);
|
||||||
|
void handleMSPTelemetry(void);
|
||||||
|
|
||||||
|
|
||||||
|
#endif /* TELEMETRY_MSP_H_ */
|
Loading…
Add table
Add a link
Reference in a new issue