5 * th9x - http://code.google.com/p/th9x
6 * er9x - http://code.google.com/p/er9x
7 * gruvin9x - http://code.google.com/p/gruvin9x
9 * License GPLv2: http://www.gnu.org/licenses/gpl-2.0.html
11 * This program is free software; you can redistribute it and/or modify
12 * it under the terms of the GNU General Public License version 2 as
13 * published by the Free Software Foundation.
15 * This program is distributed in the hope that it will be useful,
16 * but WITHOUT ANY WARRANTY; without even the implied warranty of
17 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
18 * GNU General Public License for more details.
24 uint8_t telemetryStreaming
= 0;
25 uint8_t telemetryRxBuffer
[TELEMETRY_RX_PACKET_SIZE
]; // Receive buffer. 9 bytes (full packet), worst case 18 bytes with byte-stuffing (+1)
26 uint8_t telemetryRxBufferCount
= 0;
28 uint8_t telemetryState
= TELEMETRY_INIT
;
30 TelemetryData telemetryData
;
32 uint8_t telemetryProtocol
= 255;
34 #if defined(PCBSKY9X) && defined(REVX)
35 uint8_t serialInversion
= 0;
38 void processTelemetryData(uint8_t data
)
40 #if defined(CROSSFIRE)
41 if (telemetryProtocol
== PROTOCOL_TELEMETRY_CROSSFIRE
) {
42 processCrossfireTelemetryData(data
);
47 #if defined(MULTIMODULE)
48 if (telemetryProtocol
== PROTOCOL_TELEMETRY_SPEKTRUM
) {
49 processSpektrumTelemetryData(EXTERNAL_MODULE
, data
, telemetryRxBuffer
, telemetryRxBufferCount
);
52 if (telemetryProtocol
== PROTOCOL_TELEMETRY_FLYSKY_IBUS
) {
53 processFlySkyTelemetryData(data
, telemetryRxBuffer
, telemetryRxBufferCount
);
56 if (telemetryProtocol
== PROTOCOL_TELEMETRY_MULTIMODULE
) {
57 processMultiTelemetryData(data
, EXTERNAL_MODULE
);
62 processFrskyTelemetryData(data
);
65 inline bool isBadAntennaDetected()
67 if (!isRasValueValid())
70 if (telemetryData
.swrInternal
.isFresh() && telemetryData
.swrInternal
.value() > FRSKY_BAD_ANTENNA_THRESHOLD
)
73 if (telemetryData
.swrExternal
.isFresh() && telemetryData
.swrExternal
.value() > FRSKY_BAD_ANTENNA_THRESHOLD
)
79 void telemetryWakeup()
81 uint8_t requiredTelemetryProtocol
= modelTelemetryProtocol();
85 uint8_t requiredSerialInversion
= g_model
.moduleData
[EXTERNAL_MODULE
].invertedSerial
;
86 if (telemetryProtocol
!= requiredTelemetryProtocol
|| serialInversion
!= requiredSerialInversion
) {
87 serialInversion
= requiredSerialInversion
;
88 telemetryInit(requiredTelemetryProtocol
);
91 if (telemetryProtocol
!= requiredTelemetryProtocol
) {
92 telemetryInit(requiredTelemetryProtocol
);
96 #if defined(INTERNAL_MODULE_PXX2) || defined(EXTMODULE_USART)
97 uint8_t frame
[PXX2_FRAME_MAXLENGTH
];
99 #if defined(INTERNAL_MODULE_PXX2)
100 while (intmoduleFifo
.getFrame(frame
)) {
101 processPXX2Frame(INTERNAL_MODULE
, frame
);
105 #if defined(EXTMODULE_USART)
106 while (extmoduleFifo
.getFrame(frame
)) {
107 processPXX2Frame(EXTERNAL_MODULE
, frame
);
112 #if defined(INTERNAL_MODULE_MULTI)
113 if (intmoduleFifo
.pop(data
)) {
114 LOG_TELEMETRY_WRITE_START();
116 processMultiTelemetryData(data
, INTERNAL_MODULE
);
117 LOG_TELEMETRY_WRITE_BYTE(data
);
118 } while (intmoduleFifo
.pop(data
));
123 if (telemetryGetByte(&data
)) {
124 LOG_TELEMETRY_WRITE_START();
126 processTelemetryData(data
);
127 LOG_TELEMETRY_WRITE_BYTE(data
);
128 } while (telemetryGetByte(&data
));
130 #elif defined(PCBSKY9X)
131 if (telemetryProtocol
== PROTOCOL_TELEMETRY_FRSKY_D_SECONDARY
) {
132 while (telemetrySecondPortReceive(data
)) {
133 processTelemetryData(data
);
137 // Receive serial data here
138 rxPdcUsart(processTelemetryData
);
142 for (int i
=0; i
<MAX_TELEMETRY_SENSORS
; i
++) {
143 const TelemetrySensor
& sensor
= g_model
.telemetrySensors
[i
];
144 if (sensor
.type
== TELEM_TYPE_CALCULATED
) {
145 telemetryItems
[i
].eval(sensor
);
150 if (TELEMETRY_STREAMING() && !IS_FAI_ENABLED()) {
155 static tmr10ms_t alarmsCheckTime
= 0;
156 #define SCHEDULE_NEXT_ALARMS_CHECK(seconds) alarmsCheckTime = get_tmr10ms() + (100*(seconds))
157 if (int32_t(get_tmr10ms() - alarmsCheckTime
) > 0) {
159 SCHEDULE_NEXT_ALARMS_CHECK(1/*second*/);
161 bool sensorLost
= false;
162 for (int i
=0; i
<MAX_TELEMETRY_SENSORS
; i
++) {
163 if (isTelemetryFieldAvailable(i
)) {
164 TelemetryItem
& item
= telemetryItems
[i
];
165 if (item
.timeout
== 0) {
166 TelemetrySensor
* sensor
= & g_model
.telemetrySensors
[i
];
167 if (sensor
->unit
!= UNIT_DATETIME
) {
175 if (sensorLost
&& TELEMETRY_STREAMING() && !g_model
.rssiAlarms
.disabled
) {
176 audioEvent(AU_SENSOR_LOST
);
179 #if defined(PCBTARANIS) || defined(PCBHORUS)
180 if (isBadAntennaDetected()) {
182 POPUP_WARNING(STR_WARNING
);
183 const char * w
= STR_ANTENNAPROBLEM
;
184 SET_WARNING_INFO(w
, strlen(w
), 0);
185 SCHEDULE_NEXT_ALARMS_CHECK(10/*seconds*/);
189 if (!g_model
.rssiAlarms
.disabled
) {
190 if (TELEMETRY_STREAMING()) {
191 if (TELEMETRY_RSSI() < g_model
.rssiAlarms
.getCriticalRssi() ) {
193 SCHEDULE_NEXT_ALARMS_CHECK(10/*seconds*/);
195 else if (TELEMETRY_RSSI() < g_model
.rssiAlarms
.getWarningRssi() ) {
197 SCHEDULE_NEXT_ALARMS_CHECK(10/*seconds*/);
201 if (TELEMETRY_STREAMING()) {
202 if (telemetryState
== TELEMETRY_KO
) {
203 AUDIO_TELEMETRY_BACK();
205 telemetryState
= TELEMETRY_OK
;
207 else if (telemetryState
== TELEMETRY_OK
) {
208 telemetryState
= TELEMETRY_KO
;
209 if (!isModuleInBeepMode()) {
210 AUDIO_TELEMETRY_LOST();
217 void telemetryInterrupt10ms()
219 if (telemetryStreaming
> 0) {
220 bool tick160ms
= (telemetryStreaming
& 0x0F) == 0;
221 for (int i
=0; i
<MAX_TELEMETRY_SENSORS
; i
++) {
222 const TelemetrySensor
& sensor
= g_model
.telemetrySensors
[i
];
223 if (sensor
.type
== TELEM_TYPE_CALCULATED
) {
224 telemetryItems
[i
].per10ms(sensor
);
226 if (tick160ms
&& telemetryItems
[i
].timeout
> 0) {
227 telemetryItems
[i
].timeout
--;
230 telemetryStreaming
--;
234 telemetryData
.rssi
.reset();
236 for (auto & telemetryItem
: telemetryItems
) {
237 if (telemetryItem
.isAvailable()) {
238 telemetryItem
.setOld();
244 void telemetryReset()
246 telemetryData
.clear();
248 for (auto & telemetryItem
: telemetryItems
) {
249 telemetryItem
.clear();
252 telemetryStreaming
= 0; // reset counter only if valid telemetry packets are being detected
254 telemetryState
= TELEMETRY_INIT
;
257 // we don't reset the telemetry here as we would also reset the consumption after model load
258 void telemetryInit(uint8_t protocol
)
260 telemetryProtocol
= protocol
;
262 if (protocol
== PROTOCOL_TELEMETRY_FRSKY_D
) {
263 telemetryPortInit(FRSKY_D_BAUDRATE
, TELEMETRY_SERIAL_DEFAULT
);
266 #if defined(MULTIMODULE)
267 else if (protocol
== PROTOCOL_TELEMETRY_MULTIMODULE
|| protocol
== PROTOCOL_TELEMETRY_FLYSKY_IBUS
) {
268 // The DIY Multi module always speaks 100000 baud regardless of the telemetry protocol in use
269 telemetryPortInit(MULTIMODULE_BAUDRATE
, TELEMETRY_SERIAL_8E2
);
271 outputTelemetryBuffer
.reset();
274 else if (protocol
== PROTOCOL_TELEMETRY_SPEKTRUM
) {
275 // Spektrum's own small race RX (SPM4648) uses 125000 8N1, use the same since there is no real standard
276 telemetryPortInit(125000, TELEMETRY_SERIAL_DEFAULT
);
280 #if defined(CROSSFIRE)
281 else if (protocol
== PROTOCOL_TELEMETRY_CROSSFIRE
) {
282 telemetryPortInit(CROSSFIRE_BAUDRATE
, TELEMETRY_SERIAL_DEFAULT
);
284 outputTelemetryBuffer
.reset();
286 telemetryPortSetDirectionOutput();
290 #if defined(AUX_SERIAL) || defined(PCBSKY9X)
291 else if (protocol
== PROTOCOL_TELEMETRY_FRSKY_D_SECONDARY
) {
292 telemetryPortInit(0, TELEMETRY_SERIAL_DEFAULT
);
293 auxSerialTelemetryInit(PROTOCOL_TELEMETRY_FRSKY_D_SECONDARY
);
298 telemetryPortInit(FRSKY_SPORT_BAUDRATE
, TELEMETRY_SERIAL_WITHOUT_DMA
);
300 outputTelemetryBuffer
.reset();
304 #if defined(REVX) && !defined(SIMU)
305 if (serialInversion
) {
315 #if defined(LOG_TELEMETRY) && !defined(SIMU)
316 extern FIL g_telemetryFile
;
317 void logTelemetryWriteStart()
319 static tmr10ms_t lastTime
= 0;
320 tmr10ms_t newTime
= get_tmr10ms();
321 if (lastTime
!= newTime
) {
324 f_printf(&g_telemetryFile
, "\r\n%4d-%02d-%02d,%02d:%02d:%02d.%02d0:", utm
.tm_year
+TM_YEAR_BASE
, utm
.tm_mon
+1, utm
.tm_mday
, utm
.tm_hour
, utm
.tm_min
, utm
.tm_sec
, g_ms100
);
329 void logTelemetryWriteByte(uint8_t data
)
331 f_printf(&g_telemetryFile
, " %02X", data
);
335 OutputTelemetryBuffer outputTelemetryBuffer __DMA
;
338 Fifo
<uint8_t, LUA_TELEMETRY_INPUT_FIFO_SIZE
> * luaInputTelemetryFifo
= NULL
;