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)
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/>.
25 * Dominic Clifton - Hydra - Software Serial, Electronics, Hardware Integration and debugging, HoTT Code cleanup and fixes, general telemetry improvements.
26 * Carsten Giesen - cGiesen - Baseflight port
27 * Oliver Bayer - oBayer - MultiWii-HoTT, HoTT reverse engineering
28 * Adam Majerczyk - HoTT-for-ardupilot from which some information and ideas are borrowed.
29 * Scavanger & Ziege-One: CMS Textmode addon
31 * https://github.com/obayer/MultiWii-HoTT
32 * https://github.com/oBayer/MultiHoTT-Module
33 * https://code.google.com/p/hott-for-ardupilot
35 * HoTT is implemented in Graupner equipment using a bi-directional protocol over a single wire.
37 * Generally the receiver sends a single request byte out using normal uart signals, then waits a short period for a
38 * multiple byte response and checksum byte before it sends out the next request byte.
39 * Each response byte must be send with a protocol specific delay between them.
41 * Serial ports use two wires but HoTT uses a single wire so some electronics are required so that
42 * the signals don't get mixed up. When cleanflight transmits it should not receive it's own transmission.
45 * HoTT TX/RX -> Serial RX (connect directly)
46 * Serial TX -> 1N4148 Diode -(| )-> HoTT TX/RX (connect via diode)
48 * The diode should be arranged to allow the data signals to flow the right way
49 * -(| )- == Diode, | indicates cathode marker.
51 * 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.
53 * Note: The softserial ports are not listed as 5V tolerant in the STM32F103xx data sheet pinouts and pin description
54 * section. Verify if you require a 5v/3.3v level shifters. The softserial port should not be inverted.
56 * There is a technical discussion (in German) about HoTT here
57 * http://www.rc-network.de/forum/showthread.php/281496-Graupner-HoTT-Telemetrie-Sensoren-Eigenbau-DIY-Telemetrie-Protokoll-entschl%C3%BCsselt/page21
66 #ifdef USE_TELEMETRY_HOTT
68 #include "build/build_config.h"
69 #include "build/debug.h"
71 #include "common/axis.h"
72 #include "common/maths.h"
73 #include "common/time.h"
75 #include "drivers/serial.h"
76 #include "drivers/time.h"
78 #include "fc/runtime_config.h"
80 #include "flight/position.h"
81 #include "flight/pid.h"
85 #include "sensors/battery.h"
86 #include "sensors/barometer.h"
87 #include "sensors/sensors.h"
89 #include "telemetry/hott.h"
90 #include "telemetry/telemetry.h"
92 #if defined (USE_HOTT_TEXTMODE) && defined (USE_CMS)
93 #include "scheduler/scheduler.h"
94 #include "io/displayport_hott.h"
96 #define HOTT_TEXTMODE_TASK_PERIOD 1000
97 #define HOTT_TEXTMODE_RX_SCHEDULE 5000
98 #define HOTT_TEXTMODE_TX_DELAY_US 1000
103 #define HOTT_MESSAGE_PREPARATION_FREQUENCY_5_HZ ((1000 * 1000) / 5)
104 #define HOTT_RX_SCHEDULE 4000
105 #define HOTT_TX_DELAY_US 3000
106 #define MILLISECONDS_IN_A_SECOND 1000
108 static uint32_t rxSchedule
= HOTT_RX_SCHEDULE
;
109 static uint32_t txDelayUs
= HOTT_TX_DELAY_US
;
111 static uint32_t lastHoTTRequestCheckAt
= 0;
112 static uint32_t lastMessagesPreparedAt
= 0;
113 static uint32_t lastHottAlarmSoundTime
= 0;
115 static bool hottIsSending
= false;
117 static uint8_t *hottMsg
= NULL
;
118 static uint8_t hottMsgRemainingBytesToSendCount
;
119 static uint8_t hottMsgCrc
;
121 #define HOTT_CRC_SIZE (sizeof(hottMsgCrc))
123 #define HOTT_BAUDRATE 19200
124 #define HOTT_PORT_MODE MODE_RXTX // must be opened in RXTX so that TX and RX pins are allocated.
126 static serialPort_t
*hottPort
= NULL
;
127 static const serialPortConfig_t
*portConfig
;
129 static bool hottTelemetryEnabled
= false;
130 static portSharing_e hottPortSharing
;
132 static HOTT_GPS_MSG_t hottGPSMessage
;
133 static HOTT_EAM_MSG_t hottEAMMessage
;
135 #if defined (USE_HOTT_TEXTMODE) && defined (USE_CMS)
136 static hottTextModeMsg_t hottTextModeMessage
;
137 static bool textmodeIsAlive
= false;
138 static int32_t telemetryTaskPeriod
= 0;
140 static void initialiseTextmodeMessage(hottTextModeMsg_t
*msg
)
142 msg
->start
= HOTT_TEXTMODE_START
;
143 msg
->esc
= HOTT_EAM_SENSOR_TEXT_ID
;
145 msg
->stop
= HOTT_TEXTMODE_STOP
;
149 static void initialiseEAMMessage(HOTT_EAM_MSG_t
*msg
, size_t size
)
151 memset(msg
, 0, size
);
152 msg
->start_byte
= 0x7C;
153 msg
->eam_sensor_id
= HOTT_TELEMETRY_EAM_SENSOR_ID
;
154 msg
->sensor_id
= HOTT_EAM_SENSOR_TEXT_ID
;
155 msg
->stop_byte
= 0x7D;
160 GPS_FIX_CHAR_NONE
= '-',
161 GPS_FIX_CHAR_2D
= '2',
162 GPS_FIX_CHAR_3D
= '3',
163 GPS_FIX_CHAR_DGPS
= 'D'
166 static void initialiseGPSMessage(HOTT_GPS_MSG_t
*msg
, size_t size
)
168 memset(msg
, 0, size
);
169 msg
->start_byte
= 0x7C;
170 msg
->gps_sensor_id
= HOTT_TELEMETRY_GPS_SENSOR_ID
;
171 msg
->sensor_id
= HOTT_GPS_SENSOR_TEXT_ID
;
172 msg
->stop_byte
= 0x7D;
176 static void initialiseMessages(void)
178 initialiseEAMMessage(&hottEAMMessage
, sizeof(hottEAMMessage
));
180 initialiseGPSMessage(&hottGPSMessage
, sizeof(hottGPSMessage
));
182 #if defined (USE_HOTT_TEXTMODE) && defined (USE_CMS)
183 initialiseTextmodeMessage(&hottTextModeMessage
);
188 void addGPSCoordinates(HOTT_GPS_MSG_t
*hottGPSMessage
, int32_t latitude
, int32_t longitude
)
190 int16_t deg
= latitude
/ GPS_DEGREES_DIVIDER
;
191 int32_t sec
= (latitude
- (deg
* GPS_DEGREES_DIVIDER
)) * 6;
192 int8_t min
= sec
/ 1000000L;
193 sec
= (sec
% 1000000L) / 100L;
194 uint16_t degMin
= (deg
* 100L) + min
;
196 hottGPSMessage
->pos_NS
= (latitude
< 0);
197 hottGPSMessage
->pos_NS_dm_L
= degMin
;
198 hottGPSMessage
->pos_NS_dm_H
= degMin
>> 8;
199 hottGPSMessage
->pos_NS_sec_L
= sec
;
200 hottGPSMessage
->pos_NS_sec_H
= sec
>> 8;
202 deg
= longitude
/ GPS_DEGREES_DIVIDER
;
203 sec
= (longitude
- (deg
* GPS_DEGREES_DIVIDER
)) * 6;
204 min
= sec
/ 1000000L;
205 sec
= (sec
% 1000000L) / 100L;
206 degMin
= (deg
* 100L) + min
;
208 hottGPSMessage
->pos_EW
= (longitude
< 0);
209 hottGPSMessage
->pos_EW_dm_L
= degMin
;
210 hottGPSMessage
->pos_EW_dm_H
= degMin
>> 8;
211 hottGPSMessage
->pos_EW_sec_L
= sec
;
212 hottGPSMessage
->pos_EW_sec_H
= sec
>> 8;
215 void hottPrepareGPSResponse(HOTT_GPS_MSG_t
*hottGPSMessage
)
217 hottGPSMessage
->gps_satelites
= gpsSol
.numSat
;
219 if (!STATE(GPS_FIX
)) {
220 hottGPSMessage
->gps_fix_char
= GPS_FIX_CHAR_NONE
;
224 if (gpsSol
.numSat
>= 5) {
225 hottGPSMessage
->gps_fix_char
= GPS_FIX_CHAR_3D
;
227 hottGPSMessage
->gps_fix_char
= GPS_FIX_CHAR_2D
;
230 addGPSCoordinates(hottGPSMessage
, gpsSol
.llh
.lat
, gpsSol
.llh
.lon
);
232 // GPS Speed is returned in cm/s (from io/gps.c) and must be sent in km/h (Hott requirement)
233 const uint16_t speed
= (gpsSol
.groundSpeed
* 36) / 1000;
234 hottGPSMessage
->gps_speed_L
= speed
& 0x00FF;
235 hottGPSMessage
->gps_speed_H
= speed
>> 8;
237 hottGPSMessage
->home_distance_L
= GPS_distanceToHome
& 0x00FF;
238 hottGPSMessage
->home_distance_H
= GPS_distanceToHome
>> 8;
240 int32_t altitudeM
= getEstimatedAltitudeCm() / 100;
242 const uint16_t hottGpsAltitude
= constrain(altitudeM
+ HOTT_GPS_ALTITUDE_OFFSET
, 0 , UINT16_MAX
); // gpsSol.llh.alt in m ; offset = 500 -> O m
244 hottGPSMessage
->altitude_L
= hottGpsAltitude
& 0x00FF;
245 hottGPSMessage
->altitude_H
= hottGpsAltitude
>> 8;
247 hottGPSMessage
->home_direction
= GPS_directionToHome
;
251 static bool shouldTriggerBatteryAlarmNow(void)
253 return ((millis() - lastHottAlarmSoundTime
) >= (telemetryConfig()->hottAlarmSoundInterval
* MILLISECONDS_IN_A_SECOND
));
256 static inline void updateAlarmBatteryStatus(HOTT_EAM_MSG_t
*hottEAMMessage
)
258 if (shouldTriggerBatteryAlarmNow()) {
259 lastHottAlarmSoundTime
= millis();
260 const batteryState_e voltageState
= getVoltageState();
261 const batteryState_e consumptionState
= getConsumptionState();
262 if (voltageState
== BATTERY_WARNING
|| voltageState
== BATTERY_CRITICAL
) {
263 hottEAMMessage
->warning_beeps
= 0x10;
264 hottEAMMessage
->alarm_invers1
= HOTT_EAM_ALARM1_FLAG_BATTERY_1
;
266 else if (consumptionState
== BATTERY_WARNING
|| consumptionState
== BATTERY_CRITICAL
) {
267 hottEAMMessage
->warning_beeps
= 0x16;
268 hottEAMMessage
->alarm_invers1
= HOTT_EAM_ALARM1_FLAG_MAH
;
271 hottEAMMessage
->warning_beeps
= HOTT_EAM_ALARM1_FLAG_NONE
;
272 hottEAMMessage
->alarm_invers1
= HOTT_EAM_ALARM1_FLAG_NONE
;
277 static inline void hottEAMUpdateBattery(HOTT_EAM_MSG_t
*hottEAMMessage
)
279 const uint16_t volt
= getLegacyBatteryVoltage();
280 hottEAMMessage
->main_voltage_L
= volt
& 0xFF;
281 hottEAMMessage
->main_voltage_H
= volt
>> 8;
282 hottEAMMessage
->batt1_voltage_L
= volt
& 0xFF;
283 hottEAMMessage
->batt1_voltage_H
= volt
>> 8;
285 updateAlarmBatteryStatus(hottEAMMessage
);
288 static inline void hottEAMUpdateCurrentMeter(HOTT_EAM_MSG_t
*hottEAMMessage
)
290 const int32_t amp
= getAmperage() / 10;
291 hottEAMMessage
->current_L
= amp
& 0xFF;
292 hottEAMMessage
->current_H
= amp
>> 8;
295 static inline void hottEAMUpdateBatteryDrawnCapacity(HOTT_EAM_MSG_t
*hottEAMMessage
)
297 const int32_t mAh
= getMAhDrawn() / 10;
298 hottEAMMessage
->batt_cap_L
= mAh
& 0xFF;
299 hottEAMMessage
->batt_cap_H
= mAh
>> 8;
302 static inline void hottEAMUpdateAltitude(HOTT_EAM_MSG_t
*hottEAMMessage
)
304 const uint16_t hottEamAltitude
= (getEstimatedAltitudeCm() / 100) + HOTT_EAM_OFFSET_HEIGHT
;
306 hottEAMMessage
->altitude_L
= hottEamAltitude
& 0x00FF;
307 hottEAMMessage
->altitude_H
= hottEamAltitude
>> 8;
311 static inline void hottEAMUpdateClimbrate(HOTT_EAM_MSG_t
*hottEAMMessage
)
313 const int32_t vario
= getEstimatedVario();
314 hottEAMMessage
->climbrate_L
= (30000 + vario
) & 0x00FF;
315 hottEAMMessage
->climbrate_H
= (30000 + vario
) >> 8;
316 hottEAMMessage
->climbrate3s
= 120 + (vario
/ 100);
320 void hottPrepareEAMResponse(HOTT_EAM_MSG_t
*hottEAMMessage
)
323 hottEAMMessage
->warning_beeps
= 0x0;
324 hottEAMMessage
->alarm_invers1
= 0x0;
326 hottEAMUpdateBattery(hottEAMMessage
);
327 hottEAMUpdateCurrentMeter(hottEAMMessage
);
328 hottEAMUpdateBatteryDrawnCapacity(hottEAMMessage
);
329 hottEAMUpdateAltitude(hottEAMMessage
);
331 hottEAMUpdateClimbrate(hottEAMMessage
);
335 static void hottSerialWrite(uint8_t c
)
337 static uint8_t serialWrites
= 0;
339 serialWrite(hottPort
, c
);
342 void freeHoTTTelemetryPort(void)
344 closeSerialPort(hottPort
);
346 hottTelemetryEnabled
= false;
349 void initHoTTTelemetry(void)
351 portConfig
= findSerialPortConfig(FUNCTION_TELEMETRY_HOTT
);
357 hottPortSharing
= determinePortSharing(portConfig
, FUNCTION_TELEMETRY_HOTT
);
359 #if defined (USE_HOTT_TEXTMODE) && defined (USE_CMS)
360 hottDisplayportRegister();
363 initialiseMessages();
366 static void flushHottRxBuffer(void)
368 while (serialRxBytesWaiting(hottPort
) > 0) {
369 serialRead(hottPort
);
373 static void workAroundForHottTelemetryOnUsart(serialPort_t
*instance
, portMode_e mode
)
375 closeSerialPort(hottPort
);
377 portOptions_e portOptions
= telemetryConfig()->telemetry_inverted
? SERIAL_INVERTED
: SERIAL_NOT_INVERTED
;
379 if (telemetryConfig()->halfDuplex
) {
380 portOptions
|= SERIAL_BIDIR
;
383 hottPort
= openSerialPort(instance
->identifier
, FUNCTION_TELEMETRY_HOTT
, NULL
, NULL
, HOTT_BAUDRATE
, mode
, portOptions
);
386 static bool hottIsUsingHardwareUART(void)
388 return !(portConfig
->identifier
== SERIAL_PORT_SOFTSERIAL1
|| portConfig
->identifier
== SERIAL_PORT_SOFTSERIAL2
);
391 static void hottConfigurePortForTX(void)
393 // FIXME temorary workaround for HoTT not working on Hardware serial ports due to hardware/softserial serial port initialisation differences
394 if (hottIsUsingHardwareUART()) {
395 workAroundForHottTelemetryOnUsart(hottPort
, MODE_TX
);
397 serialSetMode(hottPort
, MODE_TX
);
399 hottIsSending
= true;
403 static void hottConfigurePortForRX(void)
405 // FIXME temorary workaround for HoTT not working on Hardware serial ports due to hardware/softserial serial port initialisation differences
406 if (hottIsUsingHardwareUART()) {
407 workAroundForHottTelemetryOnUsart(hottPort
, MODE_RX
);
409 serialSetMode(hottPort
, MODE_RX
);
412 hottIsSending
= false;
416 void configureHoTTTelemetryPort(void)
422 portOptions_e portOptions
= SERIAL_NOT_INVERTED
;
424 if (telemetryConfig()->halfDuplex
) {
425 portOptions
|= SERIAL_BIDIR
;
428 hottPort
= openSerialPort(portConfig
->identifier
, FUNCTION_TELEMETRY_HOTT
, NULL
, NULL
, HOTT_BAUDRATE
, HOTT_PORT_MODE
, portOptions
);
434 hottConfigurePortForRX();
436 hottTelemetryEnabled
= true;
439 static void hottSendResponse(uint8_t *buffer
, int length
)
446 hottMsgRemainingBytesToSendCount
= length
+ HOTT_CRC_SIZE
;
449 static inline void hottSendGPSResponse(void)
451 hottSendResponse((uint8_t *)&hottGPSMessage
, sizeof(hottGPSMessage
));
454 static inline void hottSendEAMResponse(void)
456 hottSendResponse((uint8_t *)&hottEAMMessage
, sizeof(hottEAMMessage
));
459 static void hottPrepareMessages(void) {
460 hottPrepareEAMResponse(&hottEAMMessage
);
462 hottPrepareGPSResponse(&hottGPSMessage
);
466 #if defined (USE_HOTT_TEXTMODE) && defined (USE_CMS)
467 static void hottTextmodeStart()
469 // Increase menu speed
471 getTaskInfo(TASK_TELEMETRY
, &taskInfo
);
472 telemetryTaskPeriod
= taskInfo
.desiredPeriodUs
;
473 rescheduleTask(TASK_TELEMETRY
, TASK_PERIOD_HZ(HOTT_TEXTMODE_TASK_PERIOD
));
475 rxSchedule
= HOTT_TEXTMODE_RX_SCHEDULE
;
476 txDelayUs
= HOTT_TEXTMODE_TX_DELAY_US
;
479 static void hottTextmodeStop()
481 // Set back to avoid slow down of the FC
482 if (telemetryTaskPeriod
> 0) {
483 rescheduleTask(TASK_TELEMETRY
, telemetryTaskPeriod
);
484 telemetryTaskPeriod
= 0;
487 rxSchedule
= HOTT_RX_SCHEDULE
;
488 txDelayUs
= HOTT_TX_DELAY_US
;
491 bool hottTextmodeIsAlive()
493 return textmodeIsAlive
;
496 void hottTextmodeGrab()
498 hottTextModeMessage
.esc
= HOTT_EAM_SENSOR_TEXT_ID
;
501 void hottTextmodeExit()
503 hottTextModeMessage
.esc
= HOTT_TEXTMODE_ESC
;
506 void hottTextmodeWriteChar(uint8_t column
, uint8_t row
, char c
)
508 if (column
< HOTT_TEXTMODE_DISPLAY_COLUMNS
&& row
< HOTT_TEXTMODE_DISPLAY_ROWS
) {
509 if (hottTextModeMessage
.txt
[row
][column
] != c
)
510 hottTextModeMessage
.txt
[row
][column
] = c
;
514 static void processHottTextModeRequest(const uint8_t cmd
)
516 static bool setEscBack
= false;
518 if (!textmodeIsAlive
) {
520 textmodeIsAlive
= true;
523 if ((cmd
& 0xF0) != HOTT_EAM_SENSOR_TEXT_ID
) {
528 hottTextModeMessage
.esc
= HOTT_EAM_SENSOR_TEXT_ID
;
532 if (hottTextModeMessage
.esc
!= HOTT_TEXTMODE_ESC
) {
538 hottSetCmsKey(cmd
& 0x0f, hottTextModeMessage
.esc
== HOTT_TEXTMODE_ESC
);
539 hottSendResponse((uint8_t *)&hottTextModeMessage
, sizeof(hottTextModeMessage
));
543 static void processBinaryModeRequest(uint8_t address
)
545 #if defined (USE_HOTT_TEXTMODE) && defined (USE_CMS)
546 if (textmodeIsAlive
) {
548 textmodeIsAlive
= false;
553 static uint8_t hottBinaryRequests
= 0;
554 static uint8_t hottGPSRequests
= 0;
555 static uint8_t hottEAMRequests
= 0;
564 if (sensors(SENSOR_GPS
)) {
565 hottSendGPSResponse();
573 hottSendEAMResponse();
578 hottBinaryRequests
++;
579 debug
[0] = hottBinaryRequests
;
581 debug
[1] = hottGPSRequests
;
583 debug
[2] = hottEAMRequests
;
587 static void hottCheckSerialData(uint32_t currentMicros
)
589 static bool lookingForRequest
= true;
591 const uint8_t bytesWaiting
= serialRxBytesWaiting(hottPort
);
593 if (bytesWaiting
<= 1) {
597 if (bytesWaiting
!= 2) {
599 lookingForRequest
= true;
603 if (lookingForRequest
) {
604 lastHoTTRequestCheckAt
= currentMicros
;
605 lookingForRequest
= false;
608 bool enoughTimePassed
= currentMicros
- lastHoTTRequestCheckAt
>= rxSchedule
;
610 if (!enoughTimePassed
) {
613 lookingForRequest
= true;
616 const uint8_t requestId
= serialRead(hottPort
);
617 const uint8_t address
= serialRead(hottPort
);
619 if ((requestId
== 0) || (requestId
== HOTT_BINARY_MODE_REQUEST_ID
) || (address
== HOTT_TELEMETRY_NO_SENSOR_ID
)) {
621 * FIXME the first byte of the HoTT request frame is ONLY either 0x80 (binary mode) or 0x7F (text mode).
622 * The binary mode is read as 0x00 (error reading the upper bit) while the text mode is correctly decoded.
623 * The (requestId == 0) test is a workaround for detecting the binary mode with no ambiguity as there is only
624 * one other valid value (0x7F) for text mode.
625 * The error reading for the upper bit should nevertheless be fixed
627 processBinaryModeRequest(address
);
629 #if defined (USE_HOTT_TEXTMODE) && defined (USE_CMS)
630 else if (requestId
== HOTTV4_TEXT_MODE_REQUEST_ID
) {
631 processHottTextModeRequest(address
);
636 static void hottSendTelemetryData(void) {
638 if (!hottIsSending
) {
639 hottConfigurePortForTX();
643 if (hottMsgRemainingBytesToSendCount
== 0) {
644 hottConfigurePortForRX();
648 --hottMsgRemainingBytesToSendCount
;
649 if (hottMsgRemainingBytesToSendCount
== 0) {
650 hottSerialWrite(hottMsgCrc
++);
654 hottMsgCrc
+= *hottMsg
;
655 hottSerialWrite(*hottMsg
++);
658 static inline bool shouldPrepareHoTTMessages(uint32_t currentMicros
)
660 return currentMicros
- lastMessagesPreparedAt
>= HOTT_MESSAGE_PREPARATION_FREQUENCY_5_HZ
;
663 static inline bool shouldCheckForHoTTRequest(void)
671 void checkHoTTTelemetryState(void)
673 const bool newTelemetryEnabledValue
= telemetryDetermineEnabledState(hottPortSharing
);
675 if (newTelemetryEnabledValue
== hottTelemetryEnabled
) {
679 if (newTelemetryEnabledValue
) {
680 configureHoTTTelemetryPort();
682 freeHoTTTelemetryPort();
686 void handleHoTTTelemetry(timeUs_t currentTimeUs
)
688 static timeUs_t serialTimer
;
690 if (!hottTelemetryEnabled
) {
694 if (shouldPrepareHoTTMessages(currentTimeUs
)) {
695 hottPrepareMessages();
696 lastMessagesPreparedAt
= currentTimeUs
;
699 if (shouldCheckForHoTTRequest()) {
700 hottCheckSerialData(currentTimeUs
);
707 if (currentTimeUs
- serialTimer
< txDelayUs
) {
711 hottSendTelemetryData();
712 serialTimer
= currentTimeUs
;