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 * There is a technical discussion (in German) about HoTT here
54 * http://www.rc-network.de/forum/showthread.php/281496-Graupner-HoTT-Telemetrie-Sensoren-Eigenbau-DIY-Telemetrie-Protokoll-entschl%C3%BCsselt/page21
63 #ifdef USE_TELEMETRY_HOTT
65 #include "build/build_config.h"
66 #include "build/debug.h"
68 #include "common/axis.h"
69 #include "common/maths.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/position.h"
78 #include "flight/pid.h"
82 #include "sensors/battery.h"
83 #include "sensors/barometer.h"
84 #include "sensors/sensors.h"
86 #include "telemetry/hott.h"
87 #include "telemetry/telemetry.h"
89 #if defined(USE_HOTT_TEXTMODE) && defined(USE_CMS)
90 #include "scheduler/scheduler.h"
91 #include "io/displayport_hott.h"
93 #define HOTT_TEXTMODE_TASK_PERIOD 1000
94 #define HOTT_TEXTMODE_RX_SCHEDULE 5000
95 #define HOTT_TEXTMODE_TX_DELAY_US 1000
100 #define HOTT_MESSAGE_PREPARATION_FREQUENCY_5_HZ ((1000 * 1000) / 5)
101 #define HOTT_RX_SCHEDULE 4000
102 #define HOTT_TX_DELAY_US 3000
103 #define MILLISECONDS_IN_A_SECOND 1000
105 static uint32_t rxSchedule
= HOTT_RX_SCHEDULE
;
106 static uint32_t txDelayUs
= HOTT_TX_DELAY_US
;
108 static uint32_t lastHoTTRequestCheckAt
= 0;
109 static uint32_t lastMessagesPreparedAt
= 0;
110 static uint32_t lastHottAlarmSoundTime
= 0;
112 static bool hottIsSending
= false;
114 static uint8_t *hottMsg
= NULL
;
115 static uint8_t hottMsgRemainingBytesToSendCount
;
116 static uint8_t hottMsgCrc
;
118 #define HOTT_CRC_SIZE (sizeof(hottMsgCrc))
120 #define HOTT_BAUDRATE 19200
121 #define HOTT_PORT_MODE MODE_RXTX // must be opened in RXTX so that TX and RX pins are allocated.
123 static serialPort_t
*hottPort
= NULL
;
124 static const serialPortConfig_t
*portConfig
;
126 static bool hottTelemetryEnabled
= false;
127 static portSharing_e hottPortSharing
;
129 static HOTT_GPS_MSG_t hottGPSMessage
;
130 static HOTT_EAM_MSG_t hottEAMMessage
;
132 #if defined(USE_HOTT_TEXTMODE) && defined(USE_CMS)
133 static hottTextModeMsg_t hottTextModeMessage
;
134 static bool textmodeIsAlive
= false;
135 static int32_t telemetryTaskPeriod
= 0;
137 static void initialiseTextmodeMessage(hottTextModeMsg_t
*msg
)
139 msg
->start
= HOTT_TEXTMODE_START
;
140 msg
->esc
= HOTT_EAM_SENSOR_TEXT_ID
;
142 msg
->stop
= HOTT_TEXTMODE_STOP
;
146 static void initialiseEAMMessage(HOTT_EAM_MSG_t
*msg
, size_t size
)
148 memset(msg
, 0, size
);
149 msg
->start_byte
= 0x7C;
150 msg
->eam_sensor_id
= HOTT_TELEMETRY_EAM_SENSOR_ID
;
151 msg
->sensor_id
= HOTT_EAM_SENSOR_TEXT_ID
;
152 msg
->stop_byte
= 0x7D;
157 GPS_FIX_CHAR_NONE
= '-',
158 GPS_FIX_CHAR_2D
= '2',
159 GPS_FIX_CHAR_3D
= '3',
160 GPS_FIX_CHAR_DGPS
= 'D'
163 static void initialiseGPSMessage(HOTT_GPS_MSG_t
*msg
, size_t size
)
165 memset(msg
, 0, size
);
166 msg
->start_byte
= 0x7C;
167 msg
->gps_sensor_id
= HOTT_TELEMETRY_GPS_SENSOR_ID
;
168 msg
->sensor_id
= HOTT_GPS_SENSOR_TEXT_ID
;
169 msg
->stop_byte
= 0x7D;
173 static void initialiseMessages(void)
175 initialiseEAMMessage(&hottEAMMessage
, sizeof(hottEAMMessage
));
177 initialiseGPSMessage(&hottGPSMessage
, sizeof(hottGPSMessage
));
179 #if defined(USE_HOTT_TEXTMODE) && defined(USE_CMS)
180 initialiseTextmodeMessage(&hottTextModeMessage
);
185 void addGPSCoordinates(HOTT_GPS_MSG_t
*hottGPSMessage
, int32_t latitude
, int32_t longitude
)
187 int16_t deg
= latitude
/ GPS_DEGREES_DIVIDER
;
188 int32_t sec
= (latitude
- (deg
* GPS_DEGREES_DIVIDER
)) * 6;
189 int8_t min
= sec
/ 1000000L;
190 sec
= (sec
% 1000000L) / 100L;
191 uint16_t degMin
= (deg
* 100L) + min
;
193 hottGPSMessage
->pos_NS
= (latitude
< 0);
194 hottGPSMessage
->pos_NS_dm_L
= degMin
;
195 hottGPSMessage
->pos_NS_dm_H
= degMin
>> 8;
196 hottGPSMessage
->pos_NS_sec_L
= sec
;
197 hottGPSMessage
->pos_NS_sec_H
= sec
>> 8;
199 deg
= longitude
/ GPS_DEGREES_DIVIDER
;
200 sec
= (longitude
- (deg
* GPS_DEGREES_DIVIDER
)) * 6;
201 min
= sec
/ 1000000L;
202 sec
= (sec
% 1000000L) / 100L;
203 degMin
= (deg
* 100L) + min
;
205 hottGPSMessage
->pos_EW
= (longitude
< 0);
206 hottGPSMessage
->pos_EW_dm_L
= degMin
;
207 hottGPSMessage
->pos_EW_dm_H
= degMin
>> 8;
208 hottGPSMessage
->pos_EW_sec_L
= sec
;
209 hottGPSMessage
->pos_EW_sec_H
= sec
>> 8;
212 void hottPrepareGPSResponse(HOTT_GPS_MSG_t
*hottGPSMessage
)
214 hottGPSMessage
->gps_satelites
= gpsSol
.numSat
;
216 if (!STATE(GPS_FIX
)) {
217 hottGPSMessage
->gps_fix_char
= GPS_FIX_CHAR_NONE
;
221 if (gpsSol
.numSat
>= GPS_MIN_SAT_COUNT
) {
222 hottGPSMessage
->gps_fix_char
= GPS_FIX_CHAR_3D
;
224 hottGPSMessage
->gps_fix_char
= GPS_FIX_CHAR_2D
;
227 addGPSCoordinates(hottGPSMessage
, gpsSol
.llh
.lat
, gpsSol
.llh
.lon
);
229 // GPS Speed is returned in cm/s (from io/gps.c) and must be sent in km/h (Hott requirement)
230 const uint16_t speed
= (gpsSol
.groundSpeed
* 36) / 1000;
231 hottGPSMessage
->gps_speed_L
= speed
& 0x00FF;
232 hottGPSMessage
->gps_speed_H
= speed
>> 8;
234 hottGPSMessage
->home_distance_L
= GPS_distanceToHome
& 0x00FF;
235 hottGPSMessage
->home_distance_H
= GPS_distanceToHome
>> 8;
237 int32_t altitudeM
= getEstimatedAltitudeCm() / 100;
239 const uint16_t hottGpsAltitude
= constrain(altitudeM
+ HOTT_GPS_ALTITUDE_OFFSET
, 0 , UINT16_MAX
); // gpsSol.llh.alt in m ; offset = 500 -> O m
241 hottGPSMessage
->altitude_L
= hottGpsAltitude
& 0x00FF;
242 hottGPSMessage
->altitude_H
= hottGpsAltitude
>> 8;
244 hottGPSMessage
->home_direction
= GPS_directionToHome
/ 10;
248 static bool shouldTriggerBatteryAlarmNow(void)
250 return ((millis() - lastHottAlarmSoundTime
) >= (telemetryConfig()->hottAlarmSoundInterval
* MILLISECONDS_IN_A_SECOND
));
253 static inline void updateAlarmBatteryStatus(HOTT_EAM_MSG_t
*hottEAMMessage
)
255 if (shouldTriggerBatteryAlarmNow()) {
256 lastHottAlarmSoundTime
= millis();
257 const batteryState_e voltageState
= getVoltageState();
258 const batteryState_e consumptionState
= getConsumptionState();
259 if (voltageState
== BATTERY_WARNING
|| voltageState
== BATTERY_CRITICAL
) {
260 hottEAMMessage
->warning_beeps
= 0x10;
261 hottEAMMessage
->alarm_invers1
= HOTT_EAM_ALARM1_FLAG_BATTERY_1
;
262 } else if (consumptionState
== BATTERY_WARNING
|| consumptionState
== BATTERY_CRITICAL
) {
263 hottEAMMessage
->warning_beeps
= 0x16;
264 hottEAMMessage
->alarm_invers1
= HOTT_EAM_ALARM1_FLAG_MAH
;
266 hottEAMMessage
->warning_beeps
= HOTT_EAM_ALARM1_FLAG_NONE
;
267 hottEAMMessage
->alarm_invers1
= HOTT_EAM_ALARM1_FLAG_NONE
;
272 static inline void hottEAMUpdateBattery(HOTT_EAM_MSG_t
*hottEAMMessage
)
274 const uint16_t volt
= getLegacyBatteryVoltage();
275 hottEAMMessage
->main_voltage_L
= volt
& 0xFF;
276 hottEAMMessage
->main_voltage_H
= volt
>> 8;
277 hottEAMMessage
->batt1_voltage_L
= volt
& 0xFF;
278 hottEAMMessage
->batt1_voltage_H
= volt
>> 8;
280 updateAlarmBatteryStatus(hottEAMMessage
);
283 static inline void hottEAMUpdateCurrentMeter(HOTT_EAM_MSG_t
*hottEAMMessage
)
285 const int32_t amp
= getAmperage() / 10;
286 hottEAMMessage
->current_L
= amp
& 0xFF;
287 hottEAMMessage
->current_H
= amp
>> 8;
290 static inline void hottEAMUpdateBatteryDrawnCapacity(HOTT_EAM_MSG_t
*hottEAMMessage
)
292 const int32_t mAh
= getMAhDrawn() / 10;
293 hottEAMMessage
->batt_cap_L
= mAh
& 0xFF;
294 hottEAMMessage
->batt_cap_H
= mAh
>> 8;
297 static inline void hottEAMUpdateAltitude(HOTT_EAM_MSG_t
*hottEAMMessage
)
299 const uint16_t hottEamAltitude
= (getEstimatedAltitudeCm() / 100) + HOTT_EAM_OFFSET_HEIGHT
;
301 hottEAMMessage
->altitude_L
= hottEamAltitude
& 0x00FF;
302 hottEAMMessage
->altitude_H
= hottEamAltitude
>> 8;
306 static inline void hottEAMUpdateClimbrate(HOTT_EAM_MSG_t
*hottEAMMessage
)
308 const int32_t vario
= getEstimatedVario();
309 hottEAMMessage
->climbrate_L
= (30000 + vario
) & 0x00FF;
310 hottEAMMessage
->climbrate_H
= (30000 + vario
) >> 8;
311 hottEAMMessage
->climbrate3s
= 120 + (vario
/ 100);
315 void hottPrepareEAMResponse(HOTT_EAM_MSG_t
*hottEAMMessage
)
318 hottEAMMessage
->warning_beeps
= 0x0;
319 hottEAMMessage
->alarm_invers1
= 0x0;
321 hottEAMUpdateBattery(hottEAMMessage
);
322 hottEAMUpdateCurrentMeter(hottEAMMessage
);
323 hottEAMUpdateBatteryDrawnCapacity(hottEAMMessage
);
324 hottEAMUpdateAltitude(hottEAMMessage
);
326 hottEAMUpdateClimbrate(hottEAMMessage
);
330 static void hottSerialWrite(uint8_t c
)
332 static uint8_t serialWrites
= 0;
334 serialWrite(hottPort
, c
);
337 void freeHoTTTelemetryPort(void)
339 closeSerialPort(hottPort
);
341 hottTelemetryEnabled
= false;
344 void initHoTTTelemetry(void)
346 portConfig
= findSerialPortConfig(FUNCTION_TELEMETRY_HOTT
);
352 hottPortSharing
= determinePortSharing(portConfig
, FUNCTION_TELEMETRY_HOTT
);
354 #if defined(USE_HOTT_TEXTMODE) && defined(USE_CMS)
355 hottDisplayportRegister();
358 initialiseMessages();
361 static void flushHottRxBuffer(void)
363 while (serialRxBytesWaiting(hottPort
) > 0) {
364 serialRead(hottPort
);
368 static void workAroundForHottTelemetryOnUsart(serialPort_t
*instance
, portMode_e mode
)
370 closeSerialPort(hottPort
);
372 portOptions_e portOptions
= telemetryConfig()->telemetry_inverted
? SERIAL_INVERTED
: SERIAL_NOT_INVERTED
;
374 if (telemetryConfig()->halfDuplex
) {
375 portOptions
|= SERIAL_BIDIR
;
378 hottPort
= openSerialPort(instance
->identifier
, FUNCTION_TELEMETRY_HOTT
, NULL
, NULL
, HOTT_BAUDRATE
, mode
, portOptions
);
381 static bool hottIsUsingHardwareUART(void)
383 return !(portConfig
->identifier
== SERIAL_PORT_SOFTSERIAL1
|| portConfig
->identifier
== SERIAL_PORT_SOFTSERIAL2
);
386 static void hottConfigurePortForTX(void)
388 // FIXME temorary workaround for HoTT not working on Hardware serial ports due to hardware/softserial serial port initialisation differences
389 if (hottIsUsingHardwareUART()) {
390 workAroundForHottTelemetryOnUsart(hottPort
, MODE_TX
);
392 serialSetMode(hottPort
, MODE_TX
);
394 hottIsSending
= true;
398 static void hottConfigurePortForRX(void)
400 // FIXME temorary workaround for HoTT not working on Hardware serial ports due to hardware/softserial serial port initialisation differences
401 if (hottIsUsingHardwareUART()) {
402 workAroundForHottTelemetryOnUsart(hottPort
, MODE_RX
);
404 serialSetMode(hottPort
, MODE_RX
);
407 hottIsSending
= false;
411 void configureHoTTTelemetryPort(void)
417 portOptions_e portOptions
= SERIAL_NOT_INVERTED
;
419 if (telemetryConfig()->halfDuplex
) {
420 portOptions
|= SERIAL_BIDIR
;
423 hottPort
= openSerialPort(portConfig
->identifier
, FUNCTION_TELEMETRY_HOTT
, NULL
, NULL
, HOTT_BAUDRATE
, HOTT_PORT_MODE
, portOptions
);
429 hottConfigurePortForRX();
431 hottTelemetryEnabled
= true;
434 static void hottSendResponse(uint8_t *buffer
, int length
)
441 hottMsgRemainingBytesToSendCount
= length
+ HOTT_CRC_SIZE
;
444 static inline void hottSendGPSResponse(void)
446 hottSendResponse((uint8_t *)&hottGPSMessage
, sizeof(hottGPSMessage
));
449 static inline void hottSendEAMResponse(void)
451 hottSendResponse((uint8_t *)&hottEAMMessage
, sizeof(hottEAMMessage
));
454 static void hottPrepareMessages(void)
456 hottPrepareEAMResponse(&hottEAMMessage
);
458 hottPrepareGPSResponse(&hottGPSMessage
);
462 #if defined(USE_HOTT_TEXTMODE) && defined(USE_CMS)
463 static void hottTextmodeStart(void)
465 // Increase menu speed
467 getTaskInfo(TASK_TELEMETRY
, &taskInfo
);
468 telemetryTaskPeriod
= taskInfo
.desiredPeriodUs
;
469 rescheduleTask(TASK_TELEMETRY
, TASK_PERIOD_HZ(HOTT_TEXTMODE_TASK_PERIOD
));
471 rxSchedule
= HOTT_TEXTMODE_RX_SCHEDULE
;
472 txDelayUs
= HOTT_TEXTMODE_TX_DELAY_US
;
475 static void hottTextmodeStop(void)
477 // Set back to avoid slow down of the FC
478 if (telemetryTaskPeriod
> 0) {
479 rescheduleTask(TASK_TELEMETRY
, telemetryTaskPeriod
);
480 telemetryTaskPeriod
= 0;
483 rxSchedule
= HOTT_RX_SCHEDULE
;
484 txDelayUs
= HOTT_TX_DELAY_US
;
487 bool hottTextmodeIsAlive(void)
489 return textmodeIsAlive
;
492 void hottTextmodeGrab(void)
494 hottTextModeMessage
.esc
= HOTT_EAM_SENSOR_TEXT_ID
;
497 void hottTextmodeExit(void)
499 hottTextModeMessage
.esc
= HOTT_TEXTMODE_ESC
;
502 void hottTextmodeWriteChar(uint8_t column
, uint8_t row
, char c
)
504 if (column
< HOTT_TEXTMODE_DISPLAY_COLUMNS
&& row
< HOTT_TEXTMODE_DISPLAY_ROWS
) {
505 if (hottTextModeMessage
.txt
[row
][column
] != c
)
506 hottTextModeMessage
.txt
[row
][column
] = c
;
510 static void processHottTextModeRequest(const uint8_t cmd
)
512 static bool setEscBack
= false;
514 if (!textmodeIsAlive
) {
516 textmodeIsAlive
= true;
519 if ((cmd
& 0xF0) != HOTT_EAM_SENSOR_TEXT_ID
) {
524 hottTextModeMessage
.esc
= HOTT_EAM_SENSOR_TEXT_ID
;
528 if (hottTextModeMessage
.esc
!= HOTT_TEXTMODE_ESC
) {
534 hottSetCmsKey(cmd
& 0x0f, hottTextModeMessage
.esc
== HOTT_TEXTMODE_ESC
);
535 hottSendResponse((uint8_t *)&hottTextModeMessage
, sizeof(hottTextModeMessage
));
539 static void processBinaryModeRequest(uint8_t address
)
541 #if defined(USE_HOTT_TEXTMODE) && defined(USE_CMS)
542 if (textmodeIsAlive
) {
544 textmodeIsAlive
= false;
549 static uint8_t hottBinaryRequests
= 0;
550 static uint8_t hottGPSRequests
= 0;
551 static uint8_t hottEAMRequests
= 0;
560 if (sensors(SENSOR_GPS
)) {
561 hottSendGPSResponse();
569 hottSendEAMResponse();
574 hottBinaryRequests
++;
575 debug
[0] = hottBinaryRequests
;
577 debug
[1] = hottGPSRequests
;
579 debug
[2] = hottEAMRequests
;
583 static void hottCheckSerialData(uint32_t currentMicros
)
585 static bool lookingForRequest
= true;
587 const uint8_t bytesWaiting
= serialRxBytesWaiting(hottPort
);
589 if (bytesWaiting
<= 1) {
593 if (bytesWaiting
!= 2) {
595 lookingForRequest
= true;
599 if (lookingForRequest
) {
600 lastHoTTRequestCheckAt
= currentMicros
;
601 lookingForRequest
= false;
604 bool enoughTimePassed
= currentMicros
- lastHoTTRequestCheckAt
>= rxSchedule
;
606 if (!enoughTimePassed
) {
609 lookingForRequest
= true;
612 const uint8_t requestId
= serialRead(hottPort
);
613 const uint8_t address
= serialRead(hottPort
);
615 if ((requestId
== 0) || (requestId
== HOTT_BINARY_MODE_REQUEST_ID
) || (address
== HOTT_TELEMETRY_NO_SENSOR_ID
)) {
617 * FIXME the first byte of the HoTT request frame is ONLY either 0x80 (binary mode) or 0x7F (text mode).
618 * The binary mode is read as 0x00 (error reading the upper bit) while the text mode is correctly decoded.
619 * The (requestId == 0) test is a workaround for detecting the binary mode with no ambiguity as there is only
620 * one other valid value (0x7F) for text mode.
621 * The error reading for the upper bit should nevertheless be fixed
623 processBinaryModeRequest(address
);
625 #if defined(USE_HOTT_TEXTMODE) && defined(USE_CMS)
626 else if (requestId
== HOTTV4_TEXT_MODE_REQUEST_ID
) {
627 processHottTextModeRequest(address
);
632 static void hottSendTelemetryData(void)
635 if (!hottIsSending
) {
636 hottConfigurePortForTX();
640 if (hottMsgRemainingBytesToSendCount
== 0) {
641 hottConfigurePortForRX();
645 --hottMsgRemainingBytesToSendCount
;
646 if (hottMsgRemainingBytesToSendCount
== 0) {
647 hottSerialWrite(hottMsgCrc
++);
651 hottMsgCrc
+= *hottMsg
;
652 hottSerialWrite(*hottMsg
++);
655 static inline bool shouldPrepareHoTTMessages(uint32_t currentMicros
)
657 return currentMicros
- lastMessagesPreparedAt
>= HOTT_MESSAGE_PREPARATION_FREQUENCY_5_HZ
;
660 static inline bool shouldCheckForHoTTRequest(void)
668 void checkHoTTTelemetryState(void)
670 const bool newTelemetryEnabledValue
= telemetryDetermineEnabledState(hottPortSharing
);
672 if (newTelemetryEnabledValue
== hottTelemetryEnabled
) {
676 if (newTelemetryEnabledValue
) {
677 configureHoTTTelemetryPort();
679 freeHoTTTelemetryPort();
683 void handleHoTTTelemetry(timeUs_t currentTimeUs
)
685 static timeUs_t serialTimer
;
687 if (!hottTelemetryEnabled
) {
691 if (shouldPrepareHoTTMessages(currentTimeUs
)) {
692 hottPrepareMessages();
693 lastMessagesPreparedAt
= currentTimeUs
;
696 if (shouldCheckForHoTTRequest()) {
697 hottCheckSerialData(currentTimeUs
);
704 if (currentTimeUs
- serialTimer
< txDelayUs
) {
708 hottSendTelemetryData();
709 serialTimer
= currentTimeUs
;