add msp telemtry
This commit is contained in:
parent
1092fa5b40
commit
b14b058fa0
1
Makefile
1
Makefile
|
@ -82,6 +82,7 @@ COMMON_SRC = startup_stm32f10x_md_gcc.S \
|
|||
telemetry_common.c \
|
||||
telemetry_frsky.c \
|
||||
telemetry_hott.c \
|
||||
telemetry_msp.c \
|
||||
serial_common.c \
|
||||
serial_cli.c \
|
||||
serial_msp.c \
|
||||
|
|
|
@ -715,3 +715,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;
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
|
|
|
@ -2,4 +2,4 @@
|
|||
|
||||
void mspProcess(void);
|
||||
void mspInit(void);
|
||||
|
||||
void sendMspTelemetry(void);
|
||||
|
|
|
@ -6,6 +6,7 @@
|
|||
|
||||
#include "telemetry_frsky.h"
|
||||
#include "telemetry_hott.h"
|
||||
#include "telemetry_msp.h"
|
||||
|
||||
#include "telemetry_common.h"
|
||||
|
||||
|
@ -21,6 +22,10 @@ bool isTelemetryProviderHoTT(void)
|
|||
return masterConfig.telemetry_provider == TELEMETRY_PROVIDER_HOTT;
|
||||
}
|
||||
|
||||
bool isTelemetryProviderMSP(void)
|
||||
{
|
||||
return masterConfig.telemetry_provider == TELEMETRY_PROVIDER_MSP;
|
||||
}
|
||||
bool canUseTelemetryWithCurrentConfiguration(void)
|
||||
{
|
||||
if (!feature(FEATURE_TELEMETRY)) {
|
||||
|
@ -145,4 +150,7 @@ void handleTelemetry(void)
|
|||
if (isTelemetryProviderHoTT()) {
|
||||
handleHoTTTelemetry();
|
||||
}
|
||||
if (isTelemetryProviderMSP()) {
|
||||
handleMSPTelemetry();
|
||||
}
|
||||
}
|
||||
|
|
|
@ -11,7 +11,8 @@
|
|||
typedef enum {
|
||||
TELEMETRY_PROVIDER_FRSKY = 0,
|
||||
TELEMETRY_PROVIDER_HOTT,
|
||||
TELEMETRY_PROVIDER_MAX = TELEMETRY_PROVIDER_HOTT
|
||||
TELEMETRY_PROVIDER_MSP,
|
||||
TELEMETRY_PROVIDER_MAX = TELEMETRY_PROVIDER_MSP
|
||||
} TelemetryProvider;
|
||||
|
||||
typedef enum {
|
||||
|
|
|
@ -0,0 +1,13 @@
|
|||
/*
|
||||
* telemetry_MSP.c
|
||||
*
|
||||
* Created on: 22 Apr 2014
|
||||
* Author: trey marc
|
||||
*/
|
||||
|
||||
#include "serial_msp.h"
|
||||
|
||||
void handleMSPTelemetry(void)
|
||||
{
|
||||
sendMspTelemetry();
|
||||
}
|
|
@ -0,0 +1,14 @@
|
|||
/*
|
||||
* telemetry_MSP.h
|
||||
*
|
||||
* Created on: 22 Apr 2014
|
||||
* Author: trey marc
|
||||
*/
|
||||
|
||||
#ifndef TELEMETRY_MSP_H_
|
||||
#define TELEMETRY_MSP_H_
|
||||
|
||||
void handleMSPTelemetry(void);
|
||||
|
||||
|
||||
#endif /* TELEMETRY_MSP_H_ */
|
Loading…
Reference in New Issue