1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-23 16:25:31 +03:00

Replaced #include with forward reference

This commit is contained in:
Martin Budden 2016-07-12 09:10:37 +01:00
parent 84cf4eb2e1
commit 57372cf234

View file

@ -21,10 +21,8 @@
* Created on: 6 Apr 2014
* Author: Hydra
*/
#include "rx/rx.h"
#ifndef TELEMETRY_COMMON_H_
#define TELEMETRY_COMMON_H_
#pragma once
typedef enum {
FRSKY_FORMAT_DMS = 0,
@ -39,9 +37,9 @@ typedef enum {
typedef struct telemetryConfig_s {
uint8_t telemetry_switch; // Use aux channel to change serial output & baudrate( MSP / Telemetry ). It disables automatic switching to Telemetry when armed.
uint8_t telemetry_inversion; // also shared with smartport inversion
float gpsNoFixLatitude;
float gpsNoFixLongitude;
frskyGpsCoordFormat_e frsky_coordinate_format;
float gpsNoFixLatitude;
float gpsNoFixLongitude;
frskyGpsCoordFormat_e frsky_coordinate_format;
frskyUnit_e frsky_unit;
uint8_t frsky_vfas_precision;
uint8_t frsky_vfas_cell_voltage;
@ -52,7 +50,8 @@ bool telemetryCheckRxPortShared(serialPortConfig_t *portConfig);
extern serialPort_t *telemetrySharedPort;
void telemetryCheckState(void);
void telemetryProcess(rxConfig_t *rxConfig, uint16_t deadband3d_throttle);
struct rxConfig_s;
void telemetryProcess(struct rxConfig_s *rxConfig, uint16_t deadband3d_throttle);
bool telemetryDetermineEnabledState(portSharing_e portSharing);
@ -60,4 +59,3 @@ void telemetryUseConfig(telemetryConfig_t *telemetryConfig);
#define TELEMETRY_SHAREABLE_PORT_FUNCTIONS_MASK (FUNCTION_TELEMETRY_FRSKY | FUNCTION_TELEMETRY_LTM)
#endif /* TELEMETRY_COMMON_H_ */