Merge pull request #10313 from P-I-Engineer/patch-1
[inav.git] / src / main / telemetry / telemetry.h
blobc7edad973b86170c1d0dbdc1a49db39a8773136e
1 /*
2 * This file is part of Cleanflight.
4 * Cleanflight is free software: you can redistribute it and/or modify
5 * it under the terms of the GNU General Public License as published by
6 * the Free Software Foundation, either version 3 of the License, or
7 * (at your option) any later version.
9 * Cleanflight is distributed in the hope that it will be useful,
10 * but WITHOUT ANY WARRANTY; without even the implied warranty of
11 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 * GNU General Public License for more details.
14 * You should have received a copy of the GNU General Public License
15 * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
19 * telemetry.h
21 * Created on: 6 Apr 2014
22 * Author: Hydra
25 #pragma once
27 #include "common/time.h"
29 #include "config/parameter_group.h"
31 #include "io/serial.h"
33 typedef enum {
34 LTM_RATE_NORMAL,
35 LTM_RATE_MEDIUM,
36 LTM_RATE_SLOW
37 } ltmUpdateRate_e;
39 typedef enum {
40 SMARTPORT_FUEL_UNIT_PERCENT,
41 SMARTPORT_FUEL_UNIT_MAH,
42 SMARTPORT_FUEL_UNIT_MWH
43 } smartportFuelUnit_e;
45 typedef struct telemetryConfig_s {
46 uint8_t telemetry_switch; // Use aux channel to change serial output & baudrate( MSP / Telemetry ). It disables automatic switching to Telemetry when armed.
47 uint8_t telemetry_inverted; // Flip the default inversion of the protocol - Same as serialrx_inverted in rx.c, but for telemetry.
48 uint8_t frsky_pitch_roll;
49 uint8_t report_cell_voltage;
50 uint8_t hottAlarmSoundInterval;
51 uint8_t halfDuplex;
52 smartportFuelUnit_e smartportFuelUnit;
53 uint8_t ibusTelemetryType;
54 uint8_t ltmUpdateRate;
56 #ifdef USE_TELEMETRY_SIM
57 int16_t simLowAltitude;
58 char simGroundStationNumber[16];
59 char simPin[8];
60 uint16_t simTransmitInterval;
61 uint8_t simTransmitFlags;
63 uint16_t accEventThresholdHigh;
64 uint16_t accEventThresholdLow;
65 uint16_t accEventThresholdNegX;
66 #endif
67 struct {
68 uint8_t extended_status_rate;
69 uint8_t rc_channels_rate;
70 uint8_t position_rate;
71 uint8_t extra1_rate;
72 uint8_t extra2_rate;
73 uint8_t extra3_rate;
74 uint8_t version;
75 } mavlink;
76 } telemetryConfig_t;
78 PG_DECLARE(telemetryConfig_t, telemetryConfig);
80 #define TELEMETRY_SHAREABLE_PORT_FUNCTIONS_MASK (FUNCTION_TELEMETRY_LTM | FUNCTION_TELEMETRY_IBUS)
81 extern serialPort_t *telemetrySharedPort;
83 void telemetryInit(void);
84 bool telemetryCheckRxPortShared(const serialPortConfig_t *portConfig);
86 void telemetryCheckState(void);
87 void telemetryProcess(timeUs_t currentTimeUs);
89 bool telemetryDetermineEnabledState(portSharing_e portSharing);