Merge pull request #11299 from daleckystepan/vtx-start-bit
[betaflight.git] / src / main / telemetry / telemetry.c
blob2e907bfaffc2063a1725b67df612310602b2a03d
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/>.
21 #include <stddef.h>
22 #include <stdbool.h>
23 #include <stdint.h>
25 #include "platform.h"
27 #ifdef USE_TELEMETRY
29 #include "common/utils.h"
30 #include "common/unit.h"
32 #include "pg/pg.h"
33 #include "pg/pg_ids.h"
34 #include "pg/rx.h"
36 #include "drivers/timer.h"
37 #include "drivers/serial.h"
38 #include "drivers/serial_softserial.h"
40 #include "io/serial.h"
42 #include "config/config.h"
43 #include "fc/rc_modes.h"
44 #include "fc/runtime_config.h"
46 #include "msp/msp_serial.h"
48 #include "rx/rx.h"
50 #include "telemetry/telemetry.h"
51 #include "telemetry/frsky_hub.h"
52 #include "telemetry/hott.h"
53 #include "telemetry/smartport.h"
54 #include "telemetry/ltm.h"
55 #include "telemetry/jetiexbus.h"
56 #include "telemetry/mavlink.h"
57 #include "telemetry/crsf.h"
58 #include "telemetry/ghst.h"
59 #include "telemetry/srxl.h"
60 #include "telemetry/ibus.h"
61 #include "telemetry/msp_shared.h"
63 PG_REGISTER_WITH_RESET_TEMPLATE(telemetryConfig_t, telemetryConfig, PG_TELEMETRY_CONFIG, 5);
65 PG_RESET_TEMPLATE(telemetryConfig_t, telemetryConfig,
66 .telemetry_inverted = false,
67 .halfDuplex = 1,
68 .gpsNoFixLatitude = 0,
69 .gpsNoFixLongitude = 0,
70 .frsky_coordinate_format = FRSKY_FORMAT_DMS,
71 .frsky_unit = UNIT_METRIC,
72 .frsky_vfas_precision = 0,
73 .hottAlarmSoundInterval = 5,
74 .pidValuesAsTelemetry = 0,
75 .report_cell_voltage = false,
76 .flysky_sensors = {
77 IBUS_SENSOR_TYPE_TEMPERATURE,
78 IBUS_SENSOR_TYPE_RPM_FLYSKY,
79 IBUS_SENSOR_TYPE_EXTERNAL_VOLTAGE
81 .disabledSensors = ESC_SENSOR_ALL | SENSOR_CAP_USED,
82 .mavlink_mah_as_heading_divisor = 0,
85 void telemetryInit(void)
87 #ifdef USE_TELEMETRY_FRSKY_HUB
88 initFrSkyHubTelemetry();
89 #endif
90 #ifdef USE_TELEMETRY_HOTT
91 initHoTTTelemetry();
92 #endif
93 #ifdef USE_TELEMETRY_SMARTPORT
94 initSmartPortTelemetry();
95 #endif
96 #ifdef USE_TELEMETRY_LTM
97 initLtmTelemetry();
98 #endif
99 #ifdef USE_TELEMETRY_JETIEXBUS
100 initJetiExBusTelemetry();
101 #endif
102 #ifdef USE_TELEMETRY_MAVLINK
103 initMAVLinkTelemetry();
104 #endif
105 #ifdef USE_TELEMETRY_GHST
106 initGhstTelemetry();
107 #endif
108 #ifdef USE_TELEMETRY_CRSF
109 initCrsfTelemetry();
110 #if defined(USE_MSP_OVER_TELEMETRY)
111 initCrsfMspBuffer();
112 #endif
113 #endif
114 #ifdef USE_TELEMETRY_SRXL
115 initSrxlTelemetry();
116 #endif
117 #ifdef USE_TELEMETRY_IBUS
118 initIbusTelemetry();
119 #endif
120 #if defined(USE_MSP_OVER_TELEMETRY)
121 initSharedMsp();
122 #endif
124 telemetryCheckState();
127 bool telemetryDetermineEnabledState(portSharing_e portSharing)
129 bool enabled = portSharing == PORTSHARING_NOT_SHARED;
131 if (portSharing == PORTSHARING_SHARED) {
132 if (isModeActivationConditionPresent(BOXTELEMETRY))
133 enabled = IS_RC_MODE_ACTIVE(BOXTELEMETRY);
134 else
135 enabled = ARMING_FLAG(ARMED);
138 return enabled;
141 bool telemetryCheckRxPortShared(const serialPortConfig_t *portConfig, const SerialRXType serialrxProvider)
143 if (portConfig->functionMask & FUNCTION_RX_SERIAL && portConfig->functionMask & TELEMETRY_SHAREABLE_PORT_FUNCTIONS_MASK &&
144 (serialrxProvider == SERIALRX_SPEKTRUM1024 ||
145 serialrxProvider == SERIALRX_SPEKTRUM2048 ||
146 serialrxProvider == SERIALRX_SBUS ||
147 serialrxProvider == SERIALRX_SUMD ||
148 serialrxProvider == SERIALRX_SUMH ||
149 serialrxProvider == SERIALRX_XBUS_MODE_B ||
150 serialrxProvider == SERIALRX_XBUS_MODE_B_RJ01 ||
151 serialrxProvider == SERIALRX_IBUS)) {
153 return true;
155 #ifdef USE_TELEMETRY_IBUS
156 if (portConfig->functionMask & FUNCTION_TELEMETRY_IBUS
157 && portConfig->functionMask & FUNCTION_RX_SERIAL
158 && serialrxProvider == SERIALRX_IBUS) {
159 // IBUS serial RX & telemetry
160 return true;
162 #endif
163 return false;
166 serialPort_t *telemetrySharedPort = NULL;
168 void telemetryCheckState(void)
170 #ifdef USE_TELEMETRY_FRSKY_HUB
171 checkFrSkyHubTelemetryState();
172 #endif
173 #ifdef USE_TELEMETRY_HOTT
174 checkHoTTTelemetryState();
175 #endif
176 #ifdef USE_TELEMETRY_SMARTPORT
177 checkSmartPortTelemetryState();
178 #endif
179 #ifdef USE_TELEMETRY_LTM
180 checkLtmTelemetryState();
181 #endif
182 #ifdef USE_TELEMETRY_JETIEXBUS
183 checkJetiExBusTelemetryState();
184 #endif
185 #ifdef USE_TELEMETRY_MAVLINK
186 checkMAVLinkTelemetryState();
187 #endif
188 #ifdef USE_TELEMETRY_CRSF
189 checkCrsfTelemetryState();
190 #endif
191 #ifdef USE_TELEMETRY_GHST
192 checkGhstTelemetryState();
193 #endif
194 #ifdef USE_TELEMETRY_SRXL
195 checkSrxlTelemetryState();
196 #endif
197 #ifdef USE_TELEMETRY_IBUS
198 checkIbusTelemetryState();
199 #endif
202 void telemetryProcess(uint32_t currentTime)
204 #ifdef USE_TELEMETRY_FRSKY_HUB
205 handleFrSkyHubTelemetry(currentTime);
206 #else
207 UNUSED(currentTime);
208 #endif
209 #ifdef USE_TELEMETRY_HOTT
210 handleHoTTTelemetry(currentTime);
211 #else
212 UNUSED(currentTime);
213 #endif
214 #ifdef USE_TELEMETRY_SMARTPORT
215 handleSmartPortTelemetry();
216 #endif
217 #ifdef USE_TELEMETRY_LTM
218 handleLtmTelemetry();
219 #endif
220 #ifdef USE_TELEMETRY_JETIEXBUS
221 handleJetiExBusTelemetry();
222 #endif
223 #ifdef USE_TELEMETRY_MAVLINK
224 handleMAVLinkTelemetry();
225 #endif
226 #ifdef USE_TELEMETRY_CRSF
227 handleCrsfTelemetry(currentTime);
228 #endif
229 #ifdef USE_TELEMETRY_GHST
230 handleGhstTelemetry(currentTime);
231 #endif
232 #ifdef USE_TELEMETRY_SRXL
233 handleSrxlTelemetry(currentTime);
234 #endif
235 #ifdef USE_TELEMETRY_IBUS
236 handleIbusTelemetry();
237 #endif
240 bool telemetryIsSensorEnabled(sensor_e sensor)
242 return ~(telemetryConfig()->disabledSensors) & sensor;
244 #endif