1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-24 16:55:36 +03:00

HoTT update.

There's a number of changes in this commit, all related.

Improved efficiency of preparing HoTT messages.

All HoTT message data is no-longer reset each time, going forward old
data is re-used unless it is updated.  This should help with GPS
co-ordinates too since they were erased from subsequent responses when
ideally the last-known co-ordinates should be transmitted each time.

The previous update was sending one too many bytes due to the
aligned/padded uint16_t values in the HoTT data structures.  There were
two solutions, use #pragma to pack the structure or avoid larger types
in the structures, the latter made sense and results in more portable
code since it's a wire format.

Updated HoTT structures to use latest message structure from Ardupilot.
Currently the variables are in underscore_format, that will likely
change in future.

Cleaned up and deleted old ported code that was #ifdef'd out.  Some test
code still remains for now.  This will be deleted in due course.

Introduced bitmask for EAM alarm flags.

Corrected documentation.
This commit is contained in:
Dominic Clifton 2014-05-22 17:25:51 +01:00
parent 02a8e993f5
commit b37bace5c1
6 changed files with 534 additions and 266 deletions

View file

@ -57,6 +57,14 @@ void initTelemetry()
telemetryPortIsShared = isSerialPortFunctionShared(FUNCTION_TELEMETRY, FUNCTION_MSP);
isTelemetryConfigurationValid = canUseTelemetryWithCurrentConfiguration();
if (isTelemetryProviderFrSky()) {
initFrSkyTelemetry(telemetryConfig);
}
if (isTelemetryProviderHoTT()) {
initHoTTTelemetry(telemetryConfig);
}
checkTelemetryState();
}
@ -94,11 +102,11 @@ uint32_t getTelemetryProviderBaudRate(void)
static void configureTelemetryPort(void)
{
if (isTelemetryProviderFrSky()) {
configureFrSkyTelemetryPort(telemetryConfig);
configureFrSkyTelemetryPort();
}
if (isTelemetryProviderHoTT()) {
configureHoTTTelemetryPort(telemetryConfig);
configureHoTTTelemetryPort();
}
}

View file

@ -34,7 +34,7 @@ static serialPort_t *frskyPort;
#define FRSKY_BAUDRATE 9600
#define FRSKY_INITIAL_PORT_MODE MODE_TX
telemetryConfig_t *telemetryConfig;
static telemetryConfig_t *telemetryConfig;
extern int16_t telemTemperature1; // FIXME dependency on mw.c
@ -243,6 +243,11 @@ static void sendHeading(void)
serialize16(0);
}
void initFrSkyTelemetry(telemetryConfig_t *initialTelemetryConfig)
{
telemetryConfig = initialTelemetryConfig;
}
static portMode_t previousPortMode;
static uint32_t previousBaudRate;
@ -255,7 +260,7 @@ void freeFrSkyTelemetryPort(void)
endSerialPortFunction(frskyPort, FUNCTION_TELEMETRY);
}
void configureFrSkyTelemetryPort(telemetryConfig_t *telemetryConfig)
void configureFrSkyTelemetryPort(void)
{
frskyPort = findOpenSerialPort(FUNCTION_TELEMETRY);
if (frskyPort) {

View file

@ -11,7 +11,8 @@
void handleFrSkyTelemetry(void);
void checkFrSkyTelemetryState(void);
void configureFrSkyTelemetryPort(telemetryConfig_t *telemetryConfig);
void initFrSkyTelemetry(telemetryConfig_t *telemetryConfig);
void configureFrSkyTelemetryPort(void);
void freeFrSkyTelemetryPort(void);
uint32_t getFrSkyTelemetryProviderBaudRate(void);

View file

@ -69,91 +69,102 @@ static serialPort_t *hottPort;
#define HOTT_BAUDRATE 19200
#define HOTT_INITIAL_PORT_MODE MODE_RX
extern telemetryConfig_t *telemetryConfig;
static telemetryConfig_t *telemetryConfig;
const uint8_t kHoTTv4BinaryPacketSize = 45;
const uint8_t kHoTTv4TextPacketSize = 173;
static HoTTV4GPSModule_t HoTTV4GPSModule;
static HoTTV4ElectricAirModule_t HoTTV4ElectricAirModule;
static HOTT_GPS_MSG_t HoTTV4GPSModule;
static HOTT_EAM_MSG_t HoTTV4ElectricAirModule;
static void hottV4SerialWrite(uint8_t c);
static void hottV4GPSUpdate(void);
static void hottV4EAMUpdateBattery(void);
static void hottV4EAMUpdateTemperatures(void);
bool batteryWarning;
void initialiseEAMMessage(HOTT_EAM_MSG_t *msg, size_t size)
{
memset(msg, 0, size);
msg->start_byte = 0x7C;
msg->eam_sensor_id = HOTT_TELEMETRY_EAM_SENSOR_ID;
msg->sensor_id = HOTT_EAM_SENSOR_TEXT_ID;
msg->stop_byte = 0x7D;
}
void initialiseGPSMessage(HOTT_GPS_MSG_t *msg, size_t size)
{
memset(msg, 0, size);
msg->start_byte = 0x7C;
msg->gps_sensor_id = HOTT_TELEMETRY_GPS_SENSOR_ID;
msg->sensor_id = HOTT_GPS_SENSOR_TEXT_ID;
msg->stop_byte = 0x7D;
}
void initialiseMessages(void)
{
initialiseEAMMessage(&HoTTV4ElectricAirModule, sizeof(HoTTV4ElectricAirModule));
initialiseGPSMessage(&HoTTV4GPSModule, sizeof(HoTTV4GPSModule));
}
typedef enum {
GPS_FIX_CHAR_NONE = '-',
GPS_FIX_CHAR_2D = '2',
GPS_FIX_CHAR_3D = '3',
GPS_FIX_CHAR_DGPS = 'D',
} gpsFixChar_e;
/*
* Sends HoTTv4 capable GPS telemetry frame.
*/
void hottV4FormatGPSResponse(void)
{
memset(&HoTTV4GPSModule, 0, sizeof(HoTTV4GPSModule));
// Minimum data set for EAM
HoTTV4GPSModule.startByte = 0x7C;
HoTTV4GPSModule.sensorID = HOTTV4_GPS_SENSOR_ID;
HoTTV4GPSModule.sensorTextID = HOTTV4_GPS_SENSOR_TEXT_ID;
HoTTV4GPSModule.endByte = 0x7D;
// Reset alarms
HoTTV4GPSModule.alarmTone = 0x0;
HoTTV4GPSModule.alarmInverse1 = 0x0;
hottV4GPSUpdate();
}
void hottV4GPSUpdate(void)
{
// Number of Satelites
HoTTV4GPSModule.GPSNumSat = GPS_numSat;
if (f.GPS_FIX > 0) {
HoTTV4GPSModule.gps_satelites = GPS_numSat;
if (f.GPS_FIX) {
// GPS fix
HoTTV4GPSModule.GPS_fix = 0x66; // Displays a 'f' for fix
if (GPS_numSat >= 5) {
HoTTV4GPSModule.gps_fix_char = GPS_FIX_CHAR_3D;
} else {
HoTTV4GPSModule.gps_fix_char = GPS_FIX_CHAR_2D;
}
// latitude
HoTTV4GPSModule.LatitudeNS = (GPS_coord[LAT] < 0);
HoTTV4GPSModule.pos_NS = (GPS_coord[LAT] < 0);
uint8_t deg = GPS_coord[LAT] / 100000;
uint32_t sec = (GPS_coord[LAT] - (deg * 100000)) * 6;
uint8_t min = sec / 10000;
sec = sec % 10000;
uint16_t degMin = (deg * 100) + min;
HoTTV4GPSModule.LatitudeMinLow = degMin;
HoTTV4GPSModule.LatitudeMinHigh = degMin >> 8;
HoTTV4GPSModule.LatitudeSecLow = sec;
HoTTV4GPSModule.LatitudeSecHigh = sec >> 8;
HoTTV4GPSModule.pos_NS_dm_L = degMin;
HoTTV4GPSModule.pos_NS_dm_H = degMin >> 8;
HoTTV4GPSModule.pos_NS_sec_L = sec;
HoTTV4GPSModule.pos_NS_sec_H = sec >> 8;
// longitude
HoTTV4GPSModule.longitudeEW = (GPS_coord[LON] < 0);
HoTTV4GPSModule.pos_EW = (GPS_coord[LON] < 0);
deg = GPS_coord[LON] / 100000;
sec = (GPS_coord[LON] - (deg * 100000)) * 6;
min = sec / 10000;
sec = sec % 10000;
degMin = (deg * 100) + min;
HoTTV4GPSModule.longitudeMinLow = degMin;
HoTTV4GPSModule.longitudeMinHigh = degMin >> 8;
HoTTV4GPSModule.longitudeSecLow = sec;
HoTTV4GPSModule.longitudeSecHigh = sec >> 8;
HoTTV4GPSModule.pos_EW_dm_L = degMin;
HoTTV4GPSModule.pos_EW_dm_H = degMin >> 8;
HoTTV4GPSModule.pos_EW_sec_L = sec;
HoTTV4GPSModule.pos_EW_sec_H = sec >> 8;
// GPS Speed in km/h
uint16_t speed = (GPS_speed / 100) * 36; // 0.1m/s * 0.36 = km/h
HoTTV4GPSModule.GPSSpeedLow = speed & 0x00FF;
HoTTV4GPSModule.GPSSpeedHigh = speed >> 8;
HoTTV4GPSModule.gps_speed_L = speed & 0x00FF;
HoTTV4GPSModule.gps_speed_H = speed >> 8;
// Distance to home
HoTTV4GPSModule.distanceLow = GPS_distanceToHome & 0x00FF;
HoTTV4GPSModule.distanceHigh = GPS_distanceToHome >> 8;
HoTTV4GPSModule.home_distance_L = GPS_distanceToHome & 0x00FF;
HoTTV4GPSModule.home_distance_H = GPS_distanceToHome >> 8;
// Altitude
HoTTV4GPSModule.altitudeLow = GPS_altitude & 0x00FF;
HoTTV4GPSModule.altitudeHigh = GPS_altitude >> 8;
HoTTV4GPSModule.altitude_L = GPS_altitude & 0x00FF;
HoTTV4GPSModule.altitude_H = GPS_altitude >> 8;
// Direction to home
HoTTV4GPSModule.HomeDirection = GPS_directionToHome;
HoTTV4GPSModule.home_direction = GPS_directionToHome;
} else {
HoTTV4GPSModule.GPS_fix = 0x20; // Displays a ' ' to show nothing or clear the old value
HoTTV4GPSModule.gps_fix_char = GPS_FIX_CHAR_NONE;
}
}
@ -167,52 +178,44 @@ static uint8_t updateCount = 0;
static void hottV4EAMUpdateBattery(void)
{
#ifdef HOTT_DEBUG_USE_EAM_TEST_DATA
HoTTV4ElectricAirModule.cell1L = 3.30f * 10 * 5; // 2mv step - 3.30v
HoTTV4ElectricAirModule.cell1H = 4.20f * 10 * 5; // 2mv step - 4.20v
HoTTV4ElectricAirModule.cell1_L = 3.30f * 10 * 5; // 2mv step - 3.30v
HoTTV4ElectricAirModule.cell1_H = 4.20f * 10 * 5; // 2mv step - 4.20v
HoTTV4ElectricAirModule.cell2L = 0;
HoTTV4ElectricAirModule.cell2H = 0;
HoTTV4ElectricAirModule.cell2_L = 0;
HoTTV4ElectricAirModule.cell2_H = 0;
HoTTV4ElectricAirModule.cell3L = 0;
HoTTV4ElectricAirModule.cell3H = 0;
HoTTV4ElectricAirModule.cell3_L = 0;
HoTTV4ElectricAirModule.cell3_H = 0;
HoTTV4ElectricAirModule.cell4L = 0;
HoTTV4ElectricAirModule.cell4H = 0;
HoTTV4ElectricAirModule.cell4_L = 0;
HoTTV4ElectricAirModule.cell4_H = 0;
uint16_t currentUsed = updateCount * 10;
HoTTV4ElectricAirModule.batt_cap_L = currentUsed & 0xFF;
HoTTV4ElectricAirModule.batt_cap_H = currentUsed >> 8;
#endif
HoTTV4ElectricAirModule.driveVoltageLow = vbat & 0xFF;
HoTTV4ElectricAirModule.driveVoltageHigh = vbat >> 8;
HoTTV4ElectricAirModule.battery1Low = vbat & 0xFF;
HoTTV4ElectricAirModule.battery1High = vbat >> 8;
HoTTV4ElectricAirModule.main_voltage_L = vbat & 0xFF;
HoTTV4ElectricAirModule.main_voltage_H = vbat >> 8;
HoTTV4ElectricAirModule.batt1_voltage_L = vbat & 0xFF;
HoTTV4ElectricAirModule.batt1_voltage_H = vbat >> 8;
#if 0
HoTTV4ElectricAirModule.battery2Low = 0 & 0xFF;
HoTTV4ElectricAirModule.battery2High = 0 >> 8;
if (batteryWarning) {
HoTTV4ElectricAirModule.alarmTone = HoTTv4NotificationUndervoltage;
HoTTV4ElectricAirModule.alarmInverse1 |= 0x80; // Invert Voltage display
}
#if 0 // TODO find other voltage via ADC?
HoTTV4ElectricAirModule.batt2_voltage_L = 0 & 0xFF;
HoTTV4ElectricAirModule.batt2_voltage_H = 0 >> 8;
#endif
#ifdef HOTT_DEBUG_SHOW_EAM_UPDATE_TOGGLE
if (updateCount & 1) {
HoTTV4ElectricAirModule.alarmInverse1 |= 0x80; // Invert Voltage display
HoTTV4ElectricAirModule.alarm_invers1 |= HOTT_EAM_ALARM1_FLAG_MAIN_VOLTAGE; // Invert Voltage display
}
#endif
}
static void hottV4EAMUpdateTemperatures(void)
{
HoTTV4ElectricAirModule.temp1 = 20 + 0;
HoTTV4ElectricAirModule.temp2 = 20;
#if 0
if (HoTTV4ElectricAirModule.temp1 >= (20 + MultiHoTTModuleSettings.alarmTemp1)) {
HoTTV4ElectricAirModule.alarmTone = HoTTv4NotificationMaxTemperature;
HoTTV4ElectricAirModule.alarmInverse |= 0x8; // Invert Temp1 display
}
#endif
HoTTV4ElectricAirModule.temp1 = HOTT_EAM_OFFSET_TEMPERATURE + 0;
HoTTV4ElectricAirModule.temp2 = HOTT_EAM_OFFSET_TEMPERATURE + 0;
}
@ -221,29 +224,18 @@ static void hottV4EAMUpdateTemperatures(void)
*/
void hottV4FormatEAMResponse(void)
{
memset(&HoTTV4ElectricAirModule, 0, sizeof(HoTTV4ElectricAirModule));
// Minimum data set for EAM
HoTTV4ElectricAirModule.startByte = 0x7C;
HoTTV4ElectricAirModule.sensorID = HOTTV4_ELECTRICAL_AIR_SENSOR_ID;
HoTTV4ElectricAirModule.sensorTextID = HOTTV4_ELECTRICAL_AIR_SENSOR_TEXT_ID;
HoTTV4ElectricAirModule.endByte = 0x7D;
// Reset alarms
HoTTV4ElectricAirModule.alarmTone = 0x0;
HoTTV4ElectricAirModule.alarmInverse1 = 0x0;
HoTTV4ElectricAirModule.warning_beeps = 0x0;
HoTTV4ElectricAirModule.alarm_invers1 = 0x0;
hottV4EAMUpdateBattery();
hottV4EAMUpdateTemperatures();
HoTTV4ElectricAirModule.current = 0 / 10;
HoTTV4ElectricAirModule.height = OFFSET_HEIGHT + 0;
HoTTV4ElectricAirModule.m2s = OFFSET_M2S;
HoTTV4ElectricAirModule.m3s = OFFSET_M3S;
}
static void hottV4SerialWrite(uint8_t c)
{
static uint8_t serialWrites = 0;
serialWrites++;
serialWrite(hottPort, c);
}
@ -259,7 +251,14 @@ void freeHoTTTelemetryPort(void)
endSerialPortFunction(hottPort, FUNCTION_TELEMETRY);
}
void configureHoTTTelemetryPort(telemetryConfig_t *telemetryConfig)
void initHoTTTelemetry(telemetryConfig_t *initialTelemetryConfig)
{
telemetryConfig = initialTelemetryConfig;
initialiseMessages();
}
void configureHoTTTelemetryPort(void)
{
hottPort = findOpenSerialPort(FUNCTION_TELEMETRY);
if (hottPort) {
@ -303,7 +302,7 @@ void hottV4SendResponse(uint8_t *buffer, int length)
}
hottMsg = buffer;
hottMsgRemainingBytesToSendCount = length;// + HOTT_CRC_SIZE;
hottMsgRemainingBytesToSendCount = length + HOTT_CRC_SIZE;
}
void hottV4SendGPSResponse(void)
@ -390,7 +389,7 @@ void hottCheckSerialData(uint32_t currentMicros) {
uint8_t requestId = serialRead(hottPort);
uint8_t address = serialRead(hottPort);
if (requestId == HOTTV4_BINARY_MODE_REQUEST_ID) {
if (requestId == HOTT_BINARY_MODE_REQUEST_ID) {
processBinaryModeRequest(address);
}
}

View file

@ -1,28 +1,20 @@
/*
* telemetry_hott.h
*
* Created on: 6 Apr 2014
* Author: Hydra
* Authors:
* Dominic Clifton/Hydra
* Carsten Giesen
* Adam Majerczyk (majerczyk.adam@gmail.com)
* Texmode add-on by Michi (mamaretti32@gmail.com)
*/
#ifndef TELEMETRY_HOTT_H_
#define TELEMETRY_HOTT_H_
/* HoTT module specifications */
#define HOTTV4_RXTX 4
#define HOTTV4_TEXT_MODE_REQUEST_ID 0x7f
#define HOTTV4_BINARY_MODE_REQUEST_ID 0x80
#define HOTTV4_GENERAL_AIR_SENSOR_ID 0xD0
#define HOTTV4_ELECTRICAL_AIR_SENSOR_ID 0x8E // Electric Air Sensor ID
#define HOTTV4_ELECTRICAL_AIR_SENSOR_TEXT_ID 0xE0 // Electric Air Module ID
#define HOTTV4_GPS_SENSOR_ID 0x8A // GPS Sensor ID
#define HOTTV4_GPS_SENSOR_TEXT_ID 0xA0 // GPS Module ID
#define HOTTV4_RXTX 4
#define HOTTV4_BUTTON_DEC 0xEB
#define HOTTV4_BUTTON_INC 0xED
#define HOTTV4_BUTTON_SET 0xE9
@ -30,194 +22,457 @@
#define HOTTV4_BUTTON_NEXT 0xEE
#define HOTTV4_BUTTON_PREV 0xE7
#define OFFSET_HEIGHT 500
#define OFFSET_M2S 72
#define OFFSET_M3S 120
#define HOTT_EAM_OFFSET_HEIGHT 500
#define HOTT_EAM_OFFSET_M2S 72
#define HOTT_EAM_OFFSET_M3S 120
#define HOTT_EAM_OFFSET_TEMPERATURE 20
typedef enum {
HoTTv4NotificationErrorCalibration = 0x01,
HoTTv4NotificationErrorReceiver = 0x02,
HoTTv4NotificationErrorDataBus = 0x03,
HoTTv4NotificationErrorNavigation = 0x04,
HoTTv4NotificationErrorError = 0x05,
HoTTv4NotificationErrorCompass = 0x06,
HoTTv4NotificationErrorSensor = 0x07,
HoTTv4NotificationErrorGPS = 0x08,
HoTTv4NotificationErrorMotor = 0x09,
HOTT_EAM_ALARM1_FLAG_NONE = 0,
HOTT_EAM_ALARM1_FLAG_MAH = (1 << 0),
HOTT_EAM_ALARM1_FLAG_BATTERY_1 = (1 << 1),
HOTT_EAM_ALARM1_FLAG_BATTERY_2 = (1 << 2),
HOTT_EAM_ALARM1_FLAG_TEMPERATURE_1 = (1 << 3),
HOTT_EAM_ALARM1_FLAG_TEMPERATURE_2 = (1 << 4),
HOTT_EAM_ALARM1_FLAG_ALTITUDE = (1 << 5),
HOTT_EAM_ALARM1_FLAG_CURRENT = (1 << 6),
HOTT_EAM_ALARM1_FLAG_MAIN_VOLTAGE = (1 << 7),
} hottEamAlarm1Flag_e;
HoTTv4NotificationMaxTemperature = 0x0A,
HoTTv4NotificationAltitudeReached = 0x0B,
HoTTv4NotificationWaypointReached = 0x0C,
HoTTv4NotificationNextWaypoint = 0x0D,
HoTTv4NotificationLanding = 0x0E,
HoTTv4NotificationGPSFix = 0x0F,
HoTTv4NotificationUndervoltage = 0x10,
HoTTv4NotificationGPSHold = 0x11,
HoTTv4NotificationGPSHome = 0x12,
HoTTv4NotificationGPSOff = 0x13,
HoTTv4NotificationBeep = 0x14,
HoTTv4NotificationMicrocopter = 0x15,
HoTTv4NotificationCapacity = 0x16,
HoTTv4NotificationCareFreeOff = 0x17,
HoTTv4NotificationCalibrating = 0x18,
HoTTv4NotificationMaxRange = 0x19,
HoTTv4NotificationMaxAltitude = 0x1A,
typedef enum {
HOTT_EAM_ALARM2_FLAG_NONE = 0,
HOTT_EAM_ALARM2_FLAG_MS = (1 << 0),
HOTT_EAM_ALARM2_FLAG_M3S = (1 << 1),
HOTT_EAM_ALARM2_FLAG_ALTITUDE_DUPLICATE = (1 << 2),
HOTT_EAM_ALARM2_FLAG_MS_DUPLICATE = (1 << 3),
HOTT_EAM_ALARM2_FLAG_M3S_DUPLICATE = (1 << 4),
HOTT_EAM_ALARM2_FLAG_UNKNOWN_1 = (1 << 5),
HOTT_EAM_ALARM2_FLAG_UNKNOWN_2 = (1 << 6),
HOTT_EAM_ALARM2_FLAG_ON_SIGN_OR_TEXT_ACTIVE = (1 << 7),
} hottEamAlarm2Flag_e;
HoTTv4Notification20Meter = 0x25,
HoTTv4NotificationMicrocopterOff = 0x26,
HoTTv4NotificationAltitudeOn = 0x27,
HoTTv4NotificationAltitudeOff = 0x28,
HoTTv4Notification100Meter = 0x29,
HoTTv4NotificationCareFreeOn = 0x2E,
HoTTv4NotificationDown = 0x2F,
HoTTv4NotificationUp = 0x30,
HoTTv4NotificationHold = 0x31,
HoTTv4NotificationGPSOn = 0x32,
HoTTv4NotificationFollowing = 0x33,
HoTTv4NotificationStarting = 0x34,
HoTTv4NotificationReceiver = 0x35,
} HoTTv4Notification;
/**
* GPS
* Receiver -> GPS Sensor (Flightcontrol)
* Byte 1: 0x80 = Receiver byte
* Byte 2: 0x8A = GPS Sensor byte (witch data Transmitter wants to get)
* 5ms Idle Line!
* 5ms delay
*/
//
// Messages
//
typedef struct HoTTV4GPSModule_s {
uint8_t startByte; // Byte 1: 0x7C = Start byte data
uint8_t sensorID; // Byte 2: 0x8A = GPS Sensor
uint8_t alarmTone; // Byte 3: 0…= warning beeps
uint8_t sensorTextID; // Byte 4: 160 0xA0 Sensor ID Neu!
uint8_t alarmInverse1; // Byte 5: 01 inverse status
uint8_t alarmInverse2; // Byte 6: 00 inverse status status 1 = no GPS signal
uint8_t flightDirection; // Byte 7: 119 = fly direction. 1 = 2°; 0° (North), 9 0° (East), 180° (South), 270° (West)
uint8_t GPSSpeedLow; // Byte 8: 8 = GPS speed low byte 8km/h
uint8_t GPSSpeedHigh; // Byte 9: 0 = GPS speed high byte
#define HOTT_TEXT_MODE_REQUEST_ID 0x7f
#define HOTT_BINARY_MODE_REQUEST_ID 0x80
//Sensor Ids
// Example: N 48°39'988"
uint8_t LatitudeNS; // Byte 10: 000 = N; 001 = S
// 0x12E7 = 4839 (48°30')
uint8_t LatitudeMinLow; // Byte 11: 231 = 0xE7
uint8_t LatitudeMinHigh; // Byte 12: 018 = 0x12
// 0x03DC = 0988 (988")
uint8_t LatitudeSecLow; // Byte 13: 220 = 0xDC
uint8_t LatitudeSecHigh; // Byte 14: 003 = 0x03
//Id 0x80 is used when no sensor has been found during the bus scan
// additionaly meaning?
#define HOTT_TELEMETRY_NO_SENSOR_ID 0x80
// Example: E 9°25'9360"
uint8_t longitudeEW; // Byte 15: 000 = E; 001 = W;
// 0x039D = 0925 (09°25')
uint8_t longitudeMinLow; // Byte 16: 157 = 0x9D
uint8_t longitudeMinHigh; // Byte 17: 003 = 0x03
// 0x2490 = 9360 (9360")
uint8_t longitudeSecLow; // Byte 18: 144 = 0x90
uint8_t longitudeSecHigh; // Byte 19: 036 = 0x24
//Graupner #33601 Vario Module
#define HOTT_TELEMETRY_VARIO_SENSOR_ID 0x89
uint8_t distanceLow; // Byte 20: distance low byte (meter)
uint8_t distanceHigh; // Byte 21: distance high byte
uint8_t altitudeLow; // Byte 22: Altitude low byte (meter)
uint8_t altitudeHigh; // Byte 23: Altitude high byte
uint8_t resolutionLow; // Byte 24: Low Byte m/s resolution 0.01m 48 = 30000 = 0.00m/s (1=0.01m/s)
uint8_t resolutionHigh; // Byte 25: High Byte m/s resolution 0.01m
//Graupner #33600 GPS Module
#define HOTT_TELEMETRY_GPS_SENSOR_ID 0x8a
uint8_t m3s; // Byte 26: 120 = 0m/3s
uint8_t GPSNumSat; // Byte 27: number of satelites (1 byte)
uint8_t GPSFixChar; // Byte 28: GPS.FixChar. (GPS fix character. display, if DGPS, 2D oder 3D) (1 byte)
uint8_t HomeDirection; // Byte 29: HomeDirection (direction from starting point to Model position) (1 byte)
uint8_t angleXdirection; // Byte 30: angle x-direction (1 byte)
uint8_t angleYdirection; // Byte 31: angle y-direction (1 byte)
uint8_t angleZdirection; // Byte 32: angle z-direction (1 byte)
//Graupner #337xx Air ESC
#define HOTT_TELEMETRY_AIRESC_SENSOR_ID 0x8c
uint8_t gyroXLow; // Byte 33: gyro x low byte (2 bytes)
uint8_t gyroXHigh; // Byte 34: gyro x high byte
uint8_t gyroYLow; // Byte 35: gyro y low byte (2 bytes)
uint8_t gyroYHigh; // Byte 36: gyro y high byte
uint8_t gyroZLow; // Byte 37: gyro z low byte (2 bytes)
uint8_t gyroZHigh; // Byte 38: gyro z high byte
//Graupner #33611 General Air Module
#define HOTT_TELEMETRY_GAM_SENSOR_ID 0x8d
uint8_t vibration; // Byte 39: vibration (1 bytes)
uint8_t Ascii4; // Byte 40: 00 ASCII Free Character [4]
uint8_t Ascii5; // Byte 41: 00 ASCII Free Character [5]
uint8_t GPS_fix; // Byte 42: 00 ASCII Free Character [6], we use it for GPS FIX
uint8_t version; // Byte 43: 00 version number
uint8_t endByte; // Byte 44: 0x7D End byte
} HoTTV4GPSModule_t;
//Graupner #33620 Electric Air Module
#define HOTT_TELEMETRY_EAM_SENSOR_ID 0x8e
/**
* EAM (Electric Air Module) 33620
* EmpfängerElectric Sensor
* Byte 1: 80 = Receiver byte
* Byte 2: 8E = Electric Sensor byte
* 5ms Idle Line!
*/
typedef struct HoTTV4ElectricAirModule_s {
uint8_t startByte;
#define HOTT_EAM_SENSOR_TEXT_ID 0xE0 // Electric Air Module ID
#define HOTT_GPS_SENSOR_TEXT_ID 0xA0 // GPS Module ID
uint8_t sensorID;
uint8_t alarmTone; // Alarm */
#define HOTT_TEXTMODE_MSG_TEXT_LEN 168
//Text mode msgs type
struct HOTT_TEXTMODE_MSG {
uint8_t start_byte; //#01 constant value 0x7b
uint8_t fill1; //#02 constant value 0x00
uint8_t warning_beeps;//#03 1=A 2=B ...
uint8_t msg_txt[HOTT_TEXTMODE_MSG_TEXT_LEN]; //#04 ASCII text to display to
// Bit 7 = 1 -> Inverse character display
// Display 21x8
uint8_t stop_byte; //#171 constant value 0x7d
};
uint8_t sensorTextID;
typedef struct HOTT_GAM_MSG_s {
uint8_t start_byte; //#01 start uint8_t constant value 0x7c
uint8_t gam_sensor_id; //#02 EAM sensort id. constat value 0x8d
uint8_t warning_beeps; //#03 1=A 2=B ... 0x1a=Z 0 = no alarm
// Q Min cell voltage sensor 1
// R Min Battery 1 voltage sensor 1
// J Max Battery 1 voltage sensor 1
// F Min temperature sensor 1
// H Max temperature sensor 1
// S Min Battery 2 voltage sensor 2
// K Max Battery 2 voltage sensor 2
// G Min temperature sensor 2
// I Max temperature sensor 2
// W Max current
// V Max capacity mAh
// P Min main power voltage
// X Max main power voltage
// O Min altitude
// Z Max altitude
// C negative difference m/s too high
// A negative difference m/3s too high
// N positive difference m/s too high
// L positive difference m/3s too high
// T Minimum RPM
// Y Maximum RPM
uint8_t alarmInverse1;
uint8_t alarmInverse2;
uint8_t sensor_id; //#04 constant value 0xd0
uint8_t alarm_invers1; //#05 alarm bitmask. Value is displayed inverted
//Bit# Alarm field
// 0 all cell voltage
// 1 Battery 1
// 2 Battery 2
// 3 Temperature 1
// 4 Temperature 2
// 5 Fuel
// 6 mAh
// 7 Altitude
uint8_t alarm_invers2; //#06 alarm bitmask. Value is displayed inverted
//Bit# Alarm Field
// 0 main power current
// 1 main power voltage
// 2 Altitude
// 3 m/s
// 4 m/3s
// 5 unknown
// 6 unknown
// 7 "ON" sign/text msg active
uint8_t cell1L; // Low Voltage Cell 1-7 in 2mV steps */
uint8_t cell2L;
uint8_t cell3L;
uint8_t cell4L;
uint8_t cell5L;
uint8_t cell6L;
uint8_t cell7L;
uint8_t cell1; //#07 cell 1 voltage lower value. 0.02V steps, 124=2.48V
uint8_t cell2; //#08
uint8_t cell3; //#09
uint8_t cell4; //#10
uint8_t cell5; //#11
uint8_t cell6; //#12
uint8_t batt1_L; //#13 battery 1 voltage LSB value. 0.1V steps. 50 = 5.5V
uint8_t batt1_H; //#14
uint8_t batt2_L; //#15 battery 2 voltage LSB value. 0.1V steps. 50 = 5.5V
uint8_t batt2_H; //#16
uint8_t temperature1; //#17 temperature 1. offset of 20. a value of 20 = 0°C
uint8_t temperature2; //#18 temperature 2. offset of 20. a value of 20 = 0°C
uint8_t fuel_procent; //#19 Fuel capacity in %. Values 0--100
// graphical display ranges: 0-25% 50% 75% 100%
uint8_t fuel_ml_L; //#20 Fuel in ml scale. Full = 65535!
uint8_t fuel_ml_H; //#21
uint8_t rpm_L; //#22 RPM in 10 RPM steps. 300 = 3000rpm
uint8_t rpm_H; //#23
uint8_t altitude_L; //#24 altitude in meters. offset of 500, 500 = 0m
uint8_t altitude_H; //#25
uint8_t climbrate_L; //#26 climb rate in 0.01m/s. Value of 30000 = 0.00 m/s
uint8_t climbrate_H; //#27
uint8_t climbrate3s; //#28 climb rate in m/3sec. Value of 120 = 0m/3sec
uint8_t current_L; //#29 current in 0.1A steps
uint8_t current_H; //#30
uint8_t main_voltage_L; //#31 Main power voltage using 0.1V steps
uint8_t main_voltage_H; //#32
uint8_t batt_cap_L; //#33 used battery capacity in 10mAh steps
uint8_t batt_cap_H; //#34
uint8_t speed_L; //#35 (air?) speed in km/h(?) we are using ground speed here per default
uint8_t speed_H; //#36
uint8_t min_cell_volt; //#37 minimum cell voltage in 2mV steps. 124 = 2,48V
uint8_t min_cell_volt_num; //#38 number of the cell with the lowest voltage
uint8_t rpm2_L; //#39 RPM in 10 RPM steps. 300 = 3000rpm
uint8_t rpm2_H; //#40
uint8_t general_error_number;//#41 Voice error == 12. TODO: more docu
uint8_t pressure; //#42 Pressure up to 16bar. 0,1bar scale. 20 = 2bar
uint8_t version; //#43 version number TODO: more info?
uint8_t stop_byte; //#44 stop uint8_t
} OTT_GAM_MSG_t;
uint8_t cell1H; // High Voltage Cell 1-7 in 2mV steps */
uint8_t cell2H;
uint8_t cell3H;
uint8_t cell4H;
uint8_t cell5H;
uint8_t cell6H;
uint8_t cell7H;
#define HOTT_VARIO_MSG_TEXT_LEN 21
typedef struct HOTT_VARIO_MSG_s {
uint8_t start_byte; //#01 start uint8_t constant value 0x7c
uint8_t vario_sensor_id; //#02 VARIO sensort id. constat value 0x89
uint8_t warning_beeps; //#03 1=A 2=B ...
// Q Min cell voltage sensor 1
// R Min Battery 1 voltage sensor 1
// J Max Battery 1 voltage sensor 1
// F Min temperature sensor 1
// H Max temperature sensor 1
// S Min Battery voltage sensor 2
// K Max Battery voltage sensor 2
// G Min temperature sensor 2
// I Max temperature sensor 2
// W Max current
// V Max capacity mAh
// P Min main power voltage
// X Max main power voltage
// O Min altitude
// Z Max altitude
// T Minimum RPM
// Y Maximum RPM
// C m/s negative difference
// A m/3s negative difference
uint8_t battery1Low; // Battetry 1 LSB/MSB in 100mv steps; 50 == 5V */
uint8_t battery1High; // Battetry 1 LSB/MSB in 100mv steps; 50 == 5V */
uint8_t battery2Low; // Battetry 2 LSB/MSB in 100mv steps; 50 == 5V */
uint8_t battery2High; // Battetry 2 LSB/MSB in 100mv steps; 50 == 5V */
uint8_t sensor_id; //#04 constant value 0x90
uint8_t alarm_invers1; //#05 Inverse display (alarm?) bitmask
//TODO: more info
uint8_t altitude_L; //#06 Altitude low uint8_t. In meters. A value of 500 means 0m
uint8_t altitude_H; //#07 Altitude high uint8_t
uint8_t altitude_max_L; //#08 Max. measured altitude low uint8_t. In meters. A value of 500 means 0m
uint8_t altitude_max_H; //#09 Max. measured altitude high uint8_t
uint8_t altitude_min_L; //#10 Min. measured altitude low uint8_t. In meters. A value of 500 means 0m
uint8_t altitude_min_H; //#11 Min. measured altitude high uint8_t
uint8_t climbrate_L; //#12 Climb rate in m/s. Steps of 0.01m/s. Value of 30000 = 0.00 m/s
uint8_t climbrate_H; //#13 Climb rate in m/s
uint8_t climbrate3s_L; //#14 Climb rate in m/3s. Steps of 0.01m/3s. Value of 30000 = 0.00 m/3s
uint8_t climbrate3s_H; //#15 Climb rate m/3s low uint8_t
uint8_t climbrate10s_L; //#16 Climb rate m/10s. Steps of 0.01m/10s. Value of 30000 = 0.00 m/10s
uint8_t climbrate10s_H; //#17 Climb rate m/10s low uint8_t
uint8_t text_msg[HOTT_VARIO_MSG_TEXT_LEN]; //#18 Free ASCII text message
uint8_t free_char1; //#39 Free ASCII character. appears right to home distance
uint8_t free_char2; //#40 Free ASCII character. appears right to home direction
uint8_t free_char3; //#41 Free ASCII character. appears? TODO: Check where this char appears
uint8_t compass_direction; //#42 Compass heading in 2° steps. 1 = 2°
uint8_t version; //#43 version number TODO: more info?
uint8_t stop_byte; //#44 stop uint8_t, constant value 0x7d
} HOTT_VARIO_MSG_t;
uint8_t temp1; // Temp 1; Offset of 20. 20 == 0C */
uint8_t temp2; // Temp 2; Offset of 20. 20 == 0C */
typedef struct HOTT_EAM_MSG_s {
uint8_t start_byte; //#01 start uint8_t
uint8_t eam_sensor_id; //#02 EAM sensort id. constat value 0x8e
uint8_t warning_beeps; //#03 1=A 2=B ... or 'A' - 0x40 = 1
// Q Min cell voltage sensor 1
// R Min Battery 1 voltage sensor 1
// J Max Battery 1 voltage sensor 1
// F Mim temperature sensor 1
// H Max temperature sensor 1
// S Min cell voltage sensor 2
// K Max cell voltage sensor 2
// G Min temperature sensor 2
// I Max temperature sensor 2
// W Max current
// V Max capacity mAh
// P Min main power voltage
// X Max main power voltage
// O Min altitude
// Z Max altitude
// C (negative) sink rate m/sec to high
// B (negative) sink rate m/3sec to high
// N climb rate m/sec to high
// M climb rate m/3sec to high
uint16_t height; // Height. Offset -500. 500 == 0 */
uint8_t sensor_id; //#04 constant value 0xe0
uint8_t alarm_invers1; //#05 alarm bitmask. Value is displayed inverted
//Bit# Alarm field
// 0 mAh
// 1 Battery 1
// 2 Battery 2
// 3 Temperature 1
// 4 Temperature 2
// 5 Altitude
// 6 Current
// 7 Main power voltage
uint8_t alarm_invers2; //#06 alarm bitmask. Value is displayed inverted
//Bit# Alarm Field
// 0 m/s
// 1 m/3s
// 2 Altitude (duplicate?)
// 3 m/s (duplicate?)
// 4 m/3s (duplicate?)
// 5 unknown/unused
// 6 unknown/unused
// 7 "ON" sign/text msg active
uint16_t current; // 1 = 0.1A */
uint8_t cell1_L; //#07 cell 1 voltage lower value. 0.02V steps, 124=2.48V
uint8_t cell2_L; //#08
uint8_t cell3_L; //#09
uint8_t cell4_L; //#10
uint8_t cell5_L; //#11
uint8_t cell6_L; //#12
uint8_t cell7_L; //#13
uint8_t cell1_H; //#14 cell 1 voltage high value. 0.02V steps, 124=2.48V
uint8_t cell2_H; //#15
uint8_t cell3_H; //#16
uint8_t cell4_H; //#17
uint8_t cell5_H; //#18
uint8_t cell6_H; //#19
uint8_t cell7_H; //#20
uint8_t driveVoltageLow;
uint8_t driveVoltageHigh;
uint8_t batt1_voltage_L; //#21 battery 1 voltage lower value in 100mv steps, 50=5V. optionally cell8_L value 0.02V steps
uint8_t batt1_voltage_H; //#22
uint16_t capacity; // mAh */
uint8_t batt2_voltage_L; //#23 battery 2 voltage lower value in 100mv steps, 50=5V. optionally cell8_H value. 0.02V steps
uint8_t batt2_voltage_H; //#24
uint16_t m2s; // m2s; 0x48 == 0 */
uint8_t temp1; //#25 Temperature sensor 1. 20=0°, 46=26° - offset of 20.
uint8_t temp2; //#26 temperature sensor 2
uint8_t m3s; // m3s; 0x78 == 0 */
uint8_t altitude_L; //#27 Attitude lower value. unit: meters. Value of 500 = 0m
uint8_t altitude_H; //#28
uint16_t rpm; // RPM. 10er steps; 300 == 3000rpm */
uint8_t current_L; //#29 Current in 0.1 steps
uint8_t current_H; //#30
uint8_t minutes;
uint8_t seconds;
uint8_t main_voltage_L; //#31 Main power voltage (drive) in 0.1V steps
uint8_t main_voltage_H; //#32
uint16_t speed;
uint8_t batt_cap_L; //#33 used battery capacity in 10mAh steps
uint8_t batt_cap_H; //#34
uint8_t endByte;
} HoTTV4ElectricAirModule_t;
uint8_t climbrate_L; //#35 climb rate in 0.01m/s. Value of 30000 = 0.00 m/s
uint8_t climbrate_H; //#36
uint8_t climbrate3s; //#37 climbrate in m/3sec. Value of 120 = 0m/3sec
uint8_t rpm_L; //#38 RPM. Steps: 10 U/min
uint8_t rpm_H; //#39
uint8_t electric_min; //#40 Electric minutes. Time does start, when motor current is > 3 A
uint8_t electric_sec; //#41
uint8_t speed_L; //#42 (air?) speed in km/h. Steps 1km/h
uint8_t speed_H; //#43
uint8_t stop_byte; //#44 stop uint8_t
} HOTT_EAM_MSG_t;
//HoTT GPS Sensor response to Receiver (?!not?! Smartbox)
typedef struct HOTT_GPS_MSG_s {
uint8_t start_byte; //#01 constant value 0x7c
uint8_t gps_sensor_id; //#02 constant value 0x8a
uint8_t warning_beeps; //#03 1=A 2=B ...
// A Min Speed
// L Max Speed
// O Min Altitude
// Z Max Altitude
// C (negative) sink rate m/sec to high
// B (negative) sink rate m/3sec to high
// N climb rate m/sec to high
// M climb rate m/3sec to high
// D Max home distance
//
uint8_t sensor_id; //#04 constant (?) value 0xa0
uint8_t alarm_invers1; //#05
//TODO: more info
uint8_t alarm_invers2; //#06 1 = No GPS signal
//TODO: more info
uint8_t flight_direction; //#07 flight direction in 2 degreees/step (1 = 2degrees);
uint8_t gps_speed_L; //08 km/h
uint8_t gps_speed_H; //#09
uint8_t pos_NS; //#10 north = 0, south = 1
uint8_t pos_NS_dm_L; //#11 degree minutes ie N48°39988
uint8_t pos_NS_dm_H; //#12
uint8_t pos_NS_sec_L; //#13 position seconds
uint8_t pos_NS_sec_H; //#14
uint8_t pos_EW; //#15 east = 0, west = 1
uint8_t pos_EW_dm_L; //#16 degree minutes ie. E9°259360
uint8_t pos_EW_dm_H; //#17
uint8_t pos_EW_sec_L; //#18 position seconds
uint8_t pos_EW_sec_H; //#19
uint8_t home_distance_L; //#20 meters
uint8_t home_distance_H; //#21
uint8_t altitude_L; //#22 meters. Value of 500 = 0m
uint8_t altitude_H; //#23
uint8_t climbrate_L; //#24 m/s 0.01m/s resolution. Value of 30000 = 0.00 m/s
uint8_t climbrate_H; //#25
uint8_t climbrate3s; //#26 climbrate in m/3s resolution, value of 120 = 0 m/3s
uint8_t gps_satelites;//#27 sat count
uint8_t gps_fix_char; //#28 GPS fix character. display, 'D' = DGPS, '2' = 2D, '3' = 3D, '-' = no fix. Where appears this char???
uint8_t home_direction;//#29 direction from starting point to Model position (2 degree steps)
uint8_t angle_roll; //#30 angle roll in 2 degree steps
uint8_t angle_nick; //#31 angle in 2degree steps
uint8_t angle_compass; //#32 angle in 2degree steps. 1 = 2°, 255 = - 2° (1 uint8_t) North = 0°
uint8_t gps_time_h; //#33 UTC time hours
uint8_t gps_time_m; //#34 UTC time minutes
uint8_t gps_time_s; //#35 UTC time seconds
uint8_t gps_time_sss; //#36 UTC time milliseconds
uint8_t msl_altitude_L;//#37 mean sea level altitude
uint8_t msl_altitude_H;//#38
uint8_t vibration; //#39 vibrations level in %
uint8_t free_char1; //#40 appears right to home distance
uint8_t free_char2; //#41 appears right to home direction
uint8_t free_char3; //#42 GPS ASCII D=DGPS 2=2D 3=3D -=No Fix
uint8_t version; //#43
// 0 GPS Graupner #33600
// 1 Gyro Receiver
// 255 Mikrokopter
uint8_t stop_byte; //#44 constant value 0x7d
} HOTT_GPS_MSG_t;
typedef struct HOTT_AIRESC_MSG_s {
uint8_t start_byte; //#01 constant value 0x7c
uint8_t gps_sensor_id; //#02 constant value 0x8c
uint8_t warning_beeps; //#03 1=A 2=B ...
// A
// L
// O
// Z
// C
// B
// N
// M
// D
//
uint8_t sensor_id; //#04 constant value 0xc0
uint8_t alarm_invers1; //#05 TODO: more info
uint8_t alarm_invers2; //#06 TODO: more info
uint8_t input_v_L; //#07 Input voltage low byte
uint8_t input_v_H; //#08
uint8_t input_v_min_L; //#09 Input min. voltage low byte
uint8_t input_v_min_H; //#10
uint8_t batt_cap_L; //#11 battery capacity in 10mAh steps
uint8_t batt_cap_H; //#12
uint8_t esc_temp; //#13 ESC temperature
uint8_t esc_max_temp; //#14 ESC max. temperature
uint8_t current_L; //#15 Current in 0.1 steps
uint8_t current_H; //#16
uint8_t current_max_L; //#17 Current max. in 0.1 steps
uint8_t current_max_H; //#18
uint8_t rpm_L; //#19 RPM in 10U/min steps
uint8_t rpm_H; //#20
uint8_t rpm_max_L; //#21 RPM max
uint8_t rpm_max_H; //#22
uint8_t throttle; //#23 throttle in %
uint8_t speed_L; //#24 Speed
uint8_t speed_H; //#25
uint8_t speed_max_L; //#26 Speed max
uint8_t speed_max_H; //#27
uint8_t bec_v; //#28 BEC voltage
uint8_t bec_min_v; //#29 BEC min. voltage
uint8_t bec_current; //#30 BEC current
uint8_t bec_current_max_L; //#31 BEC max. current
uint8_t bec_current_max_H; //#32 TODO: not really clear why 2 bytes...
uint8_t pwm; //#33 PWM
uint8_t bec_temp; //#34 BEC temperature
uint8_t bec_temp_max; //#35 BEC highest temperature
uint8_t motor_temp; //#36 Motor or external sensor temperature
uint8_t motor_temp_max; //#37 Highest motor or external sensor temperature
uint8_t motor_rpm_L; //#38 Motor or external RPM sensor (without gear)
uint8_t motor_rpm_H; //#39
uint8_t motor_timing; //#40 Motor timing
uint8_t motor_timing_adv; //#41 Motor advanced timing
uint8_t motor_highest_current; //#42 Motor number (1-x) with highest current
uint8_t version; //#43 Version number (highest current motor 1-x)
uint8_t stop_byte; //#44 constant value 0x7d
} HOTT_AIRESC_MSG_t;
void handleHoTTTelemetry(void);
void checkTelemetryState(void);
void configureHoTTTelemetryPort(telemetryConfig_t *telemetryConfig);
void initHoTTTelemetry(telemetryConfig_t *telemetryConfig);
void configureHoTTTelemetryPort(void);
void freeHoTTTelemetryPort(void);
uint32_t getHoTTTelemetryProviderBaudRate(void);