Merge pull request #10215 from iNavFlight/mmosca-mavlinkrc
[inav.git] / src / main / telemetry / telemetry.h
blobc88089592776c7297f1c98e8245c684e00e7bb29
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 MAVLINK_RADIO_GENERIC,
41 MAVLINK_RADIO_ELRS,
42 MAVLINK_RADIO_SIK,
43 } mavlinkRadio_e;
45 typedef enum {
46 SMARTPORT_FUEL_UNIT_PERCENT,
47 SMARTPORT_FUEL_UNIT_MAH,
48 SMARTPORT_FUEL_UNIT_MWH
49 } smartportFuelUnit_e;
51 typedef struct telemetryConfig_s {
52 uint8_t telemetry_switch; // Use aux channel to change serial output & baudrate( MSP / Telemetry ). It disables automatic switching to Telemetry when armed.
53 uint8_t telemetry_inverted; // Flip the default inversion of the protocol - Same as serialrx_inverted in rx.c, but for telemetry.
54 uint8_t frsky_pitch_roll;
55 bool frsky_use_legacy_gps_mode_sensor_ids;
56 uint8_t report_cell_voltage;
57 uint8_t hottAlarmSoundInterval;
58 uint8_t halfDuplex;
59 smartportFuelUnit_e smartportFuelUnit;
60 uint8_t ibusTelemetryType;
61 uint8_t ltmUpdateRate;
63 #ifdef USE_TELEMETRY_SIM
64 int16_t simLowAltitude;
65 char simGroundStationNumber[16];
66 char simPin[8];
67 uint16_t simTransmitInterval;
68 uint8_t simTransmitFlags;
70 uint16_t accEventThresholdHigh;
71 uint16_t accEventThresholdLow;
72 uint16_t accEventThresholdNegX;
73 #endif
74 struct {
75 uint8_t extended_status_rate;
76 uint8_t rc_channels_rate;
77 uint8_t position_rate;
78 uint8_t extra1_rate;
79 uint8_t extra2_rate;
80 uint8_t extra3_rate;
81 uint8_t version;
82 uint8_t min_txbuff;
83 uint8_t radio_type;
84 } mavlink;
85 } telemetryConfig_t;
87 PG_DECLARE(telemetryConfig_t, telemetryConfig);
89 #define TELEMETRY_SHAREABLE_PORT_FUNCTIONS_MASK (FUNCTION_TELEMETRY_LTM | FUNCTION_TELEMETRY_IBUS)
90 extern serialPort_t *telemetrySharedPort;
92 void telemetryInit(void);
93 bool telemetryCheckRxPortShared(const serialPortConfig_t *portConfig);
95 void telemetryCheckState(void);
96 void telemetryProcess(timeUs_t currentTimeUs);
98 bool telemetryDetermineEnabledState(portSharing_e portSharing);