Merge remote-tracking branch 'origin/master' into mmosca-mavlinkrc
[inav.git] / src / main / telemetry / telemetry.c
blobf07d15e86468d7c58da71d9223a5df9577f8bc25
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 <stdbool.h>
19 #include <stdint.h>
20 #include <stdlib.h>
22 #include "platform.h"
24 #ifdef USE_TELEMETRY
26 #include "build/debug.h"
28 #include "common/utils.h"
30 #include "config/parameter_group.h"
31 #include "config/parameter_group_ids.h"
33 #include "drivers/serial.h"
35 #include "fc/config.h"
36 #include "fc/rc_controls.h"
37 #include "fc/rc_modes.h"
38 #include "fc/runtime_config.h"
39 #include "fc/settings.h"
41 #include "io/serial.h"
43 #include "rx/rx.h"
45 #include "telemetry/telemetry.h"
46 #include "telemetry/hott.h"
47 #include "telemetry/smartport.h"
48 #include "telemetry/ltm.h"
49 #include "telemetry/mavlink.h"
50 #include "telemetry/jetiexbus.h"
51 #include "telemetry/ibus.h"
52 #include "telemetry/crsf.h"
53 #include "telemetry/srxl.h"
54 #include "telemetry/sbus2.h"
55 #include "telemetry/sim.h"
56 #include "telemetry/ghst.h"
59 PG_REGISTER_WITH_RESET_TEMPLATE(telemetryConfig_t, telemetryConfig, PG_TELEMETRY_CONFIG, 8);
61 PG_RESET_TEMPLATE(telemetryConfig_t, telemetryConfig,
62 .telemetry_switch = SETTING_TELEMETRY_SWITCH_DEFAULT,
63 .telemetry_inverted = SETTING_TELEMETRY_INVERTED_DEFAULT,
64 .frsky_pitch_roll = SETTING_FRSKY_PITCH_ROLL_DEFAULT,
65 .report_cell_voltage = SETTING_REPORT_CELL_VOLTAGE_DEFAULT,
66 .hottAlarmSoundInterval = SETTING_HOTT_ALARM_SOUND_INTERVAL_DEFAULT,
67 .halfDuplex = SETTING_TELEMETRY_HALFDUPLEX_DEFAULT,
68 #if !defined(SETTING_SMARTPORT_FUEL_UNIT_DEFAULT) // SITL
69 .smartportFuelUnit = 1,
70 #else
71 .smartportFuelUnit = SETTING_SMARTPORT_FUEL_UNIT_DEFAULT,
72 #endif
73 .ibusTelemetryType = SETTING_IBUS_TELEMETRY_TYPE_DEFAULT,
74 .ltmUpdateRate = SETTING_LTM_UPDATE_RATE_DEFAULT,
76 #ifdef USE_TELEMETRY_SIM
77 .simTransmitInterval = SETTING_SIM_TRANSMIT_INTERVAL_DEFAULT,
78 .simTransmitFlags = SETTING_SIM_TRANSMIT_FLAGS_DEFAULT,
79 .simLowAltitude = SETTING_SIM_LOW_ALTITUDE_DEFAULT,
80 .simPin = SETTING_SIM_PIN_DEFAULT,
81 .simGroundStationNumber = SETTING_SIM_GROUND_STATION_NUMBER_DEFAULT,
83 .accEventThresholdHigh = SETTING_ACC_EVENT_THRESHOLD_HIGH_DEFAULT,
84 .accEventThresholdLow = SETTING_ACC_EVENT_THRESHOLD_LOW_DEFAULT,
85 .accEventThresholdNegX = SETTING_ACC_EVENT_THRESHOLD_NEG_X_DEFAULT,
86 #endif
88 .mavlink = {
89 .extended_status_rate = SETTING_MAVLINK_EXT_STATUS_RATE_DEFAULT,
90 .rc_channels_rate = SETTING_MAVLINK_RC_CHAN_RATE_DEFAULT,
91 .position_rate = SETTING_MAVLINK_POS_RATE_DEFAULT,
92 .extra1_rate = SETTING_MAVLINK_EXTRA1_RATE_DEFAULT,
93 .extra2_rate = SETTING_MAVLINK_EXTRA2_RATE_DEFAULT,
94 .extra3_rate = SETTING_MAVLINK_EXTRA3_RATE_DEFAULT,
95 .version = SETTING_MAVLINK_VERSION_DEFAULT,
96 .min_txbuff = SETTING_MAVLINK_MIN_TXBUFFER_DEFAULT,
97 .radio_type = SETTING_MAVLINK_RADIO_TYPE_DEFAULT
101 void telemetryInit(void)
104 #if defined(USE_TELEMETRY_HOTT)
105 initHoTTTelemetry();
106 #endif
108 #if defined(USE_TELEMETRY_SMARTPORT)
109 initSmartPortTelemetry();
110 #endif
112 #if defined(USE_TELEMETRY_LTM)
113 initLtmTelemetry();
114 #endif
116 #if defined(USE_TELEMETRY_MAVLINK)
117 initMAVLinkTelemetry();
118 #endif
120 #if defined(USE_TELEMETRY_JETIEXBUS)
121 initJetiExBusTelemetry();
122 #endif
124 #if defined(USE_TELEMETRY_IBUS)
125 initIbusTelemetry();
126 #endif
128 #if defined(USE_TELEMETRY_SIM)
129 initSimTelemetry();
130 #endif
132 #if defined(USE_SERIALRX_CRSF) && defined(USE_TELEMETRY_CRSF)
133 initCrsfTelemetry();
134 #endif
136 #ifdef USE_TELEMETRY_SRXL
137 initSrxlTelemetry();
138 #endif
140 #ifdef USE_TELEMETRY_GHST
141 initGhstTelemetry();
142 #endif
144 telemetryCheckState();
147 bool telemetryDetermineEnabledState(portSharing_e portSharing)
149 bool enabled = portSharing == PORTSHARING_NOT_SHARED;
151 if (portSharing == PORTSHARING_SHARED) {
152 if (telemetryConfig()->telemetry_switch)
153 enabled = IS_RC_MODE_ACTIVE(BOXTELEMETRY);
154 else
155 enabled = ARMING_FLAG(ARMED);
158 return enabled;
161 bool telemetryCheckRxPortShared(const serialPortConfig_t *portConfig)
163 return portConfig->functionMask & FUNCTION_RX_SERIAL && portConfig->functionMask & TELEMETRY_SHAREABLE_PORT_FUNCTIONS_MASK;
166 serialPort_t *telemetrySharedPort = NULL;
168 void telemetryCheckState(void)
171 #if defined(USE_TELEMETRY_HOTT)
172 checkHoTTTelemetryState();
173 #endif
175 #if defined(USE_TELEMETRY_SMARTPORT)
176 checkSmartPortTelemetryState();
177 #endif
179 #if defined(USE_TELEMETRY_LTM)
180 checkLtmTelemetryState();
181 #endif
183 #if defined(USE_TELEMETRY_MAVLINK)
184 checkMAVLinkTelemetryState();
185 #endif
187 #if defined(USE_TELEMETRY_JETIEXBUS)
188 checkJetiExBusTelemetryState();
189 #endif
191 #if defined(USE_TELEMETRY_IBUS)
192 checkIbusTelemetryState();
193 #endif
195 #if defined(USE_TELEMETRY_SIM)
196 checkSimTelemetryState();
197 #endif
199 #if defined(USE_SERIALRX_CRSF) && defined(USE_TELEMETRY_CRSF)
200 checkCrsfTelemetryState();
201 #endif
203 #ifdef USE_TELEMETRY_SRXL
204 checkSrxlTelemetryState();
205 #endif
206 #ifdef USE_TELEMETRY_GHST
207 checkGhstTelemetryState();
208 #endif
211 void telemetryProcess(timeUs_t currentTimeUs)
213 UNUSED(currentTimeUs); // since not used by all the telemetry protocols
215 #if defined(USE_TELEMETRY_HOTT)
216 handleHoTTTelemetry(currentTimeUs);
217 #endif
219 #if defined(USE_TELEMETRY_SMARTPORT)
220 handleSmartPortTelemetry();
221 #endif
223 #if defined(USE_TELEMETRY_LTM)
224 handleLtmTelemetry();
225 #endif
227 #if defined(USE_TELEMETRY_MAVLINK)
228 handleMAVLinkTelemetry(currentTimeUs);
229 #endif
231 #if defined(USE_TELEMETRY_JETIEXBUS)
232 handleJetiExBusTelemetry();
233 #endif
235 #if defined(USE_SERIALRX_IBUS) && defined(USE_TELEMETRY_IBUS)
236 handleIbusTelemetry();
237 #endif
239 #if defined(USE_TELEMETRY_SIM)
240 handleSimTelemetry();
241 #endif
243 #if defined(USE_SERIALRX_CRSF) && defined(USE_TELEMETRY_CRSF)
244 handleCrsfTelemetry(currentTimeUs);
245 #endif
247 #ifdef USE_TELEMETRY_SRXL
248 handleSrxlTelemetry(currentTimeUs);
249 #endif
250 #ifdef USE_TELEMETRY_GHST
251 handleGhstTelemetry(currentTimeUs);
252 #endif
254 #ifdef USE_TELEMETRY_SBUS2
255 handleSbus2Telemetry(currentTimeUs);
256 #endif
259 #endif