Merge pull request #11500 from klutvott123/crsf-baud-negotiation-improvements-2
[betaflight.git] / src / main / telemetry / hott.h
blobe3be8aa7c2cd5d1010e145df66a0384b6327bed7
1 /*
2 * This file is part of Cleanflight and Betaflight.
4 * Cleanflight and Betaflight are free software. You can redistribute
5 * this software and/or modify this software under the terms of the
6 * GNU General Public License as published by the Free Software
7 * Foundation, either version 3 of the License, or (at your option)
8 * any later version.
10 * Cleanflight and Betaflight are distributed in the hope that they
11 * will be useful, but WITHOUT ANY WARRANTY; without even the implied
12 * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
13 * See the GNU General Public License for more details.
15 * You should have received a copy of the GNU General Public License
16 * along with this software.
18 * If not, see <http://www.gnu.org/licenses/>.
22 * Authors:
23 * Dominic Clifton/Hydra
24 * Carsten Giesen
25 * Adam Majerczyk (majerczyk.adam@gmail.com)
26 * Textmode add-on by Michi (mamaretti32@gmail.com)
27 * Scavanger & Ziege-One: CMS Textmode addon
30 #pragma once
32 #include "common/time.h"
34 #define HOTTV4_RXTX 4
36 #define HOTTV4_TEXT_MODE_REQUEST_ID 0x7f
37 #define HOTTV4_BINARY_MODE_REQUEST_ID 0x80
39 #define HOTTV4_BUTTON_DEC 0xB
40 #define HOTTV4_BUTTON_INC 0xD
41 #define HOTTV4_BUTTON_SET 0x9
42 #define HOTTV4_BUTTON_NIL 0xF
43 #define HOTTV4_BUTTON_NEXT 0xE
44 #define HOTTV4_BUTTON_PREV 0x7
46 #define HOTT_EAM_OFFSET_HEIGHT 500
47 #define HOTT_EAM_OFFSET_M2S 72
48 #define HOTT_EAM_OFFSET_M3S 120
49 #define HOTT_EAM_OFFSET_TEMPERATURE 20
51 #define HOTT_GPS_ALTITUDE_OFFSET 500
53 typedef enum {
54 HOTT_EAM_ALARM1_FLAG_NONE = 0,
55 HOTT_EAM_ALARM1_FLAG_MAH = (1 << 0),
56 HOTT_EAM_ALARM1_FLAG_BATTERY_1 = (1 << 1),
57 HOTT_EAM_ALARM1_FLAG_BATTERY_2 = (1 << 2),
58 HOTT_EAM_ALARM1_FLAG_TEMPERATURE_1 = (1 << 3),
59 HOTT_EAM_ALARM1_FLAG_TEMPERATURE_2 = (1 << 4),
60 HOTT_EAM_ALARM1_FLAG_ALTITUDE = (1 << 5),
61 HOTT_EAM_ALARM1_FLAG_CURRENT = (1 << 6),
62 HOTT_EAM_ALARM1_FLAG_MAIN_VOLTAGE = (1 << 7)
63 } hottEamAlarm1Flag_e;
65 typedef enum {
66 HOTT_EAM_ALARM2_FLAG_NONE = 0,
67 HOTT_EAM_ALARM2_FLAG_MS = (1 << 0),
68 HOTT_EAM_ALARM2_FLAG_M3S = (1 << 1),
69 HOTT_EAM_ALARM2_FLAG_ALTITUDE_DUPLICATE = (1 << 2),
70 HOTT_EAM_ALARM2_FLAG_MS_DUPLICATE = (1 << 3),
71 HOTT_EAM_ALARM2_FLAG_M3S_DUPLICATE = (1 << 4),
72 HOTT_EAM_ALARM2_FLAG_UNKNOWN_1 = (1 << 5),
73 HOTT_EAM_ALARM2_FLAG_UNKNOWN_2 = (1 << 6),
74 HOTT_EAM_ALARM2_FLAG_ON_SIGN_OR_TEXT_ACTIVE = (1 << 7)
75 } hottEamAlarm2Flag_e;
79 // Messages
82 #define HOTT_TEXT_MODE_REQUEST_ID 0x7f
83 #define HOTT_BINARY_MODE_REQUEST_ID 0x80
84 //Sensor Ids
86 //Id 0x80 is used when no sensor has been found during the bus scan
87 // additionaly meaning?
88 #define HOTT_TELEMETRY_NO_SENSOR_ID 0x80
90 //Graupner #33601 Vario Module
91 #define HOTT_TELEMETRY_VARIO_SENSOR_ID 0x89
93 //Graupner #33600 GPS Module
94 #define HOTT_TELEMETRY_GPS_SENSOR_ID 0x8a
96 //Graupner #337xx Air ESC
97 #define HOTT_TELEMETRY_AIRESC_SENSOR_ID 0x8c
99 //Graupner #33611 General Air Module
100 #define HOTT_TELEMETRY_GAM_SENSOR_ID 0x8d
102 //Graupner #33620 Electric Air Module
103 #define HOTT_TELEMETRY_EAM_SENSOR_ID 0x8e
106 #define HOTT_EAM_SENSOR_TEXT_ID 0xE0 // Electric Air Module ID
107 #define HOTT_GPS_SENSOR_TEXT_ID 0xA0 // GPS Module ID
109 #define HOTT_TEXTMODE_DISPLAY_ROWS 8
110 #define HOTT_TEXTMODE_DISPLAY_COLUMNS 21
111 #define HOTT_TEXTMODE_START 0x7B
112 #define HOTT_TEXTMODE_STOP 0x7D
113 #define HOTT_TEXTMODE_ESC 0x01
114 //Text mode msgs type
115 typedef struct hottTextModeMsg_s {
116 uint8_t start; //#01 constant value 0x7b
117 uint8_t esc; //#02 Low byte: Sensor ID or 0x01 for escape
118 uint8_t warning; //#03 1=A 2=B ...
119 uint8_t txt[HOTT_TEXTMODE_DISPLAY_ROWS][HOTT_TEXTMODE_DISPLAY_COLUMNS]; //#04 ASCII text to display to
120 // Bit 7 = 1 -> Inverse character display
121 // Display 21x8
122 uint8_t stop; //#171 constant value 0x7d
123 } hottTextModeMsg_t;
125 typedef struct HOTT_GAM_MSG_s {
126 uint8_t start_byte; //#01 start uint8_t constant value 0x7c
127 uint8_t gam_sensor_id; //#02 EAM sensort id. constat value 0x8d
128 uint8_t warning_beeps; //#03 1=A 2=B ... 0x1a=Z 0 = no alarm
129 // Q Min cell voltage sensor 1
130 // R Min Battery 1 voltage sensor 1
131 // J Max Battery 1 voltage sensor 1
132 // F Min temperature sensor 1
133 // H Max temperature sensor 1
134 // S Min Battery 2 voltage sensor 2
135 // K Max Battery 2 voltage sensor 2
136 // G Min temperature sensor 2
137 // I Max temperature sensor 2
138 // W Max current
139 // V Max capacity mAh
140 // P Min main power voltage
141 // X Max main power voltage
142 // O Min altitude
143 // Z Max altitude
144 // C negative difference m/s too high
145 // A negative difference m/3s too high
146 // N positive difference m/s too high
147 // L positive difference m/3s too high
148 // T Minimum RPM
149 // Y Maximum RPM
151 uint8_t sensor_id; //#04 constant value 0xd0
152 uint8_t alarm_invers1; //#05 alarm bitmask. Value is displayed inverted
153 //Bit# Alarm field
154 // 0 all cell voltage
155 // 1 Battery 1
156 // 2 Battery 2
157 // 3 Temperature 1
158 // 4 Temperature 2
159 // 5 Fuel
160 // 6 mAh
161 // 7 Altitude
162 uint8_t alarm_invers2; //#06 alarm bitmask. Value is displayed inverted
163 //Bit# Alarm Field
164 // 0 main power current
165 // 1 main power voltage
166 // 2 Altitude
167 // 3 m/s
168 // 4 m/3s
169 // 5 unknown
170 // 6 unknown
171 // 7 "ON" sign/text msg active
173 uint8_t cell1; //#07 cell 1 voltage lower value. 0.02V steps, 124=2.48V
174 uint8_t cell2; //#08
175 uint8_t cell3; //#09
176 uint8_t cell4; //#10
177 uint8_t cell5; //#11
178 uint8_t cell6; //#12
179 uint8_t batt1_L; //#13 battery 1 voltage LSB value. 0.1V steps. 50 = 5.5V
180 uint8_t batt1_H; //#14
181 uint8_t batt2_L; //#15 battery 2 voltage LSB value. 0.1V steps. 50 = 5.5V
182 uint8_t batt2_H; //#16
183 uint8_t temperature1; //#17 temperature 1. offset of 20. a value of 20 = 0�C
184 uint8_t temperature2; //#18 temperature 2. offset of 20. a value of 20 = 0�C
185 uint8_t fuel_procent; //#19 Fuel capacity in %. Values 0--100
186 // graphical display ranges: 0-25% 50% 75% 100%
187 uint8_t fuel_ml_L; //#20 Fuel in ml scale. Full = 65535!
188 uint8_t fuel_ml_H; //#21
189 uint8_t rpm_L; //#22 RPM in 10 RPM steps. 300 = 3000rpm
190 uint8_t rpm_H; //#23
191 uint8_t altitude_L; //#24 altitude in meters. offset of 500, 500 = 0m
192 uint8_t altitude_H; //#25
193 uint8_t climbrate_L; //#26 climb rate in 0.01m/s. Value of 30000 = 0.00 m/s
194 uint8_t climbrate_H; //#27
195 uint8_t climbrate3s; //#28 climb rate in m/3sec. Value of 120 = 0m/3sec
196 uint8_t current_L; //#29 current in 0.1A steps
197 uint8_t current_H; //#30
198 uint8_t main_voltage_L; //#31 Main power voltage using 0.1V steps
199 uint8_t main_voltage_H; //#32
200 uint8_t batt_cap_L; //#33 used battery capacity in 10mAh steps
201 uint8_t batt_cap_H; //#34
202 uint8_t speed_L; //#35 (air?) speed in km/h(?) we are using ground speed here per default
203 uint8_t speed_H; //#36
204 uint8_t min_cell_volt; //#37 minimum cell voltage in 2mV steps. 124 = 2,48V
205 uint8_t min_cell_volt_num; //#38 number of the cell with the lowest voltage
206 uint8_t rpm2_L; //#39 RPM in 10 RPM steps. 300 = 3000rpm
207 uint8_t rpm2_H; //#40
208 uint8_t general_error_number;//#41 Voice error == 12. TODO: more docu
209 uint8_t pressure; //#42 Pressure up to 16bar. 0,1bar scale. 20 = 2bar
210 uint8_t version; //#43 version number TODO: more info?
211 uint8_t stop_byte; //#44 stop uint8_t
212 } OTT_GAM_MSG_t;
214 #define HOTT_VARIO_MSG_TEXT_LEN 21
215 typedef struct HOTT_VARIO_MSG_s {
216 uint8_t start_byte; //#01 start uint8_t constant value 0x7c
217 uint8_t vario_sensor_id; //#02 VARIO sensort id. constat value 0x89
218 uint8_t warning_beeps; //#03 1=A 2=B ...
219 // Q Min cell voltage sensor 1
220 // R Min Battery 1 voltage sensor 1
221 // J Max Battery 1 voltage sensor 1
222 // F Min temperature sensor 1
223 // H Max temperature sensor 1
224 // S Min Battery voltage sensor 2
225 // K Max Battery voltage sensor 2
226 // G Min temperature sensor 2
227 // I Max temperature sensor 2
228 // W Max current
229 // V Max capacity mAh
230 // P Min main power voltage
231 // X Max main power voltage
232 // O Min altitude
233 // Z Max altitude
234 // T Minimum RPM
235 // Y Maximum RPM
236 // C m/s negative difference
237 // A m/3s negative difference
240 uint8_t sensor_id; //#04 constant value 0x90
241 uint8_t alarm_invers1; //#05 Inverse display (alarm?) bitmask
242 //TODO: more info
243 uint8_t altitude_L; //#06 Altitude low uint8_t. In meters. A value of 500 means 0m
244 uint8_t altitude_H; //#07 Altitude high uint8_t
245 uint8_t altitude_max_L; //#08 Max. measured altitude low uint8_t. In meters. A value of 500 means 0m
246 uint8_t altitude_max_H; //#09 Max. measured altitude high uint8_t
247 uint8_t altitude_min_L; //#10 Min. measured altitude low uint8_t. In meters. A value of 500 means 0m
248 uint8_t altitude_min_H; //#11 Min. measured altitude high uint8_t
249 uint8_t climbrate_L; //#12 Climb rate in m/s. Steps of 0.01m/s. Value of 30000 = 0.00 m/s
250 uint8_t climbrate_H; //#13 Climb rate in m/s
251 uint8_t climbrate3s_L; //#14 Climb rate in m/3s. Steps of 0.01m/3s. Value of 30000 = 0.00 m/3s
252 uint8_t climbrate3s_H; //#15 Climb rate m/3s low uint8_t
253 uint8_t climbrate10s_L; //#16 Climb rate m/10s. Steps of 0.01m/10s. Value of 30000 = 0.00 m/10s
254 uint8_t climbrate10s_H; //#17 Climb rate m/10s low uint8_t
255 uint8_t text_msg[HOTT_VARIO_MSG_TEXT_LEN]; //#18 Free ASCII text message
256 uint8_t free_char1; //#39 Free ASCII character. appears right to home distance
257 uint8_t free_char2; //#40 Free ASCII character. appears right to home direction
258 uint8_t free_char3; //#41 Free ASCII character. appears? TODO: Check where this char appears
259 uint8_t compass_direction; //#42 Compass heading in 2� steps. 1 = 2�
260 uint8_t version; //#43 version number TODO: more info?
261 uint8_t stop_byte; //#44 stop uint8_t, constant value 0x7d
262 } HOTT_VARIO_MSG_t;
264 typedef struct HOTT_EAM_MSG_s {
265 uint8_t start_byte; //#01 start uint8_t
266 uint8_t eam_sensor_id; //#02 EAM sensort id. constat value 0x8e
267 uint8_t warning_beeps; //#03 1=A 2=B ... or 'A' - 0x40 = 1
268 // Q Min cell voltage sensor 1
269 // R Min Battery 1 voltage sensor 1
270 // J Max Battery 1 voltage sensor 1
271 // F Mim temperature sensor 1
272 // H Max temperature sensor 1
273 // S Min cell voltage sensor 2
274 // K Max cell voltage sensor 2
275 // G Min temperature sensor 2
276 // I Max temperature sensor 2
277 // W Max current
278 // V Max capacity mAh
279 // P Min main power voltage
280 // X Max main power voltage
281 // O Min altitude
282 // Z Max altitude
283 // C (negative) sink rate m/sec to high
284 // B (negative) sink rate m/3sec to high
285 // N climb rate m/sec to high
286 // M climb rate m/3sec to high
288 uint8_t sensor_id; //#04 constant value 0xe0
289 uint8_t alarm_invers1; //#05 alarm bitmask. Value is displayed inverted
290 //Bit# Alarm field
291 // 0 mAh
292 // 1 Battery 1
293 // 2 Battery 2
294 // 3 Temperature 1
295 // 4 Temperature 2
296 // 5 Altitude
297 // 6 Current
298 // 7 Main power voltage
299 uint8_t alarm_invers2; //#06 alarm bitmask. Value is displayed inverted
300 //Bit# Alarm Field
301 // 0 m/s
302 // 1 m/3s
303 // 2 Altitude (duplicate?)
304 // 3 m/s (duplicate?)
305 // 4 m/3s (duplicate?)
306 // 5 unknown/unused
307 // 6 unknown/unused
308 // 7 "ON" sign/text msg active
310 uint8_t cell1_L; //#07 cell 1 voltage lower value. 0.02V steps, 124=2.48V
311 uint8_t cell2_L; //#08
312 uint8_t cell3_L; //#09
313 uint8_t cell4_L; //#10
314 uint8_t cell5_L; //#11
315 uint8_t cell6_L; //#12
316 uint8_t cell7_L; //#13
317 uint8_t cell1_H; //#14 cell 1 voltage high value. 0.02V steps, 124=2.48V
318 uint8_t cell2_H; //#15
319 uint8_t cell3_H; //#16
320 uint8_t cell4_H; //#17
321 uint8_t cell5_H; //#18
322 uint8_t cell6_H; //#19
323 uint8_t cell7_H; //#20
325 uint8_t batt1_voltage_L; //#21 battery 1 voltage lower value in 100mv steps, 50=5V. optionally cell8_L value 0.02V steps
326 uint8_t batt1_voltage_H; //#22
328 uint8_t batt2_voltage_L; //#23 battery 2 voltage lower value in 100mv steps, 50=5V. optionally cell8_H value. 0.02V steps
329 uint8_t batt2_voltage_H; //#24
331 uint8_t temp1; //#25 Temperature sensor 1. 20=0�, 46=26� - offset of 20.
332 uint8_t temp2; //#26 temperature sensor 2
334 uint8_t altitude_L; //#27 Attitude lower value. unit: meters. Value of 500 = 0m
335 uint8_t altitude_H; //#28
337 uint8_t current_L; //#29 Current in 0.1 steps
338 uint8_t current_H; //#30
340 uint8_t main_voltage_L; //#31 Main power voltage (drive) in 0.1V steps
341 uint8_t main_voltage_H; //#32
343 uint8_t batt_cap_L; //#33 used battery capacity in 10mAh steps
344 uint8_t batt_cap_H; //#34
346 uint8_t climbrate_L; //#35 climb rate in 0.01m/s. Value of 30000 = 0.00 m/s
347 uint8_t climbrate_H; //#36
349 uint8_t climbrate3s; //#37 climbrate in m/3sec. Value of 120 = 0m/3sec
351 uint8_t rpm_L; //#38 RPM. Steps: 10 U/min
352 uint8_t rpm_H; //#39
354 uint8_t electric_min; //#40 Electric minutes. Time does start, when motor current is > 3 A
355 uint8_t electric_sec; //#41
357 uint8_t speed_L; //#42 (air?) speed in km/h. Steps 1km/h
358 uint8_t speed_H; //#43
359 uint8_t stop_byte; //#44 stop uint8_t
360 } HOTT_EAM_MSG_t;
362 //HoTT GPS Sensor response to Receiver (?!not?! Smartbox)
363 typedef struct HOTT_GPS_MSG_s {
364 uint8_t start_byte; //#01 constant value 0x7c
365 uint8_t gps_sensor_id; //#02 constant value 0x8a
366 uint8_t warning_beeps; //#03 1=A 2=B ...
367 // A Min Speed
368 // L Max Speed
369 // O Min Altitude
370 // Z Max Altitude
371 // C (negative) sink rate m/sec to high
372 // B (negative) sink rate m/3sec to high
373 // N climb rate m/sec to high
374 // M climb rate m/3sec to high
375 // D Max home distance
378 uint8_t sensor_id; //#04 constant (?) value 0xa0
379 uint8_t alarm_invers1; //#05
380 //TODO: more info
381 uint8_t alarm_invers2; //#06 1 = No GPS signal
382 //TODO: more info
384 uint8_t flight_direction; //#07 flight direction in 2 degreees/step (1 = 2degrees);
385 uint8_t gps_speed_L; //08 km/h
386 uint8_t gps_speed_H; //#09
388 uint8_t pos_NS; //#10 north = 0, south = 1
389 uint8_t pos_NS_dm_L; //#11 degree minutes ie N48�39�988
390 uint8_t pos_NS_dm_H; //#12
391 uint8_t pos_NS_sec_L; //#13 position seconds
392 uint8_t pos_NS_sec_H; //#14
394 uint8_t pos_EW; //#15 east = 0, west = 1
395 uint8_t pos_EW_dm_L; //#16 degree minutes ie. E9�25�9360
396 uint8_t pos_EW_dm_H; //#17
397 uint8_t pos_EW_sec_L; //#18 position seconds
398 uint8_t pos_EW_sec_H; //#19
400 uint8_t home_distance_L; //#20 meters
401 uint8_t home_distance_H; //#21
403 uint8_t altitude_L; //#22 meters. Value of 500 = 0m
404 uint8_t altitude_H; //#23
406 uint8_t climbrate_L; //#24 m/s 0.01m/s resolution. Value of 30000 = 0.00 m/s
407 uint8_t climbrate_H; //#25
409 uint8_t climbrate3s; //#26 climbrate in m/3s resolution, value of 120 = 0 m/3s
411 uint8_t gps_satelites;//#27 sat count
412 uint8_t gps_fix_char; //#28 GPS fix character. display, 'D' = DGPS, '2' = 2D, '3' = 3D, '-' = no fix. Where appears this char???
414 uint8_t home_direction;//#29 direction from starting point to Model position (2 degree steps)
415 uint8_t angle_roll; //#30 angle roll in 2 degree steps
416 uint8_t angle_nick; //#31 angle in 2degree steps
417 uint8_t angle_compass; //#32 angle in 2degree steps. 1 = 2�, 255 = - 2� (1 uint8_t) North = 0�
419 uint8_t gps_time_h; //#33 UTC time hours
420 uint8_t gps_time_m; //#34 UTC time minutes
421 uint8_t gps_time_s; //#35 UTC time seconds
422 uint8_t gps_time_sss; //#36 UTC time milliseconds
424 uint8_t msl_altitude_L;//#37 mean sea level altitude
425 uint8_t msl_altitude_H;//#38
427 uint8_t vibration; //#39 vibrations level in %
429 uint8_t free_char1; //#40 appears right to home distance
430 uint8_t free_char2; //#41 appears right to home direction
431 uint8_t free_char3; //#42 GPS ASCII D=DGPS 2=2D 3=3D -=No Fix
432 uint8_t version; //#43
433 // 0 GPS Graupner #33600
434 // 1 Gyro Receiver
435 // 255 Mikrokopter
436 uint8_t stop_byte; //#44 constant value 0x7d
437 } HOTT_GPS_MSG_t;
439 typedef struct HOTT_AIRESC_MSG_s {
440 uint8_t start_byte; //#01 constant value 0x7c
441 uint8_t gps_sensor_id; //#02 constant value 0x8c
442 uint8_t warning_beeps; //#03 1=A 2=B ...
443 // A
444 // L
445 // O
446 // Z
447 // C
448 // B
449 // N
450 // M
451 // D
454 uint8_t sensor_id; //#04 constant value 0xc0
455 uint8_t alarm_invers1; //#05 TODO: more info
456 uint8_t alarm_invers2; //#06 TODO: more info
457 uint8_t input_v_L; //#07 Input voltage low byte
458 uint8_t input_v_H; //#08
459 uint8_t input_v_min_L; //#09 Input min. voltage low byte
460 uint8_t input_v_min_H; //#10
461 uint8_t batt_cap_L; //#11 battery capacity in 10mAh steps
462 uint8_t batt_cap_H; //#12
463 uint8_t esc_temp; //#13 ESC temperature
464 uint8_t esc_max_temp; //#14 ESC max. temperature
465 uint8_t current_L; //#15 Current in 0.1 steps
466 uint8_t current_H; //#16
467 uint8_t current_max_L; //#17 Current max. in 0.1 steps
468 uint8_t current_max_H; //#18
469 uint8_t rpm_L; //#19 RPM in 10U/min steps
470 uint8_t rpm_H; //#20
471 uint8_t rpm_max_L; //#21 RPM max
472 uint8_t rpm_max_H; //#22
473 uint8_t throttle; //#23 throttle in %
474 uint8_t speed_L; //#24 Speed
475 uint8_t speed_H; //#25
476 uint8_t speed_max_L; //#26 Speed max
477 uint8_t speed_max_H; //#27
478 uint8_t bec_v; //#28 BEC voltage
479 uint8_t bec_min_v; //#29 BEC min. voltage
480 uint8_t bec_current; //#30 BEC current
481 uint8_t bec_current_max_L; //#31 BEC max. current
482 uint8_t bec_current_max_H; //#32 TODO: not really clear why 2 bytes...
483 uint8_t pwm; //#33 PWM
484 uint8_t bec_temp; //#34 BEC temperature
485 uint8_t bec_temp_max; //#35 BEC highest temperature
486 uint8_t motor_temp; //#36 Motor or external sensor temperature
487 uint8_t motor_temp_max; //#37 Highest motor or external sensor temperature
488 uint8_t motor_rpm_L; //#38 Motor or external RPM sensor (without gear)
489 uint8_t motor_rpm_H; //#39
490 uint8_t motor_timing; //#40 Motor timing
491 uint8_t motor_timing_adv; //#41 Motor advanced timing
492 uint8_t motor_highest_current; //#42 Motor number (1-x) with highest current
493 uint8_t version; //#43 Version number (highest current motor 1-x)
494 uint8_t stop_byte; //#44 constant value 0x7d
495 } HOTT_AIRESC_MSG_t;
497 void handleHoTTTelemetry(timeUs_t currentTimeUs);
498 void checkHoTTTelemetryState(void);
500 void initHoTTTelemetry(void);
501 void configureHoTTTelemetryPort(void);
502 void freeHoTTTelemetryPort(void);
504 #if defined (USE_HOTT_TEXTMODE) && defined (USE_CMS)
505 bool hottTextmodeIsAlive();
506 void hottTextmodeGrab();
507 void hottTextmodeExit();
508 void hottTextmodeWriteChar(uint8_t column, uint8_t row, char c);
509 #endif
511 uint32_t getHoTTTelemetryProviderBaudRate(void);
513 void hottPrepareGPSResponse(HOTT_GPS_MSG_t *hottGPSMessage);