mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-17 05:15:25 +03:00
Fixing indentation and spacing of imported HoTT code.
This commit is contained in:
parent
c012e7480f
commit
bf59943578
2 changed files with 207 additions and 207 deletions
|
@ -83,55 +83,55 @@ void hottV4FormatAndSendGPSResponse(void)
|
|||
|
||||
// Send data from output buffer
|
||||
hottV4Respond((uint8_t*)&HoTTV4GPSModule, sizeof(HoTTV4GPSModule));
|
||||
}
|
||||
}
|
||||
|
||||
void hottV4GPSUpdate(void)
|
||||
{
|
||||
//number of Satelites
|
||||
HoTTV4GPSModule.GPSNumSat=GPS_numSat;
|
||||
if (f.GPS_FIX > 0) {
|
||||
/** GPS fix */
|
||||
HoTTV4GPSModule.GPS_fix = 0x66; // Displays a 'f' for fix
|
||||
//latitude
|
||||
HoTTV4GPSModule.LatitudeNS=(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;
|
||||
//latitude
|
||||
HoTTV4GPSModule.longitudeEW=(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;
|
||||
/** 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;
|
||||
/** Distance to home */
|
||||
HoTTV4GPSModule.distanceLow = GPS_distanceToHome & 0x00FF;
|
||||
HoTTV4GPSModule.distanceHigh = GPS_distanceToHome >> 8;
|
||||
/** Altitude */
|
||||
HoTTV4GPSModule.altitudeLow = GPS_altitude & 0x00FF;
|
||||
HoTTV4GPSModule.altitudeHigh = GPS_altitude >> 8;
|
||||
/** Altitude */
|
||||
HoTTV4GPSModule.HomeDirection = GPS_directionToHome;
|
||||
}
|
||||
else
|
||||
{
|
||||
HoTTV4GPSModule.GPS_fix = 0x20; // Displays a ' ' to show nothing or clear the old value
|
||||
}
|
||||
}
|
||||
//number of Satelites
|
||||
HoTTV4GPSModule.GPSNumSat=GPS_numSat;
|
||||
if (f.GPS_FIX > 0) {
|
||||
/** GPS fix */
|
||||
HoTTV4GPSModule.GPS_fix = 0x66; // Displays a 'f' for fix
|
||||
//latitude
|
||||
HoTTV4GPSModule.LatitudeNS=(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;
|
||||
//latitude
|
||||
HoTTV4GPSModule.longitudeEW=(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;
|
||||
/** 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;
|
||||
/** Distance to home */
|
||||
HoTTV4GPSModule.distanceLow = GPS_distanceToHome & 0x00FF;
|
||||
HoTTV4GPSModule.distanceHigh = GPS_distanceToHome >> 8;
|
||||
/** Altitude */
|
||||
HoTTV4GPSModule.altitudeLow = GPS_altitude & 0x00FF;
|
||||
HoTTV4GPSModule.altitudeHigh = GPS_altitude >> 8;
|
||||
/** Altitude */
|
||||
HoTTV4GPSModule.HomeDirection = GPS_directionToHome;
|
||||
}
|
||||
else
|
||||
{
|
||||
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
|
||||
|
@ -162,8 +162,8 @@ static void hottV4EAMUpdateBattery() {
|
|||
HoTTV4ElectricAirModule.battery2High = 0 >> 8;
|
||||
|
||||
if (batteryWarning) {
|
||||
HoTTV4ElectricAirModule.alarmTone = HoTTv4NotificationUndervoltage;
|
||||
HoTTV4ElectricAirModule.alarmInverse1 |= 0x80; // Invert Voltage display
|
||||
HoTTV4ElectricAirModule.alarmTone = HoTTv4NotificationUndervoltage;
|
||||
HoTTV4ElectricAirModule.alarmInverse1 |= 0x80; // Invert Voltage display
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
@ -174,40 +174,40 @@ static void hottV4EAMUpdateTemperatures() {
|
|||
|
||||
#if 0
|
||||
if (HoTTV4ElectricAirModule.temp1 >= (20 + MultiHoTTModuleSettings.alarmTemp1)) {
|
||||
HoTTV4ElectricAirModule.alarmTone = HoTTv4NotificationMaxTemperature;
|
||||
HoTTV4ElectricAirModule.alarmInverse |= 0x8; // Invert Temp1 display
|
||||
HoTTV4ElectricAirModule.alarmTone = HoTTv4NotificationMaxTemperature;
|
||||
HoTTV4ElectricAirModule.alarmInverse |= 0x8; // Invert Temp1 display
|
||||
}
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Sends HoTTv4 capable EAM telemetry frame.
|
||||
*/
|
||||
void hottV4FormatAndSendEAMResponse(void) {
|
||||
memset(&HoTTV4ElectricAirModule, 0, sizeof(HoTTV4ElectricAirModule));
|
||||
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;
|
||||
/** ### */
|
||||
/** 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;
|
||||
/** Reset alarms */
|
||||
HoTTV4ElectricAirModule.alarmTone = 0x0;
|
||||
HoTTV4ElectricAirModule.alarmInverse1 = 0x0;
|
||||
|
||||
hottV4EAMUpdateBattery();
|
||||
hottV4EAMUpdateTemperatures();
|
||||
hottV4EAMUpdateBattery();
|
||||
hottV4EAMUpdateTemperatures();
|
||||
|
||||
HoTTV4ElectricAirModule.current = 0 / 10;
|
||||
HoTTV4ElectricAirModule.height = OFFSET_HEIGHT + 0;
|
||||
HoTTV4ElectricAirModule.m2s = OFFSET_M2S;
|
||||
HoTTV4ElectricAirModule.m3s = OFFSET_M3S;
|
||||
HoTTV4ElectricAirModule.current = 0 / 10;
|
||||
HoTTV4ElectricAirModule.height = OFFSET_HEIGHT + 0;
|
||||
HoTTV4ElectricAirModule.m2s = OFFSET_M2S;
|
||||
HoTTV4ElectricAirModule.m3s = OFFSET_M3S;
|
||||
|
||||
// Send data from output buffer
|
||||
hottV4Respond((uint8_t*)&HoTTV4ElectricAirModule, sizeof(HoTTV4ElectricAirModule));
|
||||
// Send data from output buffer
|
||||
hottV4Respond((uint8_t*)&HoTTV4ElectricAirModule, sizeof(HoTTV4ElectricAirModule));
|
||||
}
|
||||
|
||||
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;
|
||||
|
||||
for (i = 0; i < size - 1; i++) {
|
||||
crc += data[i];
|
||||
hottV4SerialWrite(data[i]);
|
||||
crc += data[i];
|
||||
hottV4SerialWrite(data[i]);
|
||||
|
||||
// Protocol specific delay between each transmitted byte
|
||||
delayMicroseconds(HOTTV4_TX_DELAY);
|
||||
// Protocol specific delay between each transmitted byte
|
||||
delayMicroseconds(HOTTV4_TX_DELAY);
|
||||
}
|
||||
|
||||
// Write package checksum
|
||||
|
@ -234,7 +234,7 @@ static void hottV4Respond(uint8_t *data, uint8_t size) {
|
|||
}
|
||||
|
||||
static void hottV4SerialWrite(uint8_t c) {
|
||||
serialWrite(core.telemport, c);
|
||||
serialWrite(core.telemport, c);
|
||||
}
|
||||
|
||||
void configureHoTTTelemetryPort(void) {
|
||||
|
@ -251,13 +251,13 @@ void handleHoTTTelemetry(void)
|
|||
uint8_t c;
|
||||
|
||||
while (serialTotalBytesWaiting(core.telemport) > 0) {
|
||||
c = serialRead(core.telemport);
|
||||
c = serialRead(core.telemport);
|
||||
|
||||
// Protocol specific waiting time
|
||||
// to avoid collisions
|
||||
delay(5);
|
||||
// Protocol specific waiting time
|
||||
// to avoid collisions
|
||||
delay(5);
|
||||
|
||||
switch (c) {
|
||||
switch (c) {
|
||||
case 0x8A:
|
||||
if (sensors(SENSOR_GPS)) hottV4FormatAndSendGPSResponse();
|
||||
break;
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue