Merge pull request #10313 from P-I-Engineer/patch-1
[inav.git] / src / main / telemetry / hott.c
blob8e2e7d8c075ca32e46bfb8cb4b68333371fadcd1
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/>.
19 * telemetry_hott.c
21 * Authors:
22 * Konstantin Sharlaimov - HoTT code cleanup, proper state machine implementation, bi-directional serial port operation cleanup
23 * Dominic Clifton - Hydra - Software Serial, Electronics, Hardware Integration and debugging, HoTT Code cleanup and fixes, general telemetry improvements.
24 * Carsten Giesen - cGiesen - Baseflight port
25 * Oliver Bayer - oBayer - MultiWii-HoTT, HoTT reverse engineering
26 * Adam Majerczyk - HoTT-for-ardupilot from which some information and ideas are borrowed.
27 * Scavanger & Ziege-One: CMS Textmode addon
29 * https://github.com/obayer/MultiWii-HoTT
30 * https://github.com/oBayer/MultiHoTT-Module
31 * https://code.google.com/p/hott-for-ardupilot
33 * HoTT is implemented in Graupner equipment using a bi-directional protocol over a single wire.
35 * Generally the receiver sends a single request byte out using normal uart signals, then waits a short period for a
36 * multiple byte response and checksum byte before it sends out the next request byte.
37 * Each response byte must be send with a protocol specific delay between them.
39 * Serial ports use two wires but HoTT uses a single wire so some electronics are required so that
40 * the signals don't get mixed up. When cleanflight transmits it should not receive it's own transmission.
42 * Connect as follows:
43 * HoTT TX/RX -> Serial RX (connect directly)
44 * Serial TX -> 1N4148 Diode -(| )-> HoTT TX/RX (connect via diode)
46 * The diode should be arranged to allow the data signals to flow the right way
47 * -(| )- == Diode, | indicates cathode marker.
49 * As noticed by Skrebber the GR-12 (and probably GR-16/24, too) are based on a PIC 24FJ64GA-002, which has 5V tolerant digital pins.
51 * Note: The softserial ports are not listed as 5V tolerant in the STM32F103xx data sheet pinouts and pin description
52 * section. Verify if you require a 5v/3.3v level shifters. The softserial port should not be inverted.
54 * There is a technical discussion (in German) about HoTT here
55 * http://www.rc-network.de/forum/showthread.php/281496-Graupner-HoTT-Telemetrie-Sensoren-Eigenbau-DIY-Telemetrie-Protokoll-entschl%C3%BCsselt/page21
57 #include <stdbool.h>
58 #include <stdint.h>
59 #include <string.h>
61 #include "platform.h"
64 #if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_HOTT)
66 #include "build/build_config.h"
67 #include "build/debug.h"
69 #include "common/axis.h"
70 #include "common/time.h"
72 #include "drivers/serial.h"
73 #include "drivers/time.h"
75 #include "fc/runtime_config.h"
77 #include "flight/pid.h"
79 #include "io/gps.h"
80 #include "io/serial.h"
82 #include "navigation/navigation.h"
84 #include "sensors/battery.h"
85 #include "sensors/sensors.h"
87 #include "telemetry/hott.h"
88 #include "telemetry/telemetry.h"
90 #if defined (USE_HOTT_TEXTMODE) && defined (USE_CMS)
91 #include "scheduler/scheduler.h"
92 #include "io/displayport_hott.h"
94 #define HOTT_TEXTMODE_TASK_PERIOD 1000
95 #define HOTT_TEXTMODE_RX_SCHEDULE 5000
96 #define HOTT_TEXTMODE_TX_DELAY_US 1000
97 #endif
99 //#define HOTT_DEBUG
101 typedef enum {
102 HOTT_WAITING_FOR_REQUEST,
103 HOTT_RECEIVING_REQUEST,
104 HOTT_WAITING_FOR_TX_WINDOW,
105 HOTT_TRANSMITTING,
106 HOTT_ENDING_TRANSMISSION
107 } hottState_e;
109 #define HOTT_MESSAGE_PREPARATION_FREQUENCY_5_HZ ((1000 * 1000) / 5)
110 #define HOTT_RX_SCHEDULE 4000
111 #define HOTT_TX_SCHEDULE 5000
112 #define HOTT_TX_DELAY_US 2000
113 #define MILLISECONDS_IN_A_SECOND 1000
115 static uint32_t rxSchedule = HOTT_RX_SCHEDULE;
116 static uint32_t txDelayUs = HOTT_TX_DELAY_US;
118 static hottState_e hottState = HOTT_WAITING_FOR_REQUEST;
119 static timeUs_t hottStateChangeUs = 0;
121 static uint8_t *hottTxMsg = NULL;
122 static uint8_t hottTxMsgSize;
123 static uint8_t hottTxMsgCrc;
125 #define HOTT_BAUDRATE 19200
126 #define HOTT_INITIAL_PORT_MODE MODE_RXTX
128 static serialPort_t *hottPort = NULL;
129 static serialPortConfig_t *portConfig;
131 static bool hottTelemetryEnabled = false;
132 static portSharing_e hottPortSharing;
134 static HOTT_GPS_MSG_t hottGPSMessage;
135 static HOTT_EAM_MSG_t hottEAMMessage;
137 #if defined (USE_HOTT_TEXTMODE) && defined (USE_CMS)
138 static hottTextModeMsg_t hottTextModeMessage;
139 static bool textmodeIsAlive = false;
140 static int32_t telemetryTaskPeriod = 0;
142 static void initialiseTextmodeMessage(hottTextModeMsg_t *msg)
144 msg->start = HOTT_TEXTMODE_START;
145 msg->esc = HOTT_EAM_SENSOR_TEXT_ID;
146 msg->warning = 0;
147 msg->stop = HOTT_TEXTMODE_STOP;
149 #endif
151 static void hottSwitchState(hottState_e newState, timeUs_t currentTimeUs)
153 if (hottState != newState) {
154 hottState = newState;
155 hottStateChangeUs = currentTimeUs;
159 static void initialiseEAMMessage(HOTT_EAM_MSG_t *msg, size_t size)
161 memset(msg, 0, size);
162 msg->start_byte = 0x7C;
163 msg->eam_sensor_id = HOTT_TELEMETRY_EAM_SENSOR_ID;
164 msg->sensor_id = HOTT_EAM_SENSOR_TEXT_ID;
165 msg->stop_byte = 0x7D;
168 #ifdef USE_GPS
169 typedef enum {
170 GPS_FIX_CHAR_NONE = '-',
171 GPS_FIX_CHAR_2D = '2',
172 GPS_FIX_CHAR_3D = '3',
173 GPS_FIX_CHAR_DGPS = 'D',
174 } gpsFixChar_e;
176 static void initialiseGPSMessage(HOTT_GPS_MSG_t *msg, size_t size)
178 memset(msg, 0, size);
179 msg->start_byte = 0x7C;
180 msg->gps_sensor_id = HOTT_TELEMETRY_GPS_SENSOR_ID;
181 msg->sensor_id = HOTT_GPS_SENSOR_TEXT_ID;
182 msg->stop_byte = 0x7D;
184 #endif
186 static void initialiseMessages(void)
188 initialiseEAMMessage(&hottEAMMessage, sizeof(hottEAMMessage));
189 #ifdef USE_GPS
190 initialiseGPSMessage(&hottGPSMessage, sizeof(hottGPSMessage));
191 #endif
192 #if defined (USE_HOTT_TEXTMODE) && defined (USE_CMS)
193 initialiseTextmodeMessage(&hottTextModeMessage);
194 #endif
197 #ifdef USE_GPS
198 void addGPSCoordinates(HOTT_GPS_MSG_t *hottGPSMessage, int32_t latitude, int32_t longitude)
200 int16_t deg = latitude / GPS_DEGREES_DIVIDER;
201 int32_t sec = (latitude - (deg * GPS_DEGREES_DIVIDER)) * 6;
202 int8_t min = sec / 1000000L;
203 sec = (sec % 1000000L) / 100L;
204 uint16_t degMin = (deg * 100L) + min;
206 hottGPSMessage->pos_NS = (latitude < 0);
207 hottGPSMessage->pos_NS_dm_L = degMin;
208 hottGPSMessage->pos_NS_dm_H = degMin >> 8;
209 hottGPSMessage->pos_NS_sec_L = sec;
210 hottGPSMessage->pos_NS_sec_H = sec >> 8;
212 deg = longitude / GPS_DEGREES_DIVIDER;
213 sec = (longitude - (deg * GPS_DEGREES_DIVIDER)) * 6;
214 min = sec / 1000000L;
215 sec = (sec % 1000000L) / 100L;
216 degMin = (deg * 100L) + min;
218 hottGPSMessage->pos_EW = (longitude < 0);
219 hottGPSMessage->pos_EW_dm_L = degMin;
220 hottGPSMessage->pos_EW_dm_H = degMin >> 8;
221 hottGPSMessage->pos_EW_sec_L = sec;
222 hottGPSMessage->pos_EW_sec_H = sec >> 8;
225 void hottPrepareGPSResponse(HOTT_GPS_MSG_t *hottGPSMessage)
227 hottGPSMessage->gps_satelites = gpsSol.numSat;
229 // Report climb rate regardless of GPS fix
230 const int32_t climbrate = MAX(0, getEstimatedActualVelocity(Z) + 30000);
231 hottGPSMessage->climbrate_L = climbrate & 0xFF;
232 hottGPSMessage->climbrate_H = climbrate >> 8;
234 const int32_t climbrate3s = MAX(0, 3.0f * getEstimatedActualVelocity(Z) / 100 + 120);
235 hottGPSMessage->climbrate3s = climbrate3s & 0xFF;
237 #ifdef USE_GPS_FIX_ESTIMATION
238 if (!(STATE(GPS_FIX) || STATE(GPS_ESTIMATED_FIX)))
239 #else
240 if (!(STATE(GPS_FIX)))
241 #endif
243 hottGPSMessage->gps_fix_char = GPS_FIX_CHAR_NONE;
244 return;
247 if (gpsSol.fixType == GPS_FIX_3D) {
248 hottGPSMessage->gps_fix_char = GPS_FIX_CHAR_3D;
249 } else {
250 hottGPSMessage->gps_fix_char = GPS_FIX_CHAR_2D;
253 addGPSCoordinates(hottGPSMessage, gpsSol.llh.lat, gpsSol.llh.lon);
255 // GPS Speed is returned in cm/s (from io/gps.c) and must be sent in km/h (Hott requirement)
256 const uint16_t speed = (gpsSol.groundSpeed * 36) / 1000;
257 hottGPSMessage->gps_speed_L = speed & 0x00FF;
258 hottGPSMessage->gps_speed_H = speed >> 8;
260 hottGPSMessage->home_distance_L = GPS_distanceToHome & 0x00FF;
261 hottGPSMessage->home_distance_H = GPS_distanceToHome >> 8;
263 const uint16_t hottGpsAltitude = (gpsSol.llh.alt / 100) + HOTT_GPS_ALTITUDE_OFFSET; // meters
265 hottGPSMessage->altitude_L = hottGpsAltitude & 0x00FF;
266 hottGPSMessage->altitude_H = hottGpsAltitude >> 8;
268 hottGPSMessage->home_direction = GPS_directionToHome;
270 #endif
272 static inline void updateAlarmBatteryStatus(HOTT_EAM_MSG_t *hottEAMMessage)
274 static uint32_t lastHottAlarmSoundTime = 0;
276 if (((millis() - lastHottAlarmSoundTime) >= (telemetryConfig()->hottAlarmSoundInterval * MILLISECONDS_IN_A_SECOND))){
277 lastHottAlarmSoundTime = millis();
278 const batteryState_e batteryState = getBatteryState();
279 if (batteryState == BATTERY_WARNING || batteryState == BATTERY_CRITICAL){
280 hottEAMMessage->warning_beeps = 0x10;
281 hottEAMMessage->alarm_invers1 = HOTT_EAM_ALARM1_FLAG_BATTERY_1;
282 } else {
283 hottEAMMessage->warning_beeps = HOTT_EAM_ALARM1_FLAG_NONE;
284 hottEAMMessage->alarm_invers1 = HOTT_EAM_ALARM1_FLAG_NONE;
289 static inline void hottEAMUpdateBattery(HOTT_EAM_MSG_t *hottEAMMessage)
291 uint8_t vbat_dcv = getBatteryVoltage() / 10; // vbat resolution is 10mV convert to 100mv (deciVolt)
292 hottEAMMessage->main_voltage_L = vbat_dcv & 0xFF;
293 hottEAMMessage->main_voltage_H = vbat_dcv >> 8;
294 hottEAMMessage->batt1_voltage_L = vbat_dcv & 0xFF;
295 hottEAMMessage->batt1_voltage_H = vbat_dcv >> 8;
297 updateAlarmBatteryStatus(hottEAMMessage);
300 static inline void hottEAMUpdateCurrentMeter(HOTT_EAM_MSG_t *hottEAMMessage)
302 const int32_t amp = getAmperage() / 10;
303 hottEAMMessage->current_L = amp & 0xFF;
304 hottEAMMessage->current_H = amp >> 8;
307 static inline void hottEAMUpdateBatteryDrawnCapacity(HOTT_EAM_MSG_t *hottEAMMessage)
309 const int32_t mAh = getMAhDrawn() / 10;
310 hottEAMMessage->batt_cap_L = mAh & 0xFF;
311 hottEAMMessage->batt_cap_H = mAh >> 8;
314 static inline void hottEAMUpdateAltitudeAndClimbrate(HOTT_EAM_MSG_t *hottEAMMessage)
316 const int32_t alt = MAX(0, (int32_t)(getEstimatedActualPosition(Z) / 100.0f + HOTT_GPS_ALTITUDE_OFFSET)); // Value of 500 = 0m
317 hottEAMMessage->altitude_L = alt & 0xFF;
318 hottEAMMessage->altitude_H = alt >> 8;
320 const int32_t climbrate = MAX(0, (int32_t)(getEstimatedActualVelocity(Z) + 30000));
321 hottEAMMessage->climbrate_L = climbrate & 0xFF;
322 hottEAMMessage->climbrate_H = climbrate >> 8;
324 const int32_t climbrate3s = MAX(0, (int32_t)(3.0f * getEstimatedActualVelocity(Z) / 100 + 120));
325 hottEAMMessage->climbrate3s = climbrate3s & 0xFF;
328 void hottPrepareEAMResponse(HOTT_EAM_MSG_t *hottEAMMessage)
330 // Reset alarms
331 hottEAMMessage->warning_beeps = 0x0;
332 hottEAMMessage->alarm_invers1 = 0x0;
334 hottEAMUpdateBattery(hottEAMMessage);
335 hottEAMUpdateCurrentMeter(hottEAMMessage);
336 hottEAMUpdateBatteryDrawnCapacity(hottEAMMessage);
337 hottEAMUpdateAltitudeAndClimbrate(hottEAMMessage);
340 static void hottSerialWrite(uint8_t c)
342 static uint8_t serialWrites = 0;
343 serialWrites++;
344 serialWrite(hottPort, c);
347 void freeHoTTTelemetryPort(void)
349 closeSerialPort(hottPort);
350 hottPort = NULL;
351 hottTelemetryEnabled = false;
354 void initHoTTTelemetry(void)
356 portConfig = findSerialPortConfig(FUNCTION_TELEMETRY_HOTT);
357 hottPortSharing = determinePortSharing(portConfig, FUNCTION_TELEMETRY_HOTT);
359 if (!portConfig) {
360 return;
363 #if defined (USE_HOTT_TEXTMODE) && defined (USE_CMS)
364 hottDisplayportRegister();
365 #endif
367 initialiseMessages();
370 void configureHoTTTelemetryPort(void)
372 if (!portConfig) {
373 return;
376 portOptions_t portOptions = (telemetryConfig()->halfDuplex ? SERIAL_BIDIR : SERIAL_UNIDIR) | (SERIAL_NOT_INVERTED);
378 hottPort = openSerialPort(portConfig->identifier, FUNCTION_TELEMETRY_HOTT, NULL, NULL, HOTT_BAUDRATE, HOTT_INITIAL_PORT_MODE, portOptions);
380 if (!hottPort) {
381 return;
384 hottTelemetryEnabled = true;
387 static void hottQueueSendResponse(uint8_t *buffer, int length)
389 hottTxMsg = buffer;
390 hottTxMsgSize = length;
393 #if defined (USE_HOTT_TEXTMODE) && defined (USE_CMS)
394 static void hottTextmodeStart(void)
396 // Increase menu speed
397 cfTaskInfo_t taskInfo;
398 getTaskInfo(TASK_TELEMETRY, &taskInfo);
399 telemetryTaskPeriod = taskInfo.desiredPeriod;
400 rescheduleTask(TASK_TELEMETRY, TASK_PERIOD_HZ(HOTT_TEXTMODE_TASK_PERIOD));
402 rxSchedule = HOTT_TEXTMODE_RX_SCHEDULE;
403 txDelayUs = HOTT_TEXTMODE_TX_DELAY_US;
406 static void hottTextmodeStop(void)
408 // Set back to avoid slow down of the FC
409 if (telemetryTaskPeriod > 0) {
410 rescheduleTask(TASK_TELEMETRY, telemetryTaskPeriod);
411 telemetryTaskPeriod = 0;
414 rxSchedule = HOTT_RX_SCHEDULE;
415 txDelayUs = HOTT_TX_DELAY_US;
418 bool hottTextmodeIsAlive(void)
420 return textmodeIsAlive;
423 void hottTextmodeGrab(void)
425 hottTextModeMessage.esc = HOTT_EAM_SENSOR_TEXT_ID;
428 void hottTextmodeExit(void)
430 hottTextModeMessage.esc = HOTT_TEXTMODE_ESC;
433 void hottTextmodeWriteChar(uint8_t column, uint8_t row, char c)
435 if (column < HOTT_TEXTMODE_DISPLAY_COLUMNS && row < HOTT_TEXTMODE_DISPLAY_ROWS) {
436 if (hottTextModeMessage.txt[row][column] != c)
437 hottTextModeMessage.txt[row][column] = c;
441 static bool processHottTextModeRequest(const uint8_t cmd)
443 static bool setEscBack = false;
445 if (!textmodeIsAlive) {
446 hottTextmodeStart();
447 textmodeIsAlive = true;
450 if ((cmd & 0xF0) != HOTT_EAM_SENSOR_TEXT_ID) {
451 return false;
454 if (setEscBack) {
455 hottTextModeMessage.esc = HOTT_EAM_SENSOR_TEXT_ID;
456 setEscBack = false;
459 if (hottTextModeMessage.esc != HOTT_TEXTMODE_ESC) {
460 hottCmsOpen();
461 } else {
462 setEscBack = true;
465 hottSetCmsKey(cmd & 0x0f, hottTextModeMessage.esc == HOTT_TEXTMODE_ESC);
466 hottQueueSendResponse((uint8_t *)&hottTextModeMessage, sizeof(hottTextModeMessage));
468 return true;
470 #endif
472 static bool processBinaryModeRequest(uint8_t address)
474 #if defined (USE_HOTT_TEXTMODE) && defined (USE_CMS)
475 if (textmodeIsAlive) {
476 hottTextmodeStop();
477 textmodeIsAlive = false;
479 #endif
481 switch (address) {
482 #ifdef USE_GPS
483 case 0x8A:
484 if (sensors(SENSOR_GPS)
485 #ifdef USE_GPS_FIX_ESTIMATION
486 || STATE(GPS_ESTIMATED_FIX)
487 #endif
489 hottPrepareGPSResponse(&hottGPSMessage);
490 hottQueueSendResponse((uint8_t *)&hottGPSMessage, sizeof(hottGPSMessage));
491 return true;
493 break;
494 #endif
495 case 0x8E:
496 hottPrepareEAMResponse(&hottEAMMessage);
497 hottQueueSendResponse((uint8_t *)&hottEAMMessage, sizeof(hottEAMMessage));
498 return true;
501 return false;
504 static void flushHottRxBuffer(void)
506 while (serialRxBytesWaiting(hottPort) > 0) {
507 serialRead(hottPort);
511 static bool hottSendTelemetryDataByte(timeUs_t currentTimeUs)
513 static timeUs_t byteSentTimeUs = 0;
515 // Guard intra-byte interval
516 if (currentTimeUs - byteSentTimeUs < HOTT_TX_DELAY_US) {
517 return false;
520 if (hottTxMsgSize == 0) {
521 // Send CRC byte
522 hottSerialWrite(hottTxMsgCrc);
523 return true;
524 } else {
525 // Send data byte
526 hottTxMsgCrc += *hottTxMsg;
527 hottSerialWrite(*hottTxMsg);
528 hottTxMsg++;
529 hottTxMsgSize--;
530 return false;
534 void checkHoTTTelemetryState(void)
536 const bool newTelemetryEnabledValue = telemetryDetermineEnabledState(hottPortSharing);
538 if (newTelemetryEnabledValue == hottTelemetryEnabled) {
539 return;
542 if (newTelemetryEnabledValue) {
543 configureHoTTTelemetryPort();
544 } else {
545 freeHoTTTelemetryPort();
549 void handleHoTTTelemetry(timeUs_t currentTimeUs)
551 static uint8_t hottRequestBuffer[2];
552 static int hottRequestBufferPtr = 0;
554 if (!hottTelemetryEnabled) {
555 return;
558 bool reprocessState;
559 do {
560 reprocessState = false;
562 switch (hottState) {
563 case HOTT_WAITING_FOR_REQUEST:
564 if (serialRxBytesWaiting(hottPort)) {
565 hottRequestBufferPtr = 0;
566 hottSwitchState(HOTT_RECEIVING_REQUEST, currentTimeUs);
567 reprocessState = true;
569 break;
571 case HOTT_RECEIVING_REQUEST:
572 if ((currentTimeUs - hottStateChangeUs) >= rxSchedule) {
573 // Waiting for too long - resync
574 flushHottRxBuffer();
575 hottSwitchState(HOTT_WAITING_FOR_REQUEST, currentTimeUs);
577 else {
578 while (serialRxBytesWaiting(hottPort) && hottRequestBufferPtr < 2) {
579 hottRequestBuffer[hottRequestBufferPtr++] = serialRead(hottPort);
582 if (hottRequestBufferPtr >= 2) {
583 if ((hottRequestBuffer[0] == 0) || (hottRequestBuffer[0] == HOTT_BINARY_MODE_REQUEST_ID)) {
585 * FIXME the first byte of the HoTT request frame is ONLY either 0x80 (binary mode) or 0x7F (text mode).
586 * The binary mode is read as 0x00 (error reading the upper bit) while the text mode is correctly decoded.
587 * The (requestId == 0) test is a workaround for detecting the binary mode with no ambiguity as there is only
588 * one other valid value (0x7F) for text mode.
589 * The error reading for the upper bit should nevertheless be fixed
591 if (processBinaryModeRequest(hottRequestBuffer[1])) {
592 hottSwitchState(HOTT_WAITING_FOR_TX_WINDOW, currentTimeUs);
594 else {
595 hottSwitchState(HOTT_WAITING_FOR_REQUEST, currentTimeUs);
598 else if (hottRequestBuffer[0] == HOTT_TEXT_MODE_REQUEST_ID) {
599 #if defined (USE_HOTT_TEXTMODE) && defined (USE_CMS)
600 if (processHottTextModeRequest(hottRequestBuffer[1])) {
601 hottSwitchState(HOTT_WAITING_FOR_TX_WINDOW, currentTimeUs);
603 else {
604 hottSwitchState(HOTT_WAITING_FOR_REQUEST, currentTimeUs);
606 #else
607 hottSwitchState(HOTT_WAITING_FOR_REQUEST, currentTimeUs);
608 #endif
610 else {
611 // Received garbage - resync
612 flushHottRxBuffer();
613 hottSwitchState(HOTT_WAITING_FOR_REQUEST, currentTimeUs);
616 reprocessState = true;
619 break;
621 case HOTT_WAITING_FOR_TX_WINDOW:
622 if ((currentTimeUs - hottStateChangeUs) >= HOTT_TX_SCHEDULE) {
623 hottTxMsgCrc = 0;
624 hottSwitchState(HOTT_TRANSMITTING, currentTimeUs);
626 break;
628 case HOTT_TRANSMITTING:
629 if (hottSendTelemetryDataByte(currentTimeUs)) {
630 hottSwitchState(HOTT_ENDING_TRANSMISSION, currentTimeUs);
632 break;
634 case HOTT_ENDING_TRANSMISSION:
635 if ((currentTimeUs - hottStateChangeUs) >= txDelayUs) {
636 flushHottRxBuffer();
637 hottSwitchState(HOTT_WAITING_FOR_REQUEST, currentTimeUs);
638 reprocessState = true;
640 break;
642 } while (reprocessState);
645 #endif