CF/BF - Fix HoTT telemetry.
[betaflight.git] / src / main / telemetry / telemetry.c
blobe3fceff50fa811d6c897cf223c224afca1e42d1a
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/>.
18 #include <stddef.h>
19 #include <stdbool.h>
20 #include <stdint.h>
22 #include "platform.h"
24 #ifdef TELEMETRY
26 #include "common/utils.h"
28 #include "config/parameter_group.h"
29 #include "config/parameter_group_ids.h"
31 #include "drivers/timer.h"
32 #include "drivers/serial.h"
33 #include "drivers/serial_softserial.h"
35 #include "io/serial.h"
37 #include "fc/config.h"
38 #include "fc/rc_controls.h"
39 #include "fc/runtime_config.h"
41 #include "msp/msp_serial.h"
43 #include "rx/rx.h"
45 #include "telemetry/telemetry.h"
46 #include "telemetry/frsky.h"
47 #include "telemetry/hott.h"
48 #include "telemetry/smartport.h"
49 #include "telemetry/ltm.h"
50 #include "telemetry/jetiexbus.h"
51 #include "telemetry/mavlink.h"
52 #include "telemetry/crsf.h"
53 #include "telemetry/srxl.h"
54 #include "telemetry/ibus.h"
57 PG_REGISTER_WITH_RESET_TEMPLATE(telemetryConfig_t, telemetryConfig, PG_TELEMETRY_CONFIG, 0);
59 #if defined(STM32F3)
60 #define TELEMETRY_DEFAULT_INVERSION 1
61 #else
62 #define TELEMETRY_DEFAULT_INVERSION 0
63 #endif
65 PG_RESET_TEMPLATE(telemetryConfig_t, telemetryConfig,
66 .telemetry_inversion = TELEMETRY_DEFAULT_INVERSION,
67 .halfDuplex = 1,
68 .telemetry_switch = 0,
69 .gpsNoFixLatitude = 0,
70 .gpsNoFixLongitude = 0,
71 .frsky_coordinate_format = FRSKY_FORMAT_DMS,
72 .frsky_unit = FRSKY_UNIT_METRICS,
73 .frsky_vfas_precision = 0,
74 .frsky_vfas_cell_voltage = 0,
75 .hottAlarmSoundInterval = 5,
76 .pidValuesAsTelemetry = 0,
77 .report_cell_voltage = false
80 void telemetryInit(void)
82 #ifdef TELEMETRY_FRSKY
83 initFrSkyTelemetry();
84 #endif
85 #ifdef TELEMETRY_HOTT
86 initHoTTTelemetry();
87 #endif
88 #ifdef TELEMETRY_SMARTPORT
89 initSmartPortTelemetry();
90 #endif
91 #ifdef TELEMETRY_LTM
92 initLtmTelemetry();
93 #endif
94 #ifdef TELEMETRY_JETIEXBUS
95 initJetiExBusTelemetry();
96 #endif
97 #ifdef TELEMETRY_MAVLINK
98 initMAVLinkTelemetry();
99 #endif
100 #ifdef TELEMETRY_CRSF
101 initCrsfTelemetry();
102 #endif
103 #ifdef TELEMETRY_SRXL
104 initSrxlTelemetry();
105 #endif
106 #ifdef TELEMETRY_IBUS
107 initIbusTelemetry();
108 #endif
110 telemetryCheckState();
113 bool telemetryDetermineEnabledState(portSharing_e portSharing)
115 bool enabled = portSharing == PORTSHARING_NOT_SHARED;
117 if (portSharing == PORTSHARING_SHARED) {
118 if (telemetryConfig()->telemetry_switch)
119 enabled = IS_RC_MODE_ACTIVE(BOXTELEMETRY);
120 else
121 enabled = ARMING_FLAG(ARMED);
124 return enabled;
127 bool telemetryCheckRxPortShared(const serialPortConfig_t *portConfig)
129 if (portConfig->functionMask & FUNCTION_RX_SERIAL && portConfig->functionMask & TELEMETRY_SHAREABLE_PORT_FUNCTIONS_MASK) {
130 return true;
132 #ifdef TELEMETRY_IBUS
133 if ( portConfig->functionMask & FUNCTION_TELEMETRY_IBUS
134 && portConfig->functionMask & FUNCTION_RX_SERIAL
135 && rxConfig()->serialrx_provider == SERIALRX_IBUS) {
136 // IBUS serial RX & telemetry
137 return true;
139 #endif
140 return false;
143 serialPort_t *telemetrySharedPort = NULL;
145 void telemetryCheckState(void)
147 #ifdef TELEMETRY_FRSKY
148 checkFrSkyTelemetryState();
149 #endif
150 #ifdef TELEMETRY_HOTT
151 checkHoTTTelemetryState();
152 #endif
153 #ifdef TELEMETRY_SMARTPORT
154 checkSmartPortTelemetryState();
155 #endif
156 #ifdef TELEMETRY_LTM
157 checkLtmTelemetryState();
158 #endif
159 #ifdef TELEMETRY_JETIEXBUS
160 checkJetiExBusTelemetryState();
161 #endif
162 #ifdef TELEMETRY_MAVLINK
163 checkMAVLinkTelemetryState();
164 #endif
165 #ifdef TELEMETRY_CRSF
166 checkCrsfTelemetryState();
167 #endif
168 #ifdef TELEMETRY_SRXL
169 checkSrxlTelemetryState();
170 #endif
171 #ifdef TELEMETRY_IBUS
172 checkIbusTelemetryState();
173 #endif
176 void telemetryProcess(uint32_t currentTime)
178 #ifdef TELEMETRY_FRSKY
179 handleFrSkyTelemetry();
180 #endif
181 #ifdef TELEMETRY_HOTT
182 handleHoTTTelemetry(currentTime);
183 #else
184 UNUSED(currentTime);
185 #endif
186 #ifdef TELEMETRY_SMARTPORT
187 handleSmartPortTelemetry();
188 #endif
189 #ifdef TELEMETRY_LTM
190 handleLtmTelemetry();
191 #endif
192 #ifdef TELEMETRY_JETIEXBUS
193 handleJetiExBusTelemetry();
194 #endif
195 #ifdef TELEMETRY_MAVLINK
196 handleMAVLinkTelemetry();
197 #endif
198 #ifdef TELEMETRY_CRSF
199 handleCrsfTelemetry(currentTime);
200 #endif
201 #ifdef TELEMETRY_SRXL
202 handleSrxlTelemetry(currentTime);
203 #endif
204 #ifdef TELEMETRY_IBUS
205 handleIbusTelemetry();
206 #endif
209 #define TELEMETRY_FUNCTION_MASK (FUNCTION_TELEMETRY_FRSKY | FUNCTION_TELEMETRY_HOTT | FUNCTION_TELEMETRY_LTM | FUNCTION_TELEMETRY_SMARTPORT)
211 void releaseSharedTelemetryPorts(void) {
212 serialPort_t *sharedPort = findSharedSerialPort(TELEMETRY_FUNCTION_MASK, FUNCTION_MSP);
213 while (sharedPort) {
214 mspSerialReleasePortIfAllocated(sharedPort);
215 sharedPort = findNextSharedSerialPort(TELEMETRY_FUNCTION_MASK, FUNCTION_MSP);
218 #endif