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 "common/utils.h"
28 #include "config/parameter_group.h"
29 #include "config/parameter_group_ids.h"
31 #include "drivers/serial.h"
33 #include "fc/config.h"
34 #include "fc/rc_controls.h"
35 #include "fc/rc_modes.h"
36 #include "fc/runtime_config.h"
37 #include "fc/settings.h"
39 #include "io/serial.h"
43 #include "telemetry/telemetry.h"
44 #include "telemetry/hott.h"
45 #include "telemetry/smartport.h"
46 #include "telemetry/ltm.h"
47 #include "telemetry/mavlink.h"
48 #include "telemetry/jetiexbus.h"
49 #include "telemetry/ibus.h"
50 #include "telemetry/crsf.h"
51 #include "telemetry/srxl.h"
52 #include "telemetry/sim.h"
53 #include "telemetry/ghst.h"
56 PG_REGISTER_WITH_RESET_TEMPLATE(telemetryConfig_t
, telemetryConfig
, PG_TELEMETRY_CONFIG
, 6);
58 PG_RESET_TEMPLATE(telemetryConfig_t
, telemetryConfig
,
59 .telemetry_switch
= SETTING_TELEMETRY_SWITCH_DEFAULT
,
60 .telemetry_inverted
= SETTING_TELEMETRY_INVERTED_DEFAULT
,
61 .frsky_pitch_roll
= SETTING_FRSKY_PITCH_ROLL_DEFAULT
,
62 .report_cell_voltage
= SETTING_REPORT_CELL_VOLTAGE_DEFAULT
,
63 .hottAlarmSoundInterval
= SETTING_HOTT_ALARM_SOUND_INTERVAL_DEFAULT
,
64 .halfDuplex
= SETTING_TELEMETRY_HALFDUPLEX_DEFAULT
,
65 #if !defined(SETTING_SMARTPORT_FUEL_UNIT_DEFAULT) // SITL
66 .smartportFuelUnit
= 1,
68 .smartportFuelUnit
= SETTING_SMARTPORT_FUEL_UNIT_DEFAULT
,
70 .ibusTelemetryType
= SETTING_IBUS_TELEMETRY_TYPE_DEFAULT
,
71 .ltmUpdateRate
= SETTING_LTM_UPDATE_RATE_DEFAULT
,
73 #ifdef USE_TELEMETRY_SIM
74 .simTransmitInterval
= SETTING_SIM_TRANSMIT_INTERVAL_DEFAULT
,
75 .simTransmitFlags
= SETTING_SIM_TRANSMIT_FLAGS_DEFAULT
,
76 .simLowAltitude
= SETTING_SIM_LOW_ALTITUDE_DEFAULT
,
77 .simPin
= SETTING_SIM_PIN_DEFAULT
,
78 .simGroundStationNumber
= SETTING_SIM_GROUND_STATION_NUMBER_DEFAULT
,
80 .accEventThresholdHigh
= SETTING_ACC_EVENT_THRESHOLD_HIGH_DEFAULT
,
81 .accEventThresholdLow
= SETTING_ACC_EVENT_THRESHOLD_LOW_DEFAULT
,
82 .accEventThresholdNegX
= SETTING_ACC_EVENT_THRESHOLD_NEG_X_DEFAULT
,
86 .extended_status_rate
= SETTING_MAVLINK_EXT_STATUS_RATE_DEFAULT
,
87 .rc_channels_rate
= SETTING_MAVLINK_RC_CHAN_RATE_DEFAULT
,
88 .position_rate
= SETTING_MAVLINK_POS_RATE_DEFAULT
,
89 .extra1_rate
= SETTING_MAVLINK_EXTRA1_RATE_DEFAULT
,
90 .extra2_rate
= SETTING_MAVLINK_EXTRA2_RATE_DEFAULT
,
91 .extra3_rate
= SETTING_MAVLINK_EXTRA3_RATE_DEFAULT
,
92 .version
= SETTING_MAVLINK_VERSION_DEFAULT
96 void telemetryInit(void)
99 #if defined(USE_TELEMETRY_HOTT)
103 #if defined(USE_TELEMETRY_SMARTPORT)
104 initSmartPortTelemetry();
107 #if defined(USE_TELEMETRY_LTM)
111 #if defined(USE_TELEMETRY_MAVLINK)
112 initMAVLinkTelemetry();
115 #if defined(USE_TELEMETRY_JETIEXBUS)
116 initJetiExBusTelemetry();
119 #if defined(USE_TELEMETRY_IBUS)
123 #if defined(USE_TELEMETRY_SIM)
127 #if defined(USE_SERIALRX_CRSF) && defined(USE_TELEMETRY_CRSF)
131 #ifdef USE_TELEMETRY_SRXL
135 #ifdef USE_TELEMETRY_GHST
139 telemetryCheckState();
142 bool telemetryDetermineEnabledState(portSharing_e portSharing
)
144 bool enabled
= portSharing
== PORTSHARING_NOT_SHARED
;
146 if (portSharing
== PORTSHARING_SHARED
) {
147 if (telemetryConfig()->telemetry_switch
)
148 enabled
= IS_RC_MODE_ACTIVE(BOXTELEMETRY
);
150 enabled
= ARMING_FLAG(ARMED
);
156 bool telemetryCheckRxPortShared(const serialPortConfig_t
*portConfig
)
158 return portConfig
->functionMask
& FUNCTION_RX_SERIAL
&& portConfig
->functionMask
& TELEMETRY_SHAREABLE_PORT_FUNCTIONS_MASK
;
161 serialPort_t
*telemetrySharedPort
= NULL
;
163 void telemetryCheckState(void)
166 #if defined(USE_TELEMETRY_HOTT)
167 checkHoTTTelemetryState();
170 #if defined(USE_TELEMETRY_SMARTPORT)
171 checkSmartPortTelemetryState();
174 #if defined(USE_TELEMETRY_LTM)
175 checkLtmTelemetryState();
178 #if defined(USE_TELEMETRY_MAVLINK)
179 checkMAVLinkTelemetryState();
182 #if defined(USE_TELEMETRY_JETIEXBUS)
183 checkJetiExBusTelemetryState();
186 #if defined(USE_TELEMETRY_IBUS)
187 checkIbusTelemetryState();
190 #if defined(USE_TELEMETRY_SIM)
191 checkSimTelemetryState();
194 #if defined(USE_SERIALRX_CRSF) && defined(USE_TELEMETRY_CRSF)
195 checkCrsfTelemetryState();
198 #ifdef USE_TELEMETRY_SRXL
199 checkSrxlTelemetryState();
201 #ifdef USE_TELEMETRY_GHST
202 checkGhstTelemetryState();
206 void telemetryProcess(timeUs_t currentTimeUs
)
208 UNUSED(currentTimeUs
); // since not used by all the telemetry protocols
210 #if defined(USE_TELEMETRY_HOTT)
211 handleHoTTTelemetry(currentTimeUs
);
214 #if defined(USE_TELEMETRY_SMARTPORT)
215 handleSmartPortTelemetry();
218 #if defined(USE_TELEMETRY_LTM)
219 handleLtmTelemetry();
222 #if defined(USE_TELEMETRY_MAVLINK)
223 handleMAVLinkTelemetry(currentTimeUs
);
226 #if defined(USE_TELEMETRY_JETIEXBUS)
227 handleJetiExBusTelemetry();
230 #if defined(USE_SERIALRX_IBUS) && defined(USE_TELEMETRY_IBUS)
231 handleIbusTelemetry();
234 #if defined(USE_TELEMETRY_SIM)
235 handleSimTelemetry();
238 #if defined(USE_SERIALRX_CRSF) && defined(USE_TELEMETRY_CRSF)
239 handleCrsfTelemetry(currentTimeUs
);
242 #ifdef USE_TELEMETRY_SRXL
243 handleSrxlTelemetry(currentTimeUs
);
245 #ifdef USE_TELEMETRY_GHST
246 handleGhstTelemetry(currentTimeUs
);