1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-15 04:15:44 +03:00

Fixing indentation and spacing of imported HoTT code.

This commit is contained in:
Dominic Clifton 2014-04-07 23:17:11 +01:00
parent c012e7480f
commit bf59943578
2 changed files with 207 additions and 207 deletions

View file

@ -83,55 +83,55 @@ void hottV4FormatAndSendGPSResponse(void)
// Send data from output buffer // Send data from output buffer
hottV4Respond((uint8_t*)&HoTTV4GPSModule, sizeof(HoTTV4GPSModule)); hottV4Respond((uint8_t*)&HoTTV4GPSModule, sizeof(HoTTV4GPSModule));
} }
void hottV4GPSUpdate(void) void hottV4GPSUpdate(void)
{ {
//number of Satelites //number of Satelites
HoTTV4GPSModule.GPSNumSat=GPS_numSat; HoTTV4GPSModule.GPSNumSat=GPS_numSat;
if (f.GPS_FIX > 0) { if (f.GPS_FIX > 0) {
/** GPS fix */ /** GPS fix */
HoTTV4GPSModule.GPS_fix = 0x66; // Displays a 'f' for fix HoTTV4GPSModule.GPS_fix = 0x66; // Displays a 'f' for fix
//latitude //latitude
HoTTV4GPSModule.LatitudeNS=(GPS_coord[LAT]<0); HoTTV4GPSModule.LatitudeNS=(GPS_coord[LAT]<0);
uint8_t deg = GPS_coord[LAT] / 100000; uint8_t deg = GPS_coord[LAT] / 100000;
uint32_t sec = (GPS_coord[LAT] - (deg * 100000)) * 6; uint32_t sec = (GPS_coord[LAT] - (deg * 100000)) * 6;
uint8_t min = sec / 10000; uint8_t min = sec / 10000;
sec = sec % 10000; sec = sec % 10000;
uint16_t degMin = (deg * 100) + min; uint16_t degMin = (deg * 100) + min;
HoTTV4GPSModule.LatitudeMinLow = degMin; HoTTV4GPSModule.LatitudeMinLow = degMin;
HoTTV4GPSModule.LatitudeMinHigh = degMin >> 8; HoTTV4GPSModule.LatitudeMinHigh = degMin >> 8;
HoTTV4GPSModule.LatitudeSecLow = sec; HoTTV4GPSModule.LatitudeSecLow = sec;
HoTTV4GPSModule.LatitudeSecHigh = sec >> 8; HoTTV4GPSModule.LatitudeSecHigh = sec >> 8;
//latitude //latitude
HoTTV4GPSModule.longitudeEW=(GPS_coord[LON]<0); HoTTV4GPSModule.longitudeEW=(GPS_coord[LON]<0);
deg = GPS_coord[LON] / 100000; deg = GPS_coord[LON] / 100000;
sec = (GPS_coord[LON] - (deg * 100000)) * 6; sec = (GPS_coord[LON] - (deg * 100000)) * 6;
min = sec / 10000; min = sec / 10000;
sec = sec % 10000; sec = sec % 10000;
degMin = (deg * 100) + min; degMin = (deg * 100) + min;
HoTTV4GPSModule.longitudeMinLow = degMin; HoTTV4GPSModule.longitudeMinLow = degMin;
HoTTV4GPSModule.longitudeMinHigh = degMin >> 8; HoTTV4GPSModule.longitudeMinHigh = degMin >> 8;
HoTTV4GPSModule.longitudeSecLow = sec; HoTTV4GPSModule.longitudeSecLow = sec;
HoTTV4GPSModule.longitudeSecHigh = sec >> 8; HoTTV4GPSModule.longitudeSecHigh = sec >> 8;
/** GPS Speed in km/h */ /** GPS Speed in km/h */
uint16_t speed = (GPS_speed / 100) * 36; // 0.1m/s * 0.36 = km/h uint16_t speed = (GPS_speed / 100) * 36; // 0.1m/s * 0.36 = km/h
HoTTV4GPSModule.GPSSpeedLow = speed & 0x00FF; HoTTV4GPSModule.GPSSpeedLow = speed & 0x00FF;
HoTTV4GPSModule.GPSSpeedHigh = speed >> 8; HoTTV4GPSModule.GPSSpeedHigh = speed >> 8;
/** Distance to home */ /** Distance to home */
HoTTV4GPSModule.distanceLow = GPS_distanceToHome & 0x00FF; HoTTV4GPSModule.distanceLow = GPS_distanceToHome & 0x00FF;
HoTTV4GPSModule.distanceHigh = GPS_distanceToHome >> 8; HoTTV4GPSModule.distanceHigh = GPS_distanceToHome >> 8;
/** Altitude */ /** Altitude */
HoTTV4GPSModule.altitudeLow = GPS_altitude & 0x00FF; HoTTV4GPSModule.altitudeLow = GPS_altitude & 0x00FF;
HoTTV4GPSModule.altitudeHigh = GPS_altitude >> 8; HoTTV4GPSModule.altitudeHigh = GPS_altitude >> 8;
/** Altitude */ /** Altitude */
HoTTV4GPSModule.HomeDirection = GPS_directionToHome; HoTTV4GPSModule.HomeDirection = GPS_directionToHome;
} }
else else
{ {
HoTTV4GPSModule.GPS_fix = 0x20; // Displays a ' ' to show nothing or clear the old value HoTTV4GPSModule.GPS_fix = 0x20; // Displays a ' ' to show nothing or clear the old value
} }
} }
/** /**
* Writes cell 1-4 high, low values and if not available * Writes cell 1-4 high, low values and if not available
@ -162,8 +162,8 @@ static void hottV4EAMUpdateBattery() {
HoTTV4ElectricAirModule.battery2High = 0 >> 8; HoTTV4ElectricAirModule.battery2High = 0 >> 8;
if (batteryWarning) { if (batteryWarning) {
HoTTV4ElectricAirModule.alarmTone = HoTTv4NotificationUndervoltage; HoTTV4ElectricAirModule.alarmTone = HoTTv4NotificationUndervoltage;
HoTTV4ElectricAirModule.alarmInverse1 |= 0x80; // Invert Voltage display HoTTV4ElectricAirModule.alarmInverse1 |= 0x80; // Invert Voltage display
} }
#endif #endif
} }
@ -174,40 +174,40 @@ static void hottV4EAMUpdateTemperatures() {
#if 0 #if 0
if (HoTTV4ElectricAirModule.temp1 >= (20 + MultiHoTTModuleSettings.alarmTemp1)) { if (HoTTV4ElectricAirModule.temp1 >= (20 + MultiHoTTModuleSettings.alarmTemp1)) {
HoTTV4ElectricAirModule.alarmTone = HoTTv4NotificationMaxTemperature; HoTTV4ElectricAirModule.alarmTone = HoTTv4NotificationMaxTemperature;
HoTTV4ElectricAirModule.alarmInverse |= 0x8; // Invert Temp1 display HoTTV4ElectricAirModule.alarmInverse |= 0x8; // Invert Temp1 display
} }
#endif #endif
} }
/** /**
* Sends HoTTv4 capable EAM telemetry frame. * Sends HoTTv4 capable EAM telemetry frame.
*/ */
void hottV4FormatAndSendEAMResponse(void) { void hottV4FormatAndSendEAMResponse(void) {
memset(&HoTTV4ElectricAirModule, 0, sizeof(HoTTV4ElectricAirModule)); memset(&HoTTV4ElectricAirModule, 0, sizeof(HoTTV4ElectricAirModule));
/** Minimum data set for EAM */ /** Minimum data set for EAM */
HoTTV4ElectricAirModule.startByte = 0x7C; HoTTV4ElectricAirModule.startByte = 0x7C;
HoTTV4ElectricAirModule.sensorID = HOTTV4_ELECTRICAL_AIR_SENSOR_ID; HoTTV4ElectricAirModule.sensorID = HOTTV4_ELECTRICAL_AIR_SENSOR_ID;
HoTTV4ElectricAirModule.sensorTextID = HOTTV4_ELECTRICAL_AIR_SENSOR_TEXT_ID; HoTTV4ElectricAirModule.sensorTextID = HOTTV4_ELECTRICAL_AIR_SENSOR_TEXT_ID;
HoTTV4ElectricAirModule.endByte = 0x7D; HoTTV4ElectricAirModule.endByte = 0x7D;
/** ### */ /** ### */
/** Reset alarms */ /** Reset alarms */
HoTTV4ElectricAirModule.alarmTone = 0x0; HoTTV4ElectricAirModule.alarmTone = 0x0;
HoTTV4ElectricAirModule.alarmInverse1 = 0x0; HoTTV4ElectricAirModule.alarmInverse1 = 0x0;
hottV4EAMUpdateBattery(); hottV4EAMUpdateBattery();
hottV4EAMUpdateTemperatures(); hottV4EAMUpdateTemperatures();
HoTTV4ElectricAirModule.current = 0 / 10; HoTTV4ElectricAirModule.current = 0 / 10;
HoTTV4ElectricAirModule.height = OFFSET_HEIGHT + 0; HoTTV4ElectricAirModule.height = OFFSET_HEIGHT + 0;
HoTTV4ElectricAirModule.m2s = OFFSET_M2S; HoTTV4ElectricAirModule.m2s = OFFSET_M2S;
HoTTV4ElectricAirModule.m3s = OFFSET_M3S; HoTTV4ElectricAirModule.m3s = OFFSET_M3S;
// Send data from output buffer // Send data from output buffer
hottV4Respond((uint8_t*)&HoTTV4ElectricAirModule, sizeof(HoTTV4ElectricAirModule)); hottV4Respond((uint8_t*)&HoTTV4ElectricAirModule, sizeof(HoTTV4ElectricAirModule));
} }
static void hottV4Respond(uint8_t *data, uint8_t size) { static void hottV4Respond(uint8_t *data, uint8_t size) {
@ -218,11 +218,11 @@ static void hottV4Respond(uint8_t *data, uint8_t size) {
uint8_t i; uint8_t i;
for (i = 0; i < size - 1; i++) { for (i = 0; i < size - 1; i++) {
crc += data[i]; crc += data[i];
hottV4SerialWrite(data[i]); hottV4SerialWrite(data[i]);
// Protocol specific delay between each transmitted byte // Protocol specific delay between each transmitted byte
delayMicroseconds(HOTTV4_TX_DELAY); delayMicroseconds(HOTTV4_TX_DELAY);
} }
// Write package checksum // Write package checksum
@ -234,7 +234,7 @@ static void hottV4Respond(uint8_t *data, uint8_t size) {
} }
static void hottV4SerialWrite(uint8_t c) { static void hottV4SerialWrite(uint8_t c) {
serialWrite(core.telemport, c); serialWrite(core.telemport, c);
} }
void configureHoTTTelemetryPort(void) { void configureHoTTTelemetryPort(void) {
@ -251,13 +251,13 @@ void handleHoTTTelemetry(void)
uint8_t c; uint8_t c;
while (serialTotalBytesWaiting(core.telemport) > 0) { while (serialTotalBytesWaiting(core.telemport) > 0) {
c = serialRead(core.telemport); c = serialRead(core.telemport);
// Protocol specific waiting time // Protocol specific waiting time
// to avoid collisions // to avoid collisions
delay(5); delay(5);
switch (c) { switch (c) {
case 0x8A: case 0x8A:
if (sensors(SENSOR_GPS)) hottV4FormatAndSendGPSResponse(); if (sensors(SENSOR_GPS)) hottV4FormatAndSendGPSResponse();
break; break;

View file

@ -33,47 +33,47 @@
#define OFFSET_M3S 120 #define OFFSET_M3S 120
typedef enum { typedef enum {
HoTTv4NotificationErrorCalibration = 0x01, HoTTv4NotificationErrorCalibration = 0x01,
HoTTv4NotificationErrorReceiver = 0x02, HoTTv4NotificationErrorReceiver = 0x02,
HoTTv4NotificationErrorDataBus = 0x03, HoTTv4NotificationErrorDataBus = 0x03,
HoTTv4NotificationErrorNavigation = 0x04, HoTTv4NotificationErrorNavigation = 0x04,
HoTTv4NotificationErrorError = 0x05, HoTTv4NotificationErrorError = 0x05,
HoTTv4NotificationErrorCompass = 0x06, HoTTv4NotificationErrorCompass = 0x06,
HoTTv4NotificationErrorSensor = 0x07, HoTTv4NotificationErrorSensor = 0x07,
HoTTv4NotificationErrorGPS = 0x08, HoTTv4NotificationErrorGPS = 0x08,
HoTTv4NotificationErrorMotor = 0x09, HoTTv4NotificationErrorMotor = 0x09,
HoTTv4NotificationMaxTemperature = 0x0A, HoTTv4NotificationMaxTemperature = 0x0A,
HoTTv4NotificationAltitudeReached = 0x0B, HoTTv4NotificationAltitudeReached = 0x0B,
HoTTv4NotificationWaypointReached = 0x0C, HoTTv4NotificationWaypointReached = 0x0C,
HoTTv4NotificationNextWaypoint = 0x0D, HoTTv4NotificationNextWaypoint = 0x0D,
HoTTv4NotificationLanding = 0x0E, HoTTv4NotificationLanding = 0x0E,
HoTTv4NotificationGPSFix = 0x0F, HoTTv4NotificationGPSFix = 0x0F,
HoTTv4NotificationUndervoltage = 0x10, HoTTv4NotificationUndervoltage = 0x10,
HoTTv4NotificationGPSHold = 0x11, HoTTv4NotificationGPSHold = 0x11,
HoTTv4NotificationGPSHome = 0x12, HoTTv4NotificationGPSHome = 0x12,
HoTTv4NotificationGPSOff = 0x13, HoTTv4NotificationGPSOff = 0x13,
HoTTv4NotificationBeep = 0x14, HoTTv4NotificationBeep = 0x14,
HoTTv4NotificationMicrocopter = 0x15, HoTTv4NotificationMicrocopter = 0x15,
HoTTv4NotificationCapacity = 0x16, HoTTv4NotificationCapacity = 0x16,
HoTTv4NotificationCareFreeOff = 0x17, HoTTv4NotificationCareFreeOff = 0x17,
HoTTv4NotificationCalibrating = 0x18, HoTTv4NotificationCalibrating = 0x18,
HoTTv4NotificationMaxRange = 0x19, HoTTv4NotificationMaxRange = 0x19,
HoTTv4NotificationMaxAltitude = 0x1A, HoTTv4NotificationMaxAltitude = 0x1A,
HoTTv4Notification20Meter = 0x25, HoTTv4Notification20Meter = 0x25,
HoTTv4NotificationMicrocopterOff = 0x26, HoTTv4NotificationMicrocopterOff = 0x26,
HoTTv4NotificationAltitudeOn = 0x27, HoTTv4NotificationAltitudeOn = 0x27,
HoTTv4NotificationAltitudeOff = 0x28, HoTTv4NotificationAltitudeOff = 0x28,
HoTTv4Notification100Meter = 0x29, HoTTv4Notification100Meter = 0x29,
HoTTv4NotificationCareFreeOn = 0x2E, HoTTv4NotificationCareFreeOn = 0x2E,
HoTTv4NotificationDown = 0x2F, HoTTv4NotificationDown = 0x2F,
HoTTv4NotificationUp = 0x30, HoTTv4NotificationUp = 0x30,
HoTTv4NotificationHold = 0x31, HoTTv4NotificationHold = 0x31,
HoTTv4NotificationGPSOn = 0x32, HoTTv4NotificationGPSOn = 0x32,
HoTTv4NotificationFollowing = 0x33, HoTTv4NotificationFollowing = 0x33,
HoTTv4NotificationStarting = 0x34, HoTTv4NotificationStarting = 0x34,
HoTTv4NotificationReceiver = 0x35, HoTTv4NotificationReceiver = 0x35,
} HoTTv4Notification; } HoTTv4Notification;
/*----------------------------------------------------------- /*-----------------------------------------------------------
@ -86,62 +86,62 @@ Byte 2: 0x8A = GPS Sensor byte (witch data Transmitter wants to get)
-----------------------------------------------------------*/ -----------------------------------------------------------*/
struct { struct {
uint8_t startByte; // Byte 1: 0x7C = Start byte data uint8_t startByte; // Byte 1: 0x7C = Start byte data
uint8_t sensorID; // Byte 2: 0x8A = GPS Sensor uint8_t sensorID; // Byte 2: 0x8A = GPS Sensor
uint8_t alarmTone; // Byte 3: 0…= warning beeps uint8_t alarmTone; // Byte 3: 0…= warning beeps
uint8_t sensorTextID; // Byte 4: 160 0xA0 Sensor ID Neu! uint8_t sensorTextID; // Byte 4: 160 0xA0 Sensor ID Neu!
uint8_t alarmInverse1; // Byte 5: 01 inverse status uint8_t alarmInverse1; // Byte 5: 01 inverse status
uint8_t alarmInverse2; // Byte 6: 00 inverse status status 1 = no GPS signal 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 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 GPSSpeedLow; // Byte 8: 8 = GPS speed low byte 8km/h
uint8_t GPSSpeedHigh; // Byte 9: 0 = GPS speed high byte uint8_t GPSSpeedHigh; // Byte 9: 0 = GPS speed high byte
// Example: N 48°39'988" // Example: N 48°39'988"
uint8_t LatitudeNS; // Byte 10: 000 = N; 001 = S uint8_t LatitudeNS; // Byte 10: 000 = N; 001 = S
// 0x12E7 = 4839 (48°30') // 0x12E7 = 4839 (48°30')
uint8_t LatitudeMinLow; // Byte 11: 231 = 0xE7 uint8_t LatitudeMinLow; // Byte 11: 231 = 0xE7
uint8_t LatitudeMinHigh; // Byte 12: 018 = 0x12 uint8_t LatitudeMinHigh; // Byte 12: 018 = 0x12
// 0x03DC = 0988 (988") // 0x03DC = 0988 (988")
uint8_t LatitudeSecLow; // Byte 13: 220 = 0xDC uint8_t LatitudeSecLow; // Byte 13: 220 = 0xDC
uint8_t LatitudeSecHigh; // Byte 14: 003 = 0x03 uint8_t LatitudeSecHigh; // Byte 14: 003 = 0x03
// Example: E 9°25'9360" // Example: E 9°25'9360"
uint8_t longitudeEW; // Byte 15: 000 = E; 001 = W; uint8_t longitudeEW; // Byte 15: 000 = E; 001 = W;
// 0x039D = 0925 (09°25') // 0x039D = 0925 (09°25')
uint8_t longitudeMinLow; // Byte 16: 157 = 0x9D uint8_t longitudeMinLow; // Byte 16: 157 = 0x9D
uint8_t longitudeMinHigh; // Byte 17: 003 = 0x03 uint8_t longitudeMinHigh; // Byte 17: 003 = 0x03
// 0x2490 = 9360 (9360") // 0x2490 = 9360 (9360")
uint8_t longitudeSecLow; // Byte 18: 144 = 0x90 uint8_t longitudeSecLow; // Byte 18: 144 = 0x90
uint8_t longitudeSecHigh; // Byte 19: 036 = 0x24 uint8_t longitudeSecHigh; // Byte 19: 036 = 0x24
uint8_t distanceLow; // Byte 20: distance low byte (meter) uint8_t distanceLow; // Byte 20: distance low byte (meter)
uint8_t distanceHigh; // Byte 21: distance high byte uint8_t distanceHigh; // Byte 21: distance high byte
uint8_t altitudeLow; // Byte 22: Altitude low byte (meter) uint8_t altitudeLow; // Byte 22: Altitude low byte (meter)
uint8_t altitudeHigh; // Byte 23: Altitude high byte 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 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 uint8_t resolutionHigh; // Byte 25: High Byte m/s resolution 0.01m
uint8_t m3s; // Byte 26: 120 = 0m/3s uint8_t m3s; // Byte 26: 120 = 0m/3s
uint8_t GPSNumSat; // Byte 27: number of satelites (1 byte) 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 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 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 angleXdirection; // Byte 30: angle x-direction (1 byte)
uint8_t angleYdirection; // Byte 31: angle y-direction (1 byte) uint8_t angleYdirection; // Byte 31: angle y-direction (1 byte)
uint8_t angleZdirection; // Byte 32: angle z-direction (1 byte) uint8_t angleZdirection; // Byte 32: angle z-direction (1 byte)
uint8_t gyroXLow; // Byte 33: gyro x low byte (2 bytes) uint8_t gyroXLow; // Byte 33: gyro x low byte (2 bytes)
uint8_t gyroXHigh; // Byte 34: gyro x high byte uint8_t gyroXHigh; // Byte 34: gyro x high byte
uint8_t gyroYLow; // Byte 35: gyro y low byte (2 bytes) uint8_t gyroYLow; // Byte 35: gyro y low byte (2 bytes)
uint8_t gyroYHigh; // Byte 36: gyro y high byte uint8_t gyroYHigh; // Byte 36: gyro y high byte
uint8_t gyroZLow; // Byte 37: gyro z low byte (2 bytes) uint8_t gyroZLow; // Byte 37: gyro z low byte (2 bytes)
uint8_t gyroZHigh; // Byte 38: gyro z high byte uint8_t gyroZHigh; // Byte 38: gyro z high byte
uint8_t vibration; // Byte 39: vibration (1 bytes) uint8_t vibration; // Byte 39: vibration (1 bytes)
uint8_t Ascii4; // Byte 40: 00 ASCII Free Character [4] uint8_t Ascii4; // Byte 40: 00 ASCII Free Character [4]
uint8_t Ascii5; // Byte 41: 00 ASCII Free Character [5] 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 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 version; // Byte 43: 00 version number
uint8_t endByte; // Byte 44: 0x7D End byte uint8_t endByte; // Byte 44: 0x7D End byte
} HoTTV4GPSModule; } HoTTV4GPSModule;
/*----------------------------------------------------------- /*-----------------------------------------------------------
@ -153,51 +153,51 @@ Byte 2: 8E = Electric Sensor byte
*-----------------------------------------------------------*/ *-----------------------------------------------------------*/
struct { struct {
uint8_t startByte; uint8_t startByte;
uint8_t sensorID; uint8_t sensorID;
uint8_t alarmTone; // Alarm */ uint8_t alarmTone; // Alarm */
uint8_t sensorTextID; uint8_t sensorTextID;
uint8_t alarmInverse1; uint8_t alarmInverse1;
uint8_t alarmInverse2; uint8_t alarmInverse2;
uint8_t cell1L; // Low Voltage Cell 1-7 in 2mV steps */ uint8_t cell1L; // Low Voltage Cell 1-7 in 2mV steps */
uint8_t cell2L; uint8_t cell2L;
uint8_t cell3L; uint8_t cell3L;
uint8_t cell4L; uint8_t cell4L;
uint8_t cell5L; uint8_t cell5L;
uint8_t cell6L; uint8_t cell6L;
uint8_t cell7L; uint8_t cell7L;
uint8_t cell1H; // High Voltage Cell 1-7 in 2mV steps */ uint8_t cell1H; // High Voltage Cell 1-7 in 2mV steps */
uint8_t cell2H; uint8_t cell2H;
uint8_t cell3H; uint8_t cell3H;
uint8_t cell4H; uint8_t cell4H;
uint8_t cell5H; uint8_t cell5H;
uint8_t cell6H; uint8_t cell6H;
uint8_t cell7H; uint8_t cell7H;
uint8_t battery1Low; // Battetry 1 LSB/MSB in 100mv steps; 50 == 5V */ 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 battery1High; // Battetry 1 LSB/MSB in 100mv steps; 50 == 5V */
uint8_t battery2Low; // Battetry 2 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 battery2High; // Battetry 2 LSB/MSB in 100mv steps; 50 == 5V */
uint8_t temp1; // Temp 1; Offset of 20. 20 == 0C */ uint8_t temp1; // Temp 1; Offset of 20. 20 == 0C */
uint8_t temp2; // Temp 2; Offset of 20. 20 == 0C */ uint8_t temp2; // Temp 2; Offset of 20. 20 == 0C */
uint16_t height; // Height. Offset -500. 500 == 0 */ uint16_t height; // Height. Offset -500. 500 == 0 */
uint16_t current; // 1 = 0.1A */ uint16_t current; // 1 = 0.1A */
uint8_t driveVoltageLow; uint8_t driveVoltageLow;
uint8_t driveVoltageHigh; uint8_t driveVoltageHigh;
uint16_t capacity; // mAh */ uint16_t capacity; // mAh */
uint16_t m2s; // m2s; 0x48 == 0 */ uint16_t m2s; // m2s; 0x48 == 0 */
uint8_t m3s; // m3s; 0x78 == 0 */ uint8_t m3s; // m3s; 0x78 == 0 */
uint16_t rpm; // RPM. 10er steps; 300 == 3000rpm */ uint16_t rpm; // RPM. 10er steps; 300 == 3000rpm */
uint8_t minutes; uint8_t minutes;
uint8_t seconds; uint8_t seconds;
uint8_t speed; uint8_t speed;
uint8_t version; uint8_t version;
uint8_t endByte; uint8_t endByte;
} HoTTV4ElectricAirModule; } HoTTV4ElectricAirModule;
void handleHoTTTelemetry(void); void handleHoTTTelemetry(void);