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/>.
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"
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
, 6);
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,
71 .smartportFuelUnit
= SETTING_SMARTPORT_FUEL_UNIT_DEFAULT
,
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
,
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
99 void telemetryInit(void)
102 #if defined(USE_TELEMETRY_HOTT)
106 #if defined(USE_TELEMETRY_SMARTPORT)
107 initSmartPortTelemetry();
110 #if defined(USE_TELEMETRY_LTM)
114 #if defined(USE_TELEMETRY_MAVLINK)
115 initMAVLinkTelemetry();
118 #if defined(USE_TELEMETRY_JETIEXBUS)
119 initJetiExBusTelemetry();
122 #if defined(USE_TELEMETRY_IBUS)
126 #if defined(USE_TELEMETRY_SIM)
130 #if defined(USE_SERIALRX_CRSF) && defined(USE_TELEMETRY_CRSF)
134 #ifdef USE_TELEMETRY_SRXL
138 #ifdef USE_TELEMETRY_GHST
142 telemetryCheckState();
145 bool telemetryDetermineEnabledState(portSharing_e portSharing
)
147 bool enabled
= portSharing
== PORTSHARING_NOT_SHARED
;
149 if (portSharing
== PORTSHARING_SHARED
) {
150 if (telemetryConfig()->telemetry_switch
)
151 enabled
= IS_RC_MODE_ACTIVE(BOXTELEMETRY
);
153 enabled
= ARMING_FLAG(ARMED
);
159 bool telemetryCheckRxPortShared(const serialPortConfig_t
*portConfig
)
161 return portConfig
->functionMask
& FUNCTION_RX_SERIAL
&& portConfig
->functionMask
& TELEMETRY_SHAREABLE_PORT_FUNCTIONS_MASK
;
164 serialPort_t
*telemetrySharedPort
= NULL
;
166 void telemetryCheckState(void)
169 #if defined(USE_TELEMETRY_HOTT)
170 checkHoTTTelemetryState();
173 #if defined(USE_TELEMETRY_SMARTPORT)
174 checkSmartPortTelemetryState();
177 #if defined(USE_TELEMETRY_LTM)
178 checkLtmTelemetryState();
181 #if defined(USE_TELEMETRY_MAVLINK)
182 checkMAVLinkTelemetryState();
185 #if defined(USE_TELEMETRY_JETIEXBUS)
186 checkJetiExBusTelemetryState();
189 #if defined(USE_TELEMETRY_IBUS)
190 checkIbusTelemetryState();
193 #if defined(USE_TELEMETRY_SIM)
194 checkSimTelemetryState();
197 #if defined(USE_SERIALRX_CRSF) && defined(USE_TELEMETRY_CRSF)
198 checkCrsfTelemetryState();
201 #ifdef USE_TELEMETRY_SRXL
202 checkSrxlTelemetryState();
204 #ifdef USE_TELEMETRY_GHST
205 checkGhstTelemetryState();
209 void telemetryProcess(timeUs_t currentTimeUs
)
211 UNUSED(currentTimeUs
); // since not used by all the telemetry protocols
213 #if defined(USE_TELEMETRY_HOTT)
214 handleHoTTTelemetry(currentTimeUs
);
217 #if defined(USE_TELEMETRY_SMARTPORT)
218 handleSmartPortTelemetry();
221 #if defined(USE_TELEMETRY_LTM)
222 handleLtmTelemetry();
225 #if defined(USE_TELEMETRY_MAVLINK)
226 handleMAVLinkTelemetry(currentTimeUs
);
229 #if defined(USE_TELEMETRY_JETIEXBUS)
230 handleJetiExBusTelemetry();
233 #if defined(USE_SERIALRX_IBUS) && defined(USE_TELEMETRY_IBUS)
234 handleIbusTelemetry();
237 #if defined(USE_TELEMETRY_SIM)
238 handleSimTelemetry();
241 #if defined(USE_SERIALRX_CRSF) && defined(USE_TELEMETRY_CRSF)
242 handleCrsfTelemetry(currentTimeUs
);
245 #ifdef USE_TELEMETRY_SRXL
246 handleSrxlTelemetry(currentTimeUs
);
248 #ifdef USE_TELEMETRY_GHST
249 handleGhstTelemetry(currentTimeUs
);
252 #ifdef USE_TELEMETRY_SBUS2
253 handleSbus2Telemetry(currentTimeUs
);