Merge pull request #11299 from daleckystepan/vtx-start-bit
[betaflight.git] / src / main / telemetry / telemetry.h
blobe11f1f1c3208f486dfb16a4d4442becd4f89e7d5
1 /*
2 * This file is part of Cleanflight and Betaflight.
4 * Cleanflight and Betaflight are free software. You can redistribute
5 * this software and/or modify this software under the terms of the
6 * GNU General Public License as published by the Free Software
7 * Foundation, either version 3 of the License, or (at your option)
8 * any later version.
10 * Cleanflight and Betaflight are distributed in the hope that they
11 * will be useful, but WITHOUT ANY WARRANTY; without even the implied
12 * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
13 * See the GNU General Public License for more details.
15 * You should have received a copy of the GNU General Public License
16 * along with this software.
18 * If not, see <http://www.gnu.org/licenses/>.
22 * telemetry.h
24 * Created on: 6 Apr 2014
25 * Author: Hydra
28 #pragma once
30 #include "common/unit.h"
32 #include "io/serial.h"
34 #include "pg/pg.h"
36 #include "rx/rx.h"
38 #include "telemetry/ibus_shared.h"
40 typedef enum {
41 FRSKY_FORMAT_DMS = 0,
42 FRSKY_FORMAT_NMEA
43 } frskyGpsCoordFormat_e;
45 typedef enum {
46 SENSOR_VOLTAGE = 1 << 0,
47 SENSOR_CURRENT = 1 << 1,
48 SENSOR_FUEL = 1 << 2,
49 SENSOR_MODE = 1 << 3,
50 SENSOR_ACC_X = 1 << 4,
51 SENSOR_ACC_Y = 1 << 5,
52 SENSOR_ACC_Z = 1 << 6,
53 SENSOR_PITCH = 1 << 7,
54 SENSOR_ROLL = 1 << 8,
55 SENSOR_HEADING = 1 << 9,
56 SENSOR_ALTITUDE = 1 << 10,
57 SENSOR_VARIO = 1 << 11,
58 SENSOR_LAT_LONG = 1 << 12,
59 SENSOR_GROUND_SPEED = 1 << 13,
60 SENSOR_DISTANCE = 1 << 14,
61 ESC_SENSOR_CURRENT = 1 << 15,
62 ESC_SENSOR_VOLTAGE = 1 << 16,
63 ESC_SENSOR_RPM = 1 << 17,
64 ESC_SENSOR_TEMPERATURE = 1 << 18,
65 ESC_SENSOR_ALL = ESC_SENSOR_CURRENT \
66 | ESC_SENSOR_VOLTAGE \
67 | ESC_SENSOR_RPM \
68 | ESC_SENSOR_TEMPERATURE,
69 SENSOR_TEMPERATURE = 1 << 19,
70 SENSOR_CAP_USED = 1 << 20,
71 SENSOR_ALL = (1 << 21) - 1,
72 } sensor_e;
74 typedef struct telemetryConfig_s {
75 int16_t gpsNoFixLatitude;
76 int16_t gpsNoFixLongitude;
77 uint8_t telemetry_inverted;
78 uint8_t halfDuplex;
79 uint8_t frsky_coordinate_format;
80 uint8_t frsky_unit;
81 uint8_t frsky_vfas_precision;
82 uint8_t hottAlarmSoundInterval;
83 uint8_t pidValuesAsTelemetry;
84 uint8_t report_cell_voltage;
85 uint8_t flysky_sensors[IBUS_SENSOR_COUNT];
86 uint16_t mavlink_mah_as_heading_divisor;
87 uint32_t disabledSensors; // bit flags
88 } telemetryConfig_t;
90 PG_DECLARE(telemetryConfig_t, telemetryConfig);
92 extern serialPort_t *telemetrySharedPort;
94 void telemetryInit(void);
95 bool telemetryCheckRxPortShared(const serialPortConfig_t *portConfig, const SerialRXType serialrxProvider);
97 void telemetryCheckState(void);
98 void telemetryProcess(uint32_t currentTime);
100 bool telemetryDetermineEnabledState(portSharing_e portSharing);
102 bool telemetryIsSensorEnabled(sensor_e sensor);