From 2fdadaa78fc0aba3b05f7af2f57e0fa7fba00421 Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Sun, 6 Apr 2014 21:36:56 +0100 Subject: [PATCH 01/24] Rename telemetry.c to telemetry_frsky.c in preparation for adding another telemetry provider --- Makefile | 2 +- baseflight.uvproj | 4 ++-- src/{telemetry.c => telemetry_frsky.c} | 0 3 files changed, 3 insertions(+), 3 deletions(-) rename src/{telemetry.c => telemetry_frsky.c} (100%) diff --git a/Makefile b/Makefile index ce2fd41072..04055fe83d 100644 --- a/Makefile +++ b/Makefile @@ -55,7 +55,7 @@ COMMON_SRC = startup_stm32f10x_md_gcc.S \ sbus.c \ sumd.c \ spektrum.c \ - telemetry.c \ + telemetry_frsky.c \ drv_gpio.c \ drv_i2c.c \ drv_i2c_soft.c \ diff --git a/baseflight.uvproj b/baseflight.uvproj index 1fd8dc25c1..2eea4a6ddf 100755 --- a/baseflight.uvproj +++ b/baseflight.uvproj @@ -1345,9 +1345,9 @@ .\src\buzzer.c - telemetry.c + telemetry_frsky.c 1 - .\src\telemetry.c + .\src\telemetry_frsky.c utils.c diff --git a/src/telemetry.c b/src/telemetry_frsky.c similarity index 100% rename from src/telemetry.c rename to src/telemetry_frsky.c From 6f0a419bf63756a4f1104aeb45c5f1dfaed34470 Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Sun, 6 Apr 2014 22:14:40 +0100 Subject: [PATCH 02/24] Cleanup telemetry code. Remove duplicate logic. Improve readability. Add support for another provider. Change default softserial baud rate to match the speed used by FrSky telemetry. --- src/board.h | 8 ++- src/cli.c | 3 +- src/config.c | 7 ++- src/mw.h | 1 + src/telemetry_frsky.c | 136 ++++++++++++++++++++++++++++-------------- 5 files changed, 106 insertions(+), 49 deletions(-) diff --git a/src/board.h b/src/board.h index f514838c4f..36ed2c90e6 100755 --- a/src/board.h +++ b/src/board.h @@ -92,9 +92,15 @@ typedef enum { GPS_MAG_BINARY, } GPSHardware; + +typedef enum { + TELEMETRY_PROVIDER_FRSKY = 0 +} TelemetryProvider; + typedef enum { TELEMETRY_UART = 0, - TELEMETRY_SOFTSERIAL, + TELEMETRY_SOFTSERIAL_1, + TELEMETRY_SOFTSERIAL_2, } TelemetrySerial; typedef enum { diff --git a/src/cli.c b/src/cli.c index b3a1606710..b1315fa0b7 100644 --- a/src/cli.c +++ b/src/cli.c @@ -51,7 +51,7 @@ static const char * const mixerNames[] = { static const char * const featureNames[] = { "PPM", "VBAT", "INFLIGHT_ACC_CAL", "SERIALRX", "MOTOR_STOP", "SERVO_TILT", "SOFTSERIAL", "LED_RING", "GPS", - "FAILSAFE", "SONAR", "TELEMETRY", "POWERMETER", "VARIO", "3D", + "FAILSAFE", "SONAR", "TELEMETRY", "POWERMETER", "VARIO", "3D", NULL }; @@ -133,6 +133,7 @@ const clivalue_t valueTable[] = { { "gps_type", VAR_UINT8, &mcfg.gps_type, 0, 3 }, { "gps_baudrate", VAR_INT8, &mcfg.gps_baudrate, 0, 4 }, { "serialrx_type", VAR_UINT8, &mcfg.serialrx_type, 0, 3 }, + { "telemetry_provider", VAR_UINT8, &mcfg.telemetry_provider, 0, 0 }, { "telemetry_softserial", VAR_UINT8, &mcfg.telemetry_softserial, 0, 1 }, { "telemetry_switch", VAR_UINT8, &mcfg.telemetry_switch, 0, 1 }, { "vbatscale", VAR_UINT8, &mcfg.vbatscale, 10, 200 }, diff --git a/src/config.c b/src/config.c index f566f2c2ce..e482f1b8e7 100755 --- a/src/config.c +++ b/src/config.c @@ -13,7 +13,7 @@ master_t mcfg; // master config struct with data independent from profiles config_t cfg; // profile config struct const char rcChannelLetters[] = "AERT1234"; -static const uint8_t EEPROM_CONF_VERSION = 60; +static const uint8_t EEPROM_CONF_VERSION = 61; static uint32_t enabledSensors = 0; static void resetConf(void); @@ -192,7 +192,8 @@ static void resetConf(void) mcfg.vbatmincellvoltage = 33; mcfg.power_adc_channel = 0; mcfg.serialrx_type = 0; - mcfg.telemetry_softserial = 0; + mcfg.telemetry_provider = TELEMETRY_PROVIDER_FRSKY; + mcfg.telemetry_softserial = TELEMETRY_UART; mcfg.telemetry_switch = 0; mcfg.midrc = 1500; mcfg.mincheck = 1100; @@ -215,7 +216,7 @@ static void resetConf(void) mcfg.gps_baudrate = 0; // serial (USART1) baudrate mcfg.serial_baudrate = 115200; - mcfg.softserial_baudrate = 19200; + mcfg.softserial_baudrate = 9600; mcfg.softserial_1_inverted = 0; mcfg.softserial_2_inverted = 0; mcfg.looptime = 3500; diff --git a/src/mw.h b/src/mw.h index e6ec6ea791..9fd5e2c846 100755 --- a/src/mw.h +++ b/src/mw.h @@ -280,6 +280,7 @@ typedef struct master_t { uint8_t softserial_1_inverted; // use inverted softserial input and output signals on port 1 uint8_t softserial_2_inverted; // use inverted softserial input and output signals on port 2 + uint8_t telemetry_provider; // Telemetry provider. 0:FRSKY uint8_t telemetry_softserial; // Serial to use for Telemetry. 0:USART1, 1:SoftSerial1 (Enable FEATURE_SOFTSERIAL first) uint8_t telemetry_switch; // Use aux channel to change serial output & baudrate( MSP / Telemetry ). It disables automatic switching to Telemetry when armed. config_t profile[3]; // 3 separate profiles diff --git a/src/telemetry_frsky.c b/src/telemetry_frsky.c index 2be8629072..54c93b2587 100644 --- a/src/telemetry_frsky.c +++ b/src/telemetry_frsky.c @@ -220,75 +220,123 @@ void initTelemetry(void) if (!feature(FEATURE_SOFTSERIAL)) mcfg.telemetry_softserial = TELEMETRY_UART; - if (mcfg.telemetry_softserial == TELEMETRY_SOFTSERIAL) + if (mcfg.telemetry_softserial == TELEMETRY_SOFTSERIAL_1) core.telemport = &(softSerialPorts[0].port); + else if (mcfg.telemetry_softserial == TELEMETRY_SOFTSERIAL_2) + core.telemport = &(softSerialPorts[1].port); else core.telemport = core.mainport; } +bool isTelemetryEnabled() +{ + bool telemetryCurrentlyEnabled = true; + + if (mcfg.telemetry_softserial == TELEMETRY_UART) { + if (!mcfg.telemetry_switch) + telemetryCurrentlyEnabled = f.ARMED; + else + telemetryCurrentlyEnabled = rcOptions[BOXTELEMETRY]; + } + + return telemetryCurrentlyEnabled; +} + +bool shouldChangeTelemetryStateNow(bool telemetryCurrentlyEnabled) +{ + return telemetryCurrentlyEnabled != telemetryEnabled; +} + void updateTelemetryState(void) { - bool State; - if (!mcfg.telemetry_switch) - State = mcfg.telemetry_softserial != TELEMETRY_UART ? true : f.ARMED; - else - State = mcfg.telemetry_softserial != TELEMETRY_UART ? true : rcOptions[BOXTELEMETRY]; + bool telemetryCurrentlyEnabled = isTelemetryEnabled(); - if (State != telemetryEnabled) { - if (mcfg.telemetry_softserial == TELEMETRY_UART) { - if (State) - serialInit(9600); - else - serialInit(mcfg.serial_baudrate); - } - telemetryEnabled = State; + if (!shouldChangeTelemetryStateNow(telemetryCurrentlyEnabled)) { + return; } + + if (mcfg.telemetry_softserial == TELEMETRY_UART && mcfg.telemetry_provider == TELEMETRY_PROVIDER_FRSKY) { + if (telemetryCurrentlyEnabled) + serialInit(9600); + else + serialInit(mcfg.serial_baudrate); + } + telemetryEnabled = telemetryCurrentlyEnabled; } static uint32_t lastCycleTime = 0; static uint8_t cycleNum = 0; -void sendTelemetry(void) +bool canSendFrSkyTelemetry(void) { - if (mcfg.telemetry_softserial == TELEMETRY_UART && ((!f.ARMED && !mcfg.telemetry_switch) || (mcfg.telemetry_switch && !rcOptions[BOXTELEMETRY]))) + return serialTotalBytesWaiting(core.telemport) == 0; +} + +bool hasEnoughTimeLapsedSinceLastTelemetryTransmission(uint32_t currentMillis) +{ + return currentMillis - lastCycleTime >= CYCLETIME; +} + +void sendFrSkyTelemetry(void) +{ + if (!canSendFrSkyTelemetry()) { return; + } - if (serialTotalBytesWaiting(core.telemport) != 0) + uint32_t now = millis(); + + if (!hasEnoughTimeLapsedSinceLastTelemetryTransmission(now)) { return; + } - if (millis() - lastCycleTime >= CYCLETIME) { - lastCycleTime = millis(); - cycleNum++; + lastCycleTime = now; - // Sent every 125ms - sendAccel(); - sendVario(); + cycleNum++; + + // Sent every 125ms + sendAccel(); + sendVario(); + sendTelemetryTail(); + + if ((cycleNum % 4) == 0) { // Sent every 500ms + sendBaro(); + sendHeading(); sendTelemetryTail(); + } - if ((cycleNum % 4) == 0) { // Sent every 500ms - sendBaro(); - sendHeading(); - sendTelemetryTail(); + if ((cycleNum % 8) == 0) { // Sent every 1s + sendTemperature1(); + + if (feature(FEATURE_VBAT)) { + sendVoltage(); + sendVoltageAmp(); } - if ((cycleNum % 8) == 0) { // Sent every 1s - sendTemperature1(); + if (sensors(SENSOR_GPS)) + sendGPS(); - if (feature(FEATURE_VBAT)) { - sendVoltage(); - sendVoltageAmp(); - } + sendTelemetryTail(); + } - if (sensors(SENSOR_GPS)) - sendGPS(); - - sendTelemetryTail(); - } - - if (cycleNum == 40) { //Frame 3: Sent every 5s - cycleNum = 0; - sendTime(); - sendTelemetryTail(); - } + if (cycleNum == 40) { //Frame 3: Sent every 5s + cycleNum = 0; + sendTime(); + sendTelemetryTail(); } } + +bool isFrSkyTelemetryEnabled(void) +{ + return mcfg.telemetry_provider == TELEMETRY_PROVIDER_FRSKY; +} + +void sendTelemetry(void) +{ + if (!isTelemetryEnabled()) + return; + + if (isFrSkyTelemetryEnabled()) { + sendFrSkyTelemetry(); + } +} + From d73094396d89a267c6cdabe186f4c344fccb068a Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Sun, 6 Apr 2014 22:33:18 +0100 Subject: [PATCH 03/24] Allow user to use telemetry on softserial port 2. Should have been in previous commit. --- src/cli.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/cli.c b/src/cli.c index b1315fa0b7..4d34bde504 100644 --- a/src/cli.c +++ b/src/cli.c @@ -134,7 +134,7 @@ const clivalue_t valueTable[] = { { "gps_baudrate", VAR_INT8, &mcfg.gps_baudrate, 0, 4 }, { "serialrx_type", VAR_UINT8, &mcfg.serialrx_type, 0, 3 }, { "telemetry_provider", VAR_UINT8, &mcfg.telemetry_provider, 0, 0 }, - { "telemetry_softserial", VAR_UINT8, &mcfg.telemetry_softserial, 0, 1 }, + { "telemetry_softserial", VAR_UINT8, &mcfg.telemetry_softserial, 0, 2 }, { "telemetry_switch", VAR_UINT8, &mcfg.telemetry_switch, 0, 1 }, { "vbatscale", VAR_UINT8, &mcfg.vbatscale, 10, 200 }, { "vbatmaxcellvoltage", VAR_UINT8, &mcfg.vbatmaxcellvoltage, 10, 50 }, From 1cbe166c497959fb917e8e3f6aef5efeab7e5d36 Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Sun, 6 Apr 2014 23:07:58 +0100 Subject: [PATCH 04/24] Move common telemetry code to telemetry_common.c/.h --- Makefile | 1 + src/main.c | 2 ++ src/mw.c | 2 ++ src/mw.h | 4 --- src/serial.c | 2 ++ src/telemetry_common.c | 51 ++++++++++++++++++++++++++++++++++ src/telemetry_common.h | 17 ++++++++++++ src/telemetry_frsky.c | 62 ++++++++---------------------------------- src/telemetry_frsky.h | 14 ++++++++++ 9 files changed, 100 insertions(+), 55 deletions(-) create mode 100644 src/telemetry_common.c create mode 100644 src/telemetry_common.h create mode 100644 src/telemetry_frsky.h diff --git a/Makefile b/Makefile index 04055fe83d..9e50b1ca81 100644 --- a/Makefile +++ b/Makefile @@ -55,6 +55,7 @@ COMMON_SRC = startup_stm32f10x_md_gcc.S \ sbus.c \ sumd.c \ spektrum.c \ + telemetry_common.c \ telemetry_frsky.c \ drv_gpio.c \ drv_i2c.c \ diff --git a/src/main.c b/src/main.c index 24907b2d1a..86f18bdfac 100755 --- a/src/main.c +++ b/src/main.c @@ -1,6 +1,8 @@ #include "board.h" #include "mw.h" +#include "telemetry_common.h" + core_t core; extern rcReadRawDataPtr rcReadRawFunc; diff --git a/src/mw.c b/src/mw.c index 026ad7e319..a4bcda0374 100755 --- a/src/mw.c +++ b/src/mw.c @@ -1,6 +1,8 @@ #include "board.h" #include "mw.h" +#include "telemetry_common.h" + // June 2013 V2.2-dev flags_t f; diff --git a/src/mw.h b/src/mw.h index 9fd5e2c846..e713477066 100755 --- a/src/mw.h +++ b/src/mw.h @@ -477,7 +477,3 @@ void GPS_reset_nav(void); void GPS_set_next_wp(int32_t* lat, int32_t* lon); int32_t wrap_18000(int32_t error); -// telemetry -void initTelemetry(void); -void updateTelemetryState(void); -void sendTelemetry(void); diff --git a/src/serial.c b/src/serial.c index 8a3bba559d..ae359c065e 100755 --- a/src/serial.c +++ b/src/serial.c @@ -1,6 +1,8 @@ #include "board.h" #include "mw.h" +#include "telemetry_common.h" + // Multiwii Serial Protocol 0 #define MSP_VERSION 0 #define CAP_PLATFORM_32BIT ((uint32_t)1 << 31) diff --git a/src/telemetry_common.c b/src/telemetry_common.c new file mode 100644 index 0000000000..79398530bb --- /dev/null +++ b/src/telemetry_common.c @@ -0,0 +1,51 @@ +#include "board.h" +#include "mw.h" + +#include "telemetry_frsky.h" + +void initTelemetry(void) +{ + // Sanity check for softserial vs. telemetry port + if (!feature(FEATURE_SOFTSERIAL)) + mcfg.telemetry_softserial = TELEMETRY_UART; + + if (mcfg.telemetry_softserial == TELEMETRY_SOFTSERIAL_1) + core.telemport = &(softSerialPorts[0].port); + else if (mcfg.telemetry_softserial == TELEMETRY_SOFTSERIAL_2) + core.telemport = &(softSerialPorts[1].port); + else + core.telemport = core.mainport; +} + +void updateTelemetryState(void) { + updateFrSkyTelemetryState(); +} + +bool isTelemetryEnabled(void) +{ + bool telemetryCurrentlyEnabled = true; + + if (mcfg.telemetry_softserial == TELEMETRY_UART) { + if (!mcfg.telemetry_switch) + telemetryCurrentlyEnabled = f.ARMED; + else + telemetryCurrentlyEnabled = rcOptions[BOXTELEMETRY]; + } + + return telemetryCurrentlyEnabled; +} + +bool isFrSkyTelemetryEnabled(void) +{ + return mcfg.telemetry_provider == TELEMETRY_PROVIDER_FRSKY; +} + +void sendTelemetry(void) +{ + if (!isTelemetryEnabled()) + return; + + if (isFrSkyTelemetryEnabled()) { + sendFrSkyTelemetry(); + } +} diff --git a/src/telemetry_common.h b/src/telemetry_common.h new file mode 100644 index 0000000000..9a41299688 --- /dev/null +++ b/src/telemetry_common.h @@ -0,0 +1,17 @@ +/* + * telemetry_common.h + * + * Created on: 6 Apr 2014 + * Author: Hydra + */ + +#ifndef TELEMETRY_COMMON_H_ +#define TELEMETRY_COMMON_H_ + +// telemetry +void initTelemetry(void); +void updateTelemetryState(void); +void sendTelemetry(void); +bool isTelemetryEnabled(void); + +#endif /* TELEMETRY_COMMON_H_ */ diff --git a/src/telemetry_frsky.c b/src/telemetry_frsky.c index 54c93b2587..ade5fdb133 100644 --- a/src/telemetry_frsky.c +++ b/src/telemetry_frsky.c @@ -4,6 +4,9 @@ #include "board.h" #include "mw.h" +#include "telemetry_common.h" +#include "telemetry_frsky.h" + #define CYCLETIME 125 #define PROTOCOL_HEADER 0x5E @@ -212,56 +215,28 @@ static void sendHeading(void) serialize16(0); } -static bool telemetryEnabled = false; +static bool frSkyTelemetryEnabled = false; -void initTelemetry(void) +bool shouldChangeTelemetryStateNow(bool frSkyTelemetryCurrentlyEnabled) { - // Sanity check for softserial vs. telemetry port - if (!feature(FEATURE_SOFTSERIAL)) - mcfg.telemetry_softserial = TELEMETRY_UART; - - if (mcfg.telemetry_softserial == TELEMETRY_SOFTSERIAL_1) - core.telemport = &(softSerialPorts[0].port); - else if (mcfg.telemetry_softserial == TELEMETRY_SOFTSERIAL_2) - core.telemport = &(softSerialPorts[1].port); - else - core.telemport = core.mainport; + return frSkyTelemetryCurrentlyEnabled != frSkyTelemetryEnabled; } -bool isTelemetryEnabled() +void updateFrSkyTelemetryState(void) { - bool telemetryCurrentlyEnabled = true; + bool frSkyTelemetryCurrentlyEnabled = isTelemetryEnabled(); - if (mcfg.telemetry_softserial == TELEMETRY_UART) { - if (!mcfg.telemetry_switch) - telemetryCurrentlyEnabled = f.ARMED; - else - telemetryCurrentlyEnabled = rcOptions[BOXTELEMETRY]; - } - - return telemetryCurrentlyEnabled; -} - -bool shouldChangeTelemetryStateNow(bool telemetryCurrentlyEnabled) -{ - return telemetryCurrentlyEnabled != telemetryEnabled; -} - -void updateTelemetryState(void) -{ - bool telemetryCurrentlyEnabled = isTelemetryEnabled(); - - if (!shouldChangeTelemetryStateNow(telemetryCurrentlyEnabled)) { + if (!shouldChangeTelemetryStateNow(frSkyTelemetryCurrentlyEnabled)) { return; } if (mcfg.telemetry_softserial == TELEMETRY_UART && mcfg.telemetry_provider == TELEMETRY_PROVIDER_FRSKY) { - if (telemetryCurrentlyEnabled) + if (frSkyTelemetryCurrentlyEnabled) serialInit(9600); else serialInit(mcfg.serial_baudrate); } - telemetryEnabled = telemetryCurrentlyEnabled; + frSkyTelemetryEnabled = frSkyTelemetryCurrentlyEnabled; } static uint32_t lastCycleTime = 0; @@ -325,18 +300,3 @@ void sendFrSkyTelemetry(void) } } -bool isFrSkyTelemetryEnabled(void) -{ - return mcfg.telemetry_provider == TELEMETRY_PROVIDER_FRSKY; -} - -void sendTelemetry(void) -{ - if (!isTelemetryEnabled()) - return; - - if (isFrSkyTelemetryEnabled()) { - sendFrSkyTelemetry(); - } -} - diff --git a/src/telemetry_frsky.h b/src/telemetry_frsky.h new file mode 100644 index 0000000000..343b09be9c --- /dev/null +++ b/src/telemetry_frsky.h @@ -0,0 +1,14 @@ +/* + * telemetry_frsky.h + * + * Created on: 6 Apr 2014 + * Author: Hydra + */ + +#ifndef TELEMETRY_FRSKY_H_ +#define TELEMETRY_FRSKY_H_ + +void sendFrSkyTelemetry(void); +void updateFrSkyTelemetryState(void); + +#endif /* TELEMETRY_FRSKY_H_ */ From 08ee21cd580ee6cdc568fdc2364de365a458adff Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Sun, 6 Apr 2014 23:15:03 +0100 Subject: [PATCH 05/24] Removed unused variables. Compiler warning were generated when compiling using GCC with -Wunused-variable --- src/gps.c | 14 -------------- 1 file changed, 14 deletions(-) diff --git a/src/gps.c b/src/gps.c index 8a0b6d1a7b..2c864f3e4a 100644 --- a/src/gps.c +++ b/src/gps.c @@ -41,20 +41,6 @@ static const uint8_t ubloxInit[] = { 0xB5, 0x62, 0x06, 0x08, 0x06, 0x00, 0xC8, 0x00, 0x01, 0x00, 0x01, 0x00, 0xDE, 0x6A, // set rate to 5Hz }; -static const char *mtkNMEAInit[] = { - "$PMTK314,0,1,0,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0*28\r\n", // only GGA and RMC sentence - "$PMTK220,200*2C\r\n" // 5 Hz update rate -}; - -static const char *mtkBinaryInit[] = { - "$PMTK319,1*24\r\n", // SBAS Integrity Mode - "$PMTK220,200*2C\r\n", // 5 Hz update rate - "$PMTK397,0*23\r\n", // NAVTHRES_OFF - "$PMTK313,1*2E\r\n", // SBAS_ON - "$PMTK301,2*2E\r\n", // WAAS_ON - "$PGCMD,16,0,0,0,0,0*6A\r\n" // Binary ON -}; - enum { GPS_UNKNOWN, GPS_INITIALIZING, From 3ca868a59fc87558400a13f59e6d29ca855437d1 Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Sun, 6 Apr 2014 23:34:37 +0100 Subject: [PATCH 06/24] Enable HoTT as a telemetry provider. Import cGiensen's HoTT telemetry implementation - untested. --- Makefile | 1 + src/board.h | 3 +- src/cli.c | 5 +- src/cli.h | 13 +++ src/mixer.c | 2 - src/mw.c | 5 + src/serial.c | 6 +- src/telemetry_common.c | 14 ++- src/telemetry_common.h | 2 +- src/telemetry_frsky.c | 2 +- src/telemetry_frsky.h | 2 +- src/telemetry_hott.c | 254 +++++++++++++++++++++++++++++++++++++++++ src/telemetry_hott.h | 204 +++++++++++++++++++++++++++++++++ 13 files changed, 499 insertions(+), 14 deletions(-) create mode 100644 src/cli.h create mode 100644 src/telemetry_hott.c create mode 100644 src/telemetry_hott.h diff --git a/Makefile b/Makefile index 9e50b1ca81..2cee3893df 100644 --- a/Makefile +++ b/Makefile @@ -57,6 +57,7 @@ COMMON_SRC = startup_stm32f10x_md_gcc.S \ spektrum.c \ telemetry_common.c \ telemetry_frsky.c \ + telemetry_hott.c \ drv_gpio.c \ drv_i2c.c \ drv_i2c_soft.c \ diff --git a/src/board.h b/src/board.h index 36ed2c90e6..77a84e7162 100755 --- a/src/board.h +++ b/src/board.h @@ -94,7 +94,8 @@ typedef enum { typedef enum { - TELEMETRY_PROVIDER_FRSKY = 0 + TELEMETRY_PROVIDER_FRSKY = 0, + TELEMETRY_PROVIDER_HOTT } TelemetryProvider; typedef enum { diff --git a/src/cli.c b/src/cli.c index 4d34bde504..4dd8f6311f 100644 --- a/src/cli.c +++ b/src/cli.c @@ -30,6 +30,9 @@ extern const char rcChannelLetters[]; // from mixer.c extern int16_t motor_disarmed[MAX_MOTORS]; +// signal that we're in cli mode +uint8_t cliMode = 0; + // buffer static char cliBuffer[48]; static uint32_t bufferIndex = 0; @@ -133,7 +136,7 @@ const clivalue_t valueTable[] = { { "gps_type", VAR_UINT8, &mcfg.gps_type, 0, 3 }, { "gps_baudrate", VAR_INT8, &mcfg.gps_baudrate, 0, 4 }, { "serialrx_type", VAR_UINT8, &mcfg.serialrx_type, 0, 3 }, - { "telemetry_provider", VAR_UINT8, &mcfg.telemetry_provider, 0, 0 }, + { "telemetry_provider", VAR_UINT8, &mcfg.telemetry_provider, 0, 1 }, { "telemetry_softserial", VAR_UINT8, &mcfg.telemetry_softserial, 0, 2 }, { "telemetry_switch", VAR_UINT8, &mcfg.telemetry_switch, 0, 1 }, { "vbatscale", VAR_UINT8, &mcfg.vbatscale, 10, 200 }, diff --git a/src/cli.h b/src/cli.h new file mode 100644 index 0000000000..f21bceb439 --- /dev/null +++ b/src/cli.h @@ -0,0 +1,13 @@ +/* + * cli.h + * + * Created on: 6 Apr 2014 + * Author: Hydra + */ + +#ifndef CLI_H_ +#define CLI_H_ + +extern uint8_t cliMode; + +#endif /* CLI_H_ */ diff --git a/src/mixer.c b/src/mixer.c index 364a1e2ae0..d982c8e4dd 100755 --- a/src/mixer.c +++ b/src/mixer.c @@ -304,8 +304,6 @@ void writeServos(void) } } -extern uint8_t cliMode; - void writeMotors(void) { uint8_t i; diff --git a/src/mw.c b/src/mw.c index a4bcda0374..7214c36abc 100755 --- a/src/mw.c +++ b/src/mw.c @@ -1,6 +1,7 @@ #include "board.h" #include "mw.h" +#include "cli.h" #include "telemetry_common.h" // June 2013 V2.2-dev @@ -206,6 +207,10 @@ void annexCode(void) serialCom(); + if (!cliMode && feature(FEATURE_TELEMETRY)) { + handleTelemetry(); + } + if (sensors(SENSOR_GPS)) { static uint32_t GPSLEDTime; if ((int32_t)(currentTime - GPSLEDTime) >= 0 && (GPS_numSat >= 5)) { diff --git a/src/serial.c b/src/serial.c index ae359c065e..719ffe93af 100755 --- a/src/serial.c +++ b/src/serial.c @@ -1,6 +1,7 @@ #include "board.h" #include "mw.h" +#include "cli.h" #include "telemetry_common.h" // Multiwii Serial Protocol 0 @@ -114,8 +115,6 @@ static const char pidnames[] = static uint8_t checksum, indRX, inBuf[INBUF_SIZE]; static uint8_t cmdMSP; -// signal that we're in cli mode -uint8_t cliMode = 0; void serialize32(uint32_t a) { @@ -696,7 +695,4 @@ void serialCom(void) c_state = IDLE; } } - if (!cliMode && feature(FEATURE_TELEMETRY)) { // The first condition should never evaluate to true but I'm putting it here anyway - silpstream - sendTelemetry(); - } } diff --git a/src/telemetry_common.c b/src/telemetry_common.c index 79398530bb..828fff630b 100644 --- a/src/telemetry_common.c +++ b/src/telemetry_common.c @@ -2,6 +2,7 @@ #include "mw.h" #include "telemetry_frsky.h" +#include "telemetry_hott.h" void initTelemetry(void) { @@ -40,12 +41,21 @@ bool isFrSkyTelemetryEnabled(void) return mcfg.telemetry_provider == TELEMETRY_PROVIDER_FRSKY; } -void sendTelemetry(void) +bool isHoTTTelemetryEnabled(void) +{ + return mcfg.telemetry_provider == TELEMETRY_PROVIDER_HOTT; +} + +void handleTelemetry(void) { if (!isTelemetryEnabled()) return; if (isFrSkyTelemetryEnabled()) { - sendFrSkyTelemetry(); + handleFrSkyTelemetry(); + } + + if (isHoTTTelemetryEnabled()) { + handleHoTTTelemetry(); } } diff --git a/src/telemetry_common.h b/src/telemetry_common.h index 9a41299688..defd43320a 100644 --- a/src/telemetry_common.h +++ b/src/telemetry_common.h @@ -11,7 +11,7 @@ // telemetry void initTelemetry(void); void updateTelemetryState(void); -void sendTelemetry(void); +void handleTelemetry(void); bool isTelemetryEnabled(void); #endif /* TELEMETRY_COMMON_H_ */ diff --git a/src/telemetry_frsky.c b/src/telemetry_frsky.c index ade5fdb133..e0724dcdd5 100644 --- a/src/telemetry_frsky.c +++ b/src/telemetry_frsky.c @@ -252,7 +252,7 @@ bool hasEnoughTimeLapsedSinceLastTelemetryTransmission(uint32_t currentMillis) return currentMillis - lastCycleTime >= CYCLETIME; } -void sendFrSkyTelemetry(void) +void handleFrSkyTelemetry(void) { if (!canSendFrSkyTelemetry()) { return; diff --git a/src/telemetry_frsky.h b/src/telemetry_frsky.h index 343b09be9c..550b929324 100644 --- a/src/telemetry_frsky.h +++ b/src/telemetry_frsky.h @@ -8,7 +8,7 @@ #ifndef TELEMETRY_FRSKY_H_ #define TELEMETRY_FRSKY_H_ -void sendFrSkyTelemetry(void); +void handleFrSkyTelemetry(void); void updateFrSkyTelemetryState(void); #endif /* TELEMETRY_FRSKY_H_ */ diff --git a/src/telemetry_hott.c b/src/telemetry_hott.c new file mode 100644 index 0000000000..78f4c0e6a1 --- /dev/null +++ b/src/telemetry_hott.c @@ -0,0 +1,254 @@ +/* + * telemetry_hott.c + * + * Created on: 6 Apr 2014 + * Author: Hydra/cGiesen + */ + +#include "board.h" +#include "mw.h" + +#include "telemetry_hott.h" + + +const uint8_t kHoTTv4BinaryPacketSize = 45; +const uint8_t kHoTTv4TextPacketSize = 173; + +static uint8_t outBuffer[173]; +static void hottV4SerialWrite(uint8_t c); +static inline void hottV4EnableReceiverMode(void); +static inline void hottV4EnableTransmitterMode(void); + +static void hottV4SendData(uint8_t *data, uint8_t size); +static void hottV4SendGPS(void); +static void hottV4GPSUpdate(void); +static void hottV4SendEAM(void); +static void hottV4EAMUpdateBattery(void); +static void hottV4EAMUpdateTemperatures(void); +bool batteryWarning; + +/* + * Sends HoTTv4 capable GPS telemetry frame. + */ + +void hottV4SendGPS(void) +{ + /** 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(); + + // Clear output buffer + memset(&outBuffer, 0, sizeof(outBuffer)); + + // Copy EAM data to output buffer + memcpy(&outBuffer, &HoTTV4GPSModule, kHoTTv4BinaryPacketSize); + + // Send data from output buffer + hottV4SendData(outBuffer, kHoTTv4BinaryPacketSize); + } + +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 + } + } + + /** + * Writes cell 1-4 high, low values and if not available + * calculates vbat. + */ + static void hottV4EAMUpdateBattery() { +// HoTTV4ElectricAirModule.cell1L = 0; +// HoTTV4ElectricAirModule.cell1H = 0; + +// HoTTV4ElectricAirModule.cell2L = 0; +// HoTTV4ElectricAirModule.cell2H = 0; + +// HoTTV4ElectricAirModule.cell3L = 0; +// HoTTV4ElectricAirModule.cell3H = 0; + +// HoTTV4ElectricAirModule.cell4L = 0; +// HoTTV4ElectricAirModule.cell4H = 0; + + HoTTV4ElectricAirModule.driveVoltageLow = vbat & 0xFF; + HoTTV4ElectricAirModule.driveVoltageHigh = vbat >> 8; + HoTTV4ElectricAirModule.battery1Low = vbat & 0xFF; + HoTTV4ElectricAirModule.battery1High = vbat >> 8; + +// HoTTV4ElectricAirModule.battery2Low = 0 & 0xFF; +// HoTTV4ElectricAirModule.battery2High = 0 >> 8; + + if (batteryWarning) { + HoTTV4ElectricAirModule.alarmTone = HoTTv4NotificationUndervoltage; + HoTTV4ElectricAirModule.alarmInverse1 |= 0x80; // Invert Voltage display + } + } + + static void hottV4EAMUpdateTemperatures() { + HoTTV4ElectricAirModule.temp1 = 20 + 0; + HoTTV4ElectricAirModule.temp2 = 20; + + //if (HoTTV4ElectricAirModule.temp1 >= (20 + MultiHoTTModuleSettings.alarmTemp1)) { + // HoTTV4ElectricAirModule.alarmTone = HoTTv4NotificationMaxTemperature; + // HoTTV4ElectricAirModule.alarmInverse |= 0x8; // Invert Temp1 display + //} + } + + +/** + * Sends HoTTv4 capable EAM telemetry frame. + */ +void hottV4SendEAM(void) { + /** 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; + + hottV4EAMUpdateBattery(); + hottV4EAMUpdateTemperatures(); + + HoTTV4ElectricAirModule.current = 0 / 10; + HoTTV4ElectricAirModule.height = OFFSET_HEIGHT + 0; + HoTTV4ElectricAirModule.m2s = OFFSET_M2S; + HoTTV4ElectricAirModule.m3s = OFFSET_M3S; + + // Clear output buffer + memset(&outBuffer, 0, sizeof(outBuffer)); + + // Copy EAM data to output buffer + memcpy(&outBuffer, &HoTTV4ElectricAirModule, kHoTTv4BinaryPacketSize); + + // Send data from output buffer + hottV4SendData(outBuffer, kHoTTv4BinaryPacketSize); +} + +/** + * Expects an array of at least size bytes. All bytes till size will be transmitted + * to the HoTT capable receiver. Last byte will always be treated as checksum and is + * calculated on the fly. + */ +static void hottV4SendData(uint8_t *data, uint8_t size) { + //hottV4Serial.flush(); + + // Protocoll specific waiting time + // to avoid collisions + delay(5); + + if (serialTotalBytesWaiting(core.telemport) == 0) { + hottV4EnableTransmitterMode(); + + uint16_t crc = 0; + uint8_t i; + + for (i = 0; i < (size - 1); i++) { + crc += data[i]; + hottV4SerialWrite(data[i]); + + // Protocoll specific delay between each transmitted byte + delayMicroseconds(HOTTV4_TX_DELAY); + } + + // Write package checksum + hottV4SerialWrite(crc & 0xFF); + + hottV4EnableReceiverMode(); + } +} + +/** + * Writes out given byte to HoTT serial interface. + * If in debug mode, data is also written to UART serial interface. + */ +static void hottV4SerialWrite(uint8_t c) { + //hottV4Serial.write(c); + serialWrite(core.telemport, c); +} + +/** + * Enables RX and disables TX + */ +static inline void hottV4EnableReceiverMode() { + //DDRD &= ~(1 << HOTTV4_RXTX); + //PORTD |= (1 << HOTTV4_RXTX); +} + +/** + * Enabels TX and disables RX + */ +static inline void hottV4EnableTransmitterMode() { + //DDRD |= (1 << HOTTV4_RXTX); +} + +void handleHoTTTelemetry(void) +{ + while (serialTotalBytesWaiting(core.telemport)) { + uint8_t c = serialRead(core.telemport); + switch (c) { + case 0x8A: + if (sensors(SENSOR_GPS)) hottV4SendGPS(); + break; + case 0x8E: + hottV4SendEAM(); + break; + } + } +} + + diff --git a/src/telemetry_hott.h b/src/telemetry_hott.h new file mode 100644 index 0000000000..21c6956bc8 --- /dev/null +++ b/src/telemetry_hott.h @@ -0,0 +1,204 @@ +/* + * telemetry_hott.h + * + * Created on: 6 Apr 2014 + * Author: Hydra + */ + +#ifndef TELEMETRY_HOTT_H_ +#define TELEMETRY_HOTT_H_ + +/* ###### HoTT module specifications ###### */ + +#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_TX_DELAY 1000 + +#define HOTTV4_BUTTON_DEC 0xEB +#define HOTTV4_BUTTON_INC 0xED +#define HOTTV4_BUTTON_SET 0xE9 +#define HOTTV4_BUTTON_NIL 0x0F +#define HOTTV4_BUTTON_NEXT 0xEE +#define HOTTV4_BUTTON_PREV 0xE7 + +#define OFFSET_HEIGHT 500 +#define OFFSET_M2S 72 +#define OFFSET_M3S 120 + +typedef enum { + HoTTv4NotificationErrorCalibration = 0x01, + HoTTv4NotificationErrorReceiver = 0x02, + HoTTv4NotificationErrorDataBus = 0x03, + HoTTv4NotificationErrorNavigation = 0x04, + HoTTv4NotificationErrorError = 0x05, + HoTTv4NotificationErrorCompass = 0x06, + HoTTv4NotificationErrorSensor = 0x07, + HoTTv4NotificationErrorGPS = 0x08, + HoTTv4NotificationErrorMotor = 0x09, + + 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, + + 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 +-----------------------------------------------------------*/ + +struct { + 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 + + // 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 + + // 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 + + 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 + uint8_t unknow1; // 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) + 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 + 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 Ende byte + uint8_t chksum; // Byte 45: Parity Byte +} HoTTV4GPSModule; + +/*----------------------------------------------------------- +EAM (Electric Air Module) 33620 +EmpfängerElectric Sensor +Byte 1: 80 = Receiver byte +Byte 2: 8E = Electric Sensor byte +5ms Idle Line! + *-----------------------------------------------------------*/ + +struct { + uint8_t startByte; + uint8_t sensorID; + uint8_t alarmTone; // Alarm */ + uint8_t sensorTextID; + uint8_t alarmInverse1; + uint8_t alarmInverse2; + + 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 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; + + 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 temp1; // Temp 1; 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 current; // 1 = 0.1A */ + uint8_t driveVoltageLow; + uint8_t driveVoltageHigh; + uint16_t capacity; // mAh */ + uint16_t m2s; // m2s; 0x48 == 0 */ + uint8_t m3s; // m3s; 0x78 == 0 */ + + uint16_t rpm; // RPM. 10er steps; 300 == 3000rpm */ + uint8_t minutes; + uint8_t seconds; + uint8_t speed; + + uint8_t version; + uint8_t endByte; + uint8_t chksum; +} HoTTV4ElectricAirModule; + +void handleHoTTTelemetry(void); + +#endif /* TELEMETRY_HOTT_H_ */ From f7c937a3238c374970640ced9561c951230386e1 Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Mon, 7 Apr 2014 00:16:26 +0100 Subject: [PATCH 07/24] Improve HoTT code readability. Add protocol overview comments. --- src/telemetry_hott.c | 71 ++++++++++++++++++++------------------------ 1 file changed, 32 insertions(+), 39 deletions(-) diff --git a/src/telemetry_hott.c b/src/telemetry_hott.c index 78f4c0e6a1..6c3ee44845 100644 --- a/src/telemetry_hott.c +++ b/src/telemetry_hott.c @@ -5,6 +5,19 @@ * Author: Hydra/cGiesen */ +/* + * HoTT is implemented in Graupner equipment using a bi-directional protocol over a single wire. + * + * Generally the receiver sends a single request byte out using normal uart signals, then waits a short period for a + * multiple byte response and checksum byte before it sends out the next request byte. + * Each response byte must be send with a protocol specific delay between them. + * + * Serial ports use two wires so connect the receiver's HoTT signal to a uart/softserial RX pin via a diode + * and then also connect a uart/softserial TX pin to the same HoTT pin on the receiver, but NOT via a diode. + * + * This is so that when baseflight transmits it does not receive it's own transmission. + */ + #include "board.h" #include "mw.h" @@ -16,13 +29,11 @@ const uint8_t kHoTTv4TextPacketSize = 173; static uint8_t outBuffer[173]; static void hottV4SerialWrite(uint8_t c); -static inline void hottV4EnableReceiverMode(void); -static inline void hottV4EnableTransmitterMode(void); -static void hottV4SendData(uint8_t *data, uint8_t size); -static void hottV4SendGPS(void); +static void hottV4Respond(uint8_t *data, uint8_t size); +static void hottV4FormatAndSendGPSResponse(void); static void hottV4GPSUpdate(void); -static void hottV4SendEAM(void); +static void hottV4FormatAndSendEAMResponse(void); static void hottV4EAMUpdateBattery(void); static void hottV4EAMUpdateTemperatures(void); bool batteryWarning; @@ -31,7 +42,7 @@ bool batteryWarning; * Sends HoTTv4 capable GPS telemetry frame. */ -void hottV4SendGPS(void) +void hottV4FormatAndSendGPSResponse(void) { /** Minimum data set for EAM */ HoTTV4GPSModule.startByte = 0x7C; @@ -53,7 +64,7 @@ void hottV4SendGPS(void) memcpy(&outBuffer, &HoTTV4GPSModule, kHoTTv4BinaryPacketSize); // Send data from output buffer - hottV4SendData(outBuffer, kHoTTv4BinaryPacketSize); + hottV4Respond(outBuffer, kHoTTv4BinaryPacketSize); } void hottV4GPSUpdate(void) @@ -149,7 +160,7 @@ void hottV4GPSUpdate(void) /** * Sends HoTTv4 capable EAM telemetry frame. */ -void hottV4SendEAM(void) { +void hottV4FormatAndSendEAMResponse(void) { /** Minimum data set for EAM */ HoTTV4ElectricAirModule.startByte = 0x7C; HoTTV4ElectricAirModule.sensorID = HOTTV4_ELECTRICAL_AIR_SENSOR_ID; @@ -176,7 +187,7 @@ void hottV4SendEAM(void) { memcpy(&outBuffer, &HoTTV4ElectricAirModule, kHoTTv4BinaryPacketSize); // Send data from output buffer - hottV4SendData(outBuffer, kHoTTv4BinaryPacketSize); + hottV4Respond(outBuffer, kHoTTv4BinaryPacketSize); } /** @@ -184,15 +195,11 @@ void hottV4SendEAM(void) { * to the HoTT capable receiver. Last byte will always be treated as checksum and is * calculated on the fly. */ -static void hottV4SendData(uint8_t *data, uint8_t size) { - //hottV4Serial.flush(); +static void hottV4Respond(uint8_t *data, uint8_t size) { - // Protocoll specific waiting time - // to avoid collisions - delay(5); - - if (serialTotalBytesWaiting(core.telemport) == 0) { - hottV4EnableTransmitterMode(); + if (serialTotalBytesWaiting(core.telemport) != 0 ) { + return; // cannot respond since another request came in. + } uint16_t crc = 0; uint8_t i; @@ -201,15 +208,12 @@ static void hottV4SendData(uint8_t *data, uint8_t size) { crc += data[i]; hottV4SerialWrite(data[i]); - // Protocoll specific delay between each transmitted byte + // Protocol specific delay between each transmitted byte delayMicroseconds(HOTTV4_TX_DELAY); } // Write package checksum hottV4SerialWrite(crc & 0xFF); - - hottV4EnableReceiverMode(); - } } /** @@ -217,35 +221,24 @@ static void hottV4SendData(uint8_t *data, uint8_t size) { * If in debug mode, data is also written to UART serial interface. */ static void hottV4SerialWrite(uint8_t c) { - //hottV4Serial.write(c); serialWrite(core.telemport, c); } -/** - * Enables RX and disables TX - */ -static inline void hottV4EnableReceiverMode() { - //DDRD &= ~(1 << HOTTV4_RXTX); - //PORTD |= (1 << HOTTV4_RXTX); -} - -/** - * Enabels TX and disables RX - */ -static inline void hottV4EnableTransmitterMode() { - //DDRD |= (1 << HOTTV4_RXTX); -} - void handleHoTTTelemetry(void) { while (serialTotalBytesWaiting(core.telemport)) { uint8_t c = serialRead(core.telemport); + + // Protocol specific waiting time + // to avoid collisions + delay(5); + switch (c) { case 0x8A: - if (sensors(SENSOR_GPS)) hottV4SendGPS(); + if (sensors(SENSOR_GPS)) hottV4FormatAndSendGPSResponse(); break; case 0x8E: - hottV4SendEAM(); + hottV4FormatAndSendEAMResponse(); break; } } From 3007d3cbdc91127285809cf376ce88b94622cb28 Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Mon, 7 Apr 2014 01:04:40 +0100 Subject: [PATCH 08/24] Improving code readability by aligning comments with code and removing comments that duplicated code. Comments are harder to refactor than code and become stale. Updating default and limit values for some settings to use enum values. --- src/board.h | 21 ++++++++++++++++----- src/cli.c | 8 ++++---- src/config.c | 4 ++-- src/gps.c | 20 +++++++++++--------- src/mw.h | 8 ++++---- src/telemetry_common.c | 8 ++++---- src/telemetry_frsky.c | 2 +- 7 files changed, 42 insertions(+), 29 deletions(-) diff --git a/src/board.h b/src/board.h index 77a84e7162..099e6620f9 100755 --- a/src/board.h +++ b/src/board.h @@ -90,19 +90,30 @@ typedef enum { GPS_MTK_NMEA, GPS_MTK_BINARY, GPS_MAG_BINARY, + GPS_HARDWARE_MAX = GPS_MAG_BINARY, } GPSHardware; +typedef enum { + GPS_BAUD_115200 = 0, + GPS_BAUD_57600, + GPS_BAUD_38400, + GPS_BAUD_19200, + GPS_BAUD_9600, + GPS_BAUD_MAX = GPS_BAUD_9600 +} GPSBaudRates; typedef enum { TELEMETRY_PROVIDER_FRSKY = 0, - TELEMETRY_PROVIDER_HOTT + TELEMETRY_PROVIDER_HOTT, + TELEMETRY_PROVIDER_MAX = TELEMETRY_PROVIDER_HOTT } TelemetryProvider; typedef enum { - TELEMETRY_UART = 0, - TELEMETRY_SOFTSERIAL_1, - TELEMETRY_SOFTSERIAL_2, -} TelemetrySerial; + TELEMETRY_PORT_UART = 0, + TELEMETRY_PORT_SOFTSERIAL_1, // Requires FEATURE_SOFTSERIAL + TELEMETRY_PORT_SOFTSERIAL_2, // Requires FEATURE_SOFTSERIAL + TELEMETRY_PORT_MAX = TELEMETRY_PORT_SOFTSERIAL_2 +} TelemetryPort; typedef enum { X = 0, diff --git a/src/cli.c b/src/cli.c index 4dd8f6311f..361b2115ab 100644 --- a/src/cli.c +++ b/src/cli.c @@ -133,11 +133,11 @@ const clivalue_t valueTable[] = { { "softserial_baudrate", VAR_UINT32, &mcfg.softserial_baudrate, 1200, 19200 }, { "softserial_1_inverted", VAR_UINT8, &mcfg.softserial_1_inverted, 0, 1 }, { "softserial_2_inverted", VAR_UINT8, &mcfg.softserial_2_inverted, 0, 1 }, - { "gps_type", VAR_UINT8, &mcfg.gps_type, 0, 3 }, - { "gps_baudrate", VAR_INT8, &mcfg.gps_baudrate, 0, 4 }, + { "gps_type", VAR_UINT8, &mcfg.gps_type, 0, GPS_HARDWARE_MAX }, + { "gps_baudrate", VAR_INT8, &mcfg.gps_baudrate, 0, GPS_BAUD_MAX }, { "serialrx_type", VAR_UINT8, &mcfg.serialrx_type, 0, 3 }, - { "telemetry_provider", VAR_UINT8, &mcfg.telemetry_provider, 0, 1 }, - { "telemetry_softserial", VAR_UINT8, &mcfg.telemetry_softserial, 0, 2 }, + { "telemetry_provider", VAR_UINT8, &mcfg.telemetry_provider, 0, TELEMETRY_PROVIDER_MAX }, + { "telemetry_port", VAR_UINT8, &mcfg.telemetry_port, 0, TELEMETRY_PORT_MAX }, { "telemetry_switch", VAR_UINT8, &mcfg.telemetry_switch, 0, 1 }, { "vbatscale", VAR_UINT8, &mcfg.vbatscale, 10, 200 }, { "vbatmaxcellvoltage", VAR_UINT8, &mcfg.vbatmaxcellvoltage, 10, 50 }, diff --git a/src/config.c b/src/config.c index e482f1b8e7..adfe278b41 100755 --- a/src/config.c +++ b/src/config.c @@ -193,7 +193,7 @@ static void resetConf(void) mcfg.power_adc_channel = 0; mcfg.serialrx_type = 0; mcfg.telemetry_provider = TELEMETRY_PROVIDER_FRSKY; - mcfg.telemetry_softserial = TELEMETRY_UART; + mcfg.telemetry_port = TELEMETRY_PORT_UART; mcfg.telemetry_switch = 0; mcfg.midrc = 1500; mcfg.mincheck = 1100; @@ -213,7 +213,7 @@ static void resetConf(void) mcfg.servo_pwm_rate = 50; // gps/nav stuff mcfg.gps_type = GPS_NMEA; - mcfg.gps_baudrate = 0; + mcfg.gps_baudrate = GPS_BAUD_115200; // serial (USART1) baudrate mcfg.serial_baudrate = 115200; mcfg.softserial_baudrate = 9600; diff --git a/src/gps.c b/src/gps.c index 2c864f3e4a..98b34d89e7 100644 --- a/src/gps.c +++ b/src/gps.c @@ -8,22 +8,24 @@ // GPS timeout for wrong baud rate/disconnection/etc in milliseconds (default 2.5second) #define GPS_TIMEOUT (2500) // How many entries in gpsInitData array below -#define GPS_INIT_ENTRIES (5) +#define GPS_INIT_ENTRIES (GPS_BAUD_MAX + 1) #define GPS_BAUD_DELAY (100) typedef struct gpsInitData_t { + uint8_t index; uint32_t baudrate; const char *ubx; const char *mtk; } gpsInitData_t; +// NMEA will cycle through these until valid data is received static const gpsInitData_t gpsInitData[] = { - { 115200, "$PUBX,41,1,0003,0001,115200,0*1E\r\n", "$PMTK251,115200*1F\r\n" }, - { 57600, "$PUBX,41,1,0003,0001,57600,0*2D\r\n", "$PMTK251,57600*2C\r\n" }, - { 38400, "$PUBX,41,1,0003,0001,38400,0*26\r\n", "$PMTK251,38400*27\r\n" }, - { 19200, "$PUBX,41,1,0003,0001,19200,0*23\r\n", "$PMTK251,19200*22\r\n" }, + { GPS_BAUD_115200, 115200, "$PUBX,41,1,0003,0001,115200,0*1E\r\n", "$PMTK251,115200*1F\r\n" }, + { GPS_BAUD_57600, 57600, "$PUBX,41,1,0003,0001,57600,0*2D\r\n", "$PMTK251,57600*2C\r\n" }, + { GPS_BAUD_38400, 38400, "$PUBX,41,1,0003,0001,38400,0*26\r\n", "$PMTK251,38400*27\r\n" }, + { GPS_BAUD_19200, 19200, "$PUBX,41,1,0003,0001,19200,0*23\r\n", "$PMTK251,19200*22\r\n" }, // 9600 is not enough for 5Hz updates - leave for compatibility to dumb NMEA that only runs at this speed - { 9600, "", "" } + { GPS_BAUD_9600, 9600, "", "" } }; static const uint8_t ubloxInit[] = { @@ -74,7 +76,7 @@ static void gpsSetState(uint8_t state) gpsData.state_ts = millis(); } -void gpsInit(uint8_t baudrate) +void gpsInit(uint8_t baudrateIndex) { portMode_t mode = MODE_RXTX; @@ -83,7 +85,7 @@ void gpsInit(uint8_t baudrate) if (!feature(FEATURE_GPS)) return; - gpsData.baudrateIndex = baudrate; + gpsData.baudrateIndex = baudrateIndex; gpsData.lastMessage = millis(); gpsData.errors = 0; // only RX is needed for NMEA-style GPS @@ -91,7 +93,7 @@ void gpsInit(uint8_t baudrate) mode = MODE_RX; gpsSetPIDs(); - core.gpsport = uartOpen(USART2, gpsNewData, gpsInitData[baudrate].baudrate, mode); + core.gpsport = uartOpen(USART2, gpsNewData, gpsInitData[baudrateIndex].baudrate, mode); // signal GPS "thread" to initialize when it gets to it gpsSetState(GPS_INITIALIZING); } diff --git a/src/mw.h b/src/mw.h index e713477066..5722259d51 100755 --- a/src/mw.h +++ b/src/mw.h @@ -271,8 +271,8 @@ typedef struct master_t { uint8_t rssi_aux_channel; // Read rssi from channel. 1+ = AUX1+, 0 to disable. // gps-related stuff - uint8_t gps_type; // Type of GPS hardware. 0: NMEA 1: UBX 2: MTK NMEA 3: MTK Binary - int8_t gps_baudrate; // GPS baudrate, 0: 115200, 1: 57600, 2: 38400, 3: 19200, 4: 9600. NMEA will cycle through these until valid data is received + uint8_t gps_type; // See GPSHardware enum. + int8_t gps_baudrate; // See GPSBaudRates enum. uint32_t serial_baudrate; @@ -280,8 +280,8 @@ typedef struct master_t { uint8_t softserial_1_inverted; // use inverted softserial input and output signals on port 1 uint8_t softserial_2_inverted; // use inverted softserial input and output signals on port 2 - uint8_t telemetry_provider; // Telemetry provider. 0:FRSKY - uint8_t telemetry_softserial; // Serial to use for Telemetry. 0:USART1, 1:SoftSerial1 (Enable FEATURE_SOFTSERIAL first) + uint8_t telemetry_provider; // See TelemetryProvider enum. + uint8_t telemetry_port; // See TelemetryPort enum. uint8_t telemetry_switch; // Use aux channel to change serial output & baudrate( MSP / Telemetry ). It disables automatic switching to Telemetry when armed. config_t profile[3]; // 3 separate profiles uint8_t current_profile; // currently loaded profile diff --git a/src/telemetry_common.c b/src/telemetry_common.c index 828fff630b..a595378367 100644 --- a/src/telemetry_common.c +++ b/src/telemetry_common.c @@ -8,11 +8,11 @@ void initTelemetry(void) { // Sanity check for softserial vs. telemetry port if (!feature(FEATURE_SOFTSERIAL)) - mcfg.telemetry_softserial = TELEMETRY_UART; + mcfg.telemetry_port = TELEMETRY_PORT_UART; - if (mcfg.telemetry_softserial == TELEMETRY_SOFTSERIAL_1) + if (mcfg.telemetry_port == TELEMETRY_PORT_SOFTSERIAL_1) core.telemport = &(softSerialPorts[0].port); - else if (mcfg.telemetry_softserial == TELEMETRY_SOFTSERIAL_2) + else if (mcfg.telemetry_port == TELEMETRY_PORT_SOFTSERIAL_2) core.telemport = &(softSerialPorts[1].port); else core.telemport = core.mainport; @@ -26,7 +26,7 @@ bool isTelemetryEnabled(void) { bool telemetryCurrentlyEnabled = true; - if (mcfg.telemetry_softserial == TELEMETRY_UART) { + if (mcfg.telemetry_port == TELEMETRY_PORT_UART) { if (!mcfg.telemetry_switch) telemetryCurrentlyEnabled = f.ARMED; else diff --git a/src/telemetry_frsky.c b/src/telemetry_frsky.c index e0724dcdd5..a551ecde09 100644 --- a/src/telemetry_frsky.c +++ b/src/telemetry_frsky.c @@ -230,7 +230,7 @@ void updateFrSkyTelemetryState(void) return; } - if (mcfg.telemetry_softserial == TELEMETRY_UART && mcfg.telemetry_provider == TELEMETRY_PROVIDER_FRSKY) { + if (mcfg.telemetry_port == TELEMETRY_PORT_UART && mcfg.telemetry_provider == TELEMETRY_PROVIDER_FRSKY) { if (frSkyTelemetryCurrentlyEnabled) serialInit(9600); else From 55f14d21587eb4c581dfa7d112569a12a23298f0 Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Mon, 7 Apr 2014 01:25:52 +0100 Subject: [PATCH 09/24] Adding author information and linking to original source for some of the HoTT code - https://github.com/cGiesen/MultiHoTT-Module --- src/telemetry_hott.c | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/src/telemetry_hott.c b/src/telemetry_hott.c index 6c3ee44845..94673bbc6b 100644 --- a/src/telemetry_hott.c +++ b/src/telemetry_hott.c @@ -3,6 +3,10 @@ * * Created on: 6 Apr 2014 * Author: Hydra/cGiesen + * + * It should be noted that the initial cut of code that deals with the handling of requests and formatting and + * sending of responses comes from the MultiHoTT-module project, here: https://github.com/cGiesen/MultiHoTT-Module + * */ /* From 1051cbcf52713a001cc0374a552468c476b22428 Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Mon, 7 Apr 2014 14:12:45 +0100 Subject: [PATCH 10/24] Removed needless memory copy operation. Removed checksum bytes from HoTT packet structures, checksum is always sent by the response sending code. Reduce ram usage by 173+ bytes. Corrected accreditations. Updating documentation to match code. Replaced comments that commented out code with #ifdef blocks because commented out code is not found by refactoring tools. --- src/telemetry_hott.c | 123 ++++++++++++++++++++++++------------------- src/telemetry_hott.h | 4 +- 2 files changed, 69 insertions(+), 58 deletions(-) diff --git a/src/telemetry_hott.c b/src/telemetry_hott.c index 94673bbc6b..8bb8b03216 100644 --- a/src/telemetry_hott.c +++ b/src/telemetry_hott.c @@ -2,24 +2,47 @@ * telemetry_hott.c * * Created on: 6 Apr 2014 - * Author: Hydra/cGiesen + * Authors: + * Dominic Clifton - Hydra - Software Serial, Electronics, Hardware Integration and debugging, HoTT Code cleanup and fixes, general telemetry improvements. + * Carsten Giesen - cGiesen - Baseflight port + * Oliver Bayer - oBayer - MultiWii-HoTT, HoTT reverse engineering * - * It should be noted that the initial cut of code that deals with the handling of requests and formatting and - * sending of responses comes from the MultiHoTT-module project, here: https://github.com/cGiesen/MultiHoTT-Module + * It should be noted that the initial cut of code that deals with the handling of requests and formatting and + * sending of responses comes from the MultiWii-Meets-HoTT and MultiHoTT-module projects + * + * https://github.com/obayer/MultiWii-HoTT + * https://github.com/oBayer/MultiHoTT-Module * - */ - -/* * HoTT is implemented in Graupner equipment using a bi-directional protocol over a single wire. * * Generally the receiver sends a single request byte out using normal uart signals, then waits a short period for a * multiple byte response and checksum byte before it sends out the next request byte. * Each response byte must be send with a protocol specific delay between them. * - * Serial ports use two wires so connect the receiver's HoTT signal to a uart/softserial RX pin via a diode - * and then also connect a uart/softserial TX pin to the same HoTT pin on the receiver, but NOT via a diode. + * Serial ports use two wires but HoTT uses a single wire so some electronics are required so that + * the signals don't get mixed up. When baseflight transmits it should not receive it's own transmission. * - * This is so that when baseflight transmits it does not receive it's own transmission. + * Connect as follows: + * HoTT TX/RX -> 1N4148 Diode -(| )- -> Serial RX + * Serial TX -> 1N4148 Diode -(| )- -> 10k Resistor -(||| |) -> HoTT TX/RX + * + * Diodes should be arranged to allow the data signals to flow the right way + * -(| )- == Diode, | indicates cathode marker. + * 10k Resistor is Brown Black Orange, Gold (5%) + * + * Note the above connections are not 100% reliable, the signal at the HoTT port is not clean, perhaps a + * transistor on the serial RX line is needed? + * + * As noticed by Skrebber the GR-12 (and probably GR-16/24, too) are based on a PIC 24FJ64GA-002, which digitals pins are 5V tolerant. + * + * Note: The softserial ports are not listed as 5V tolerant in the STM32F103xx data sheet pinouts and pin description + * section. No 5v/3.3v level shifters are required. The softserial port should not be inverted. + * + * Technically it is possible to use less components and disable softserial RX when transmitting but that is + * not currently supported. + * + * There is a technical discussion (in German) about HoTT here + * http://www.rc-network.de/forum/showthread.php/281496-Graupner-HoTT-Telemetrie-Sensoren-Eigenbau-DIY-Telemetrie-Protokoll-entschl%C3%BCsselt/page21 */ #include "board.h" @@ -31,7 +54,6 @@ const uint8_t kHoTTv4BinaryPacketSize = 45; const uint8_t kHoTTv4TextPacketSize = 173; -static uint8_t outBuffer[173]; static void hottV4SerialWrite(uint8_t c); static void hottV4Respond(uint8_t *data, uint8_t size); @@ -48,6 +70,8 @@ bool batteryWarning; void hottV4FormatAndSendGPSResponse(void) { + memset(&HoTTV4GPSModule, 0, sizeof(HoTTV4GPSModule)); + /** Minimum data set for EAM */ HoTTV4GPSModule.startByte = 0x7C; HoTTV4GPSModule.sensorID = HOTTV4_GPS_SENSOR_ID; @@ -61,14 +85,8 @@ void hottV4FormatAndSendGPSResponse(void) hottV4GPSUpdate(); - // Clear output buffer - memset(&outBuffer, 0, sizeof(outBuffer)); - - // Copy EAM data to output buffer - memcpy(&outBuffer, &HoTTV4GPSModule, kHoTTv4BinaryPacketSize); - // Send data from output buffer - hottV4Respond(outBuffer, kHoTTv4BinaryPacketSize); + hottV4Respond((uint8_t*)&HoTTV4GPSModule, sizeof(HoTTV4GPSModule)); } void hottV4GPSUpdate(void) @@ -119,45 +137,51 @@ void hottV4GPSUpdate(void) } } - /** - * Writes cell 1-4 high, low values and if not available - * calculates vbat. - */ - static void hottV4EAMUpdateBattery() { -// HoTTV4ElectricAirModule.cell1L = 0; -// HoTTV4ElectricAirModule.cell1H = 0; +/** + * Writes cell 1-4 high, low values and if not available + * calculates vbat. + */ +static void hottV4EAMUpdateBattery() { +#if 0 + HoTTV4ElectricAirModule.cell1L = 4.2f * 10 * 5; // 2mv step + HoTTV4ElectricAirModule.cell1H = 0; -// HoTTV4ElectricAirModule.cell2L = 0; -// HoTTV4ElectricAirModule.cell2H = 0; + HoTTV4ElectricAirModule.cell2L = 0; + HoTTV4ElectricAirModule.cell2H = 0; -// HoTTV4ElectricAirModule.cell3L = 0; -// HoTTV4ElectricAirModule.cell3H = 0; + HoTTV4ElectricAirModule.cell3L = 0; + HoTTV4ElectricAirModule.cell3H = 0; -// HoTTV4ElectricAirModule.cell4L = 0; -// HoTTV4ElectricAirModule.cell4H = 0; + HoTTV4ElectricAirModule.cell4L = 0; + HoTTV4ElectricAirModule.cell4H = 0; +#endif HoTTV4ElectricAirModule.driveVoltageLow = vbat & 0xFF; HoTTV4ElectricAirModule.driveVoltageHigh = vbat >> 8; HoTTV4ElectricAirModule.battery1Low = vbat & 0xFF; HoTTV4ElectricAirModule.battery1High = vbat >> 8; -// HoTTV4ElectricAirModule.battery2Low = 0 & 0xFF; -// HoTTV4ElectricAirModule.battery2High = 0 >> 8; +#if 0 + HoTTV4ElectricAirModule.battery2Low = 0 & 0xFF; + HoTTV4ElectricAirModule.battery2High = 0 >> 8; if (batteryWarning) { HoTTV4ElectricAirModule.alarmTone = HoTTv4NotificationUndervoltage; HoTTV4ElectricAirModule.alarmInverse1 |= 0x80; // Invert Voltage display } - } +#endif +} - static void hottV4EAMUpdateTemperatures() { +static void hottV4EAMUpdateTemperatures() { HoTTV4ElectricAirModule.temp1 = 20 + 0; HoTTV4ElectricAirModule.temp2 = 20; - //if (HoTTV4ElectricAirModule.temp1 >= (20 + MultiHoTTModuleSettings.alarmTemp1)) { - // HoTTV4ElectricAirModule.alarmTone = HoTTv4NotificationMaxTemperature; - // HoTTV4ElectricAirModule.alarmInverse |= 0x8; // Invert Temp1 display - //} +#if 0 + if (HoTTV4ElectricAirModule.temp1 >= (20 + MultiHoTTModuleSettings.alarmTemp1)) { + HoTTV4ElectricAirModule.alarmTone = HoTTv4NotificationMaxTemperature; + HoTTV4ElectricAirModule.alarmInverse |= 0x8; // Invert Temp1 display + } +#endif } @@ -165,6 +189,8 @@ void hottV4GPSUpdate(void) * Sends HoTTv4 capable EAM telemetry frame. */ void hottV4FormatAndSendEAMResponse(void) { + memset(&HoTTV4ElectricAirModule, 0, sizeof(HoTTV4ElectricAirModule)); + /** Minimum data set for EAM */ HoTTV4ElectricAirModule.startByte = 0x7C; HoTTV4ElectricAirModule.sensorID = HOTTV4_ELECTRICAL_AIR_SENSOR_ID; @@ -184,21 +210,10 @@ void hottV4FormatAndSendEAMResponse(void) { HoTTV4ElectricAirModule.m2s = OFFSET_M2S; HoTTV4ElectricAirModule.m3s = OFFSET_M3S; - // Clear output buffer - memset(&outBuffer, 0, sizeof(outBuffer)); - - // Copy EAM data to output buffer - memcpy(&outBuffer, &HoTTV4ElectricAirModule, kHoTTv4BinaryPacketSize); - // Send data from output buffer - hottV4Respond(outBuffer, kHoTTv4BinaryPacketSize); + hottV4Respond((uint8_t*)&HoTTV4ElectricAirModule, sizeof(HoTTV4ElectricAirModule)); } -/** - * Expects an array of at least size bytes. All bytes till size will be transmitted - * to the HoTT capable receiver. Last byte will always be treated as checksum and is - * calculated on the fly. - */ static void hottV4Respond(uint8_t *data, uint8_t size) { if (serialTotalBytesWaiting(core.telemport) != 0 ) { @@ -208,7 +223,7 @@ static void hottV4Respond(uint8_t *data, uint8_t size) { uint16_t crc = 0; uint8_t i; - for (i = 0; i < (size - 1); i++) { + for (i = 0; i < size; i++) { crc += data[i]; hottV4SerialWrite(data[i]); @@ -218,12 +233,10 @@ static void hottV4Respond(uint8_t *data, uint8_t size) { // Write package checksum hottV4SerialWrite(crc & 0xFF); + + delayMicroseconds(HOTTV4_TX_DELAY); } -/** - * Writes out given byte to HoTT serial interface. - * If in debug mode, data is also written to UART serial interface. - */ static void hottV4SerialWrite(uint8_t c) { serialWrite(core.telemport, c); } diff --git a/src/telemetry_hott.h b/src/telemetry_hott.h index 21c6956bc8..352452cb9f 100644 --- a/src/telemetry_hott.h +++ b/src/telemetry_hott.h @@ -138,8 +138,7 @@ struct { 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 Ende byte - uint8_t chksum; // Byte 45: Parity Byte + uint8_t endByte; // Byte 44: 0x7D End byte } HoTTV4GPSModule; /*----------------------------------------------------------- @@ -196,7 +195,6 @@ struct { uint8_t version; uint8_t endByte; - uint8_t chksum; } HoTTV4ElectricAirModule; void handleHoTTTelemetry(void); From ac0f3e9186ade164264ea592163b69372d91360f Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Mon, 7 Apr 2014 16:39:09 +0100 Subject: [PATCH 11/24] Move port telemetry port configuration logic into common telemetry code. Update software serial to support RX, TX or RX&TX modes. Update serial API to allow on-the-fly changing of serial port mode. Update HoTT to change serial port mode when transmitting. --- src/drv_serial.c | 5 +++ src/drv_serial.h | 3 ++ src/drv_softserial.c | 99 ++++++++++++++++++++++++++++++------------ src/drv_uart.c | 9 +++- src/main.c | 2 +- src/mw.c | 2 +- src/telemetry_common.c | 57 ++++++++++++++++++++---- src/telemetry_common.h | 2 +- src/telemetry_frsky.c | 24 +++------- src/telemetry_frsky.h | 5 ++- src/telemetry_hott.c | 21 ++++++--- src/telemetry_hott.h | 4 ++ 12 files changed, 169 insertions(+), 64 deletions(-) diff --git a/src/drv_serial.c b/src/drv_serial.c index ee55de4b35..93f9c23996 100644 --- a/src/drv_serial.c +++ b/src/drv_serial.c @@ -38,3 +38,8 @@ inline bool isSerialTransmitBufferEmpty(serialPort_t *instance) return instance->vTable->isSerialTransmitBufferEmpty(instance); } +inline void serialSetMode(serialPort_t *instance, portMode_t mode) +{ + instance->vTable->setMode(instance, mode); +} + diff --git a/src/drv_serial.h b/src/drv_serial.h index 6d83b56c79..22adee4ce2 100644 --- a/src/drv_serial.h +++ b/src/drv_serial.h @@ -38,12 +38,15 @@ struct serialPortVTable { void (*serialSetBaudRate)(serialPort_t *instance, uint32_t baudRate); bool (*isSerialTransmitBufferEmpty)(serialPort_t *instance); + + void (*setMode)(serialPort_t *instance, portMode_t mode); }; inline void serialWrite(serialPort_t *instance, uint8_t ch); inline uint8_t serialTotalBytesWaiting(serialPort_t *instance); inline uint8_t serialRead(serialPort_t *instance); inline void serialSetBaudRate(serialPort_t *instance, uint32_t baudRate); +void serialSetMode(serialPort_t *instance, portMode_t mode); inline bool isSerialTransmitBufferEmpty(serialPort_t *instance); void serialPrint(serialPort_t *instance, const char *str); uint32_t serialGetBaudRate(serialPort_t *instance); diff --git a/src/drv_softserial.c b/src/drv_softserial.c index 848cb7d1e7..d38395d985 100644 --- a/src/drv_softserial.c +++ b/src/drv_softserial.c @@ -120,11 +120,8 @@ void serialOutputPortConfig(const timerHardware_t *timerHardwarePtr) softSerialGPIOConfig(timerHardwarePtr->gpio, timerHardwarePtr->pin, Mode_Out_PP); } -void initialiseSoftSerial(softSerial_t *softSerial, uint8_t portIndex, uint32_t baud, uint8_t inverted) +void resetBuffers(softSerial_t *softSerial) { - softSerial->port.vTable = softSerialVTable; - softSerial->port.mode = MODE_RXTX; - softSerial->port.rxBufferSize = SOFT_SERIAL_BUFFER_SIZE; softSerial->port.rxBuffer = softSerial->rxBuffer; softSerial->port.rxBufferTail = 0; @@ -134,6 +131,14 @@ void initialiseSoftSerial(softSerial_t *softSerial, uint8_t portIndex, uint32_t softSerial->port.txBufferSize = SOFT_SERIAL_BUFFER_SIZE, softSerial->port.txBufferTail = 0; softSerial->port.txBufferHead = 0; +} + +void initialiseSoftSerial(softSerial_t *softSerial, uint8_t portIndex, uint32_t baud, uint8_t inverted) +{ + softSerial->port.vTable = softSerialVTable; + softSerial->port.mode = MODE_RXTX; + + resetBuffers(softSerial); softSerial->isTransmittingData = false; @@ -198,39 +203,50 @@ void updateBufferIndex(softSerial_t *softSerial) /*********************************************/ +void prepareToSendNextByte(softSerial_t *softSerial) +{ + char byteToSend; + + if ((softSerial->port.mode & MODE_TX) == 0) { + return; + } + + if (isSoftSerialTransmitBufferEmpty((serialPort_t *)softSerial)) { + return; + } + + // choose data to send and update pointer to next byte + byteToSend = softSerial->port.txBuffer[softSerial->port.txBufferTail++]; + if (softSerial->port.txBufferTail >= softSerial->port.txBufferSize) { + softSerial->port.txBufferTail = 0; + } + + // build internal buffer, MSB = Stop Bit (1) + data bits (MSB to LSB) + start bit(0) LSB + softSerial->internalTxBuffer = (1 << (TX_TOTAL_BITS - 1)) | (byteToSend << 1); + softSerial->bitsLeftToTransmit = TX_TOTAL_BITS; + softSerial->isTransmittingData = true; +} + void processTxState(softSerial_t *softSerial) { uint8_t mask; - if (!softSerial->isTransmittingData) { - char byteToSend; - if (isSoftSerialTransmitBufferEmpty((serialPort_t *)softSerial)) { - return; - } + if (softSerial->isTransmittingData) { + mask = softSerial->internalTxBuffer & 1; + softSerial->internalTxBuffer >>= 1; - // data to send - byteToSend = softSerial->port.txBuffer[softSerial->port.txBufferTail++]; - if (softSerial->port.txBufferTail >= softSerial->port.txBufferSize) { - softSerial->port.txBufferTail = 0; - } + setTxSignal(softSerial, mask); - // build internal buffer, MSB = Stop Bit (1) + data bits (MSB to LSB) + start bit(0) LSB - softSerial->internalTxBuffer = (1 << (TX_TOTAL_BITS - 1)) | (byteToSend << 1); - softSerial->bitsLeftToTransmit = TX_TOTAL_BITS; - softSerial->isTransmittingData = true; + if (--softSerial->bitsLeftToTransmit <= 0) { + softSerial->isTransmittingData = false; + } return; } - mask = softSerial->internalTxBuffer & 1; - softSerial->internalTxBuffer >>= 1; - - setTxSignal(softSerial, mask); - - if (--softSerial->bitsLeftToTransmit <= 0) { - softSerial->isTransmittingData = false; - } + prepareToSendNextByte(softSerial); } + enum { TRAILING, LEADING @@ -259,6 +275,10 @@ void prepareForNextRxByte(softSerial_t *softSerial) void extractAndStoreRxByte(softSerial_t *softSerial) { + if ((softSerial->port.mode & MODE_RX) == 0) { + return; + } + uint8_t rxByte = (softSerial->internalRxBuffer >> 1) & 0xFF; softSerial->port.rxBuffer[softSerial->port.rxBufferTail] = rxByte; updateBufferIndex(softSerial); @@ -295,6 +315,10 @@ void onSerialRxPinChange(uint8_t portIndex, uint16_t capture) { softSerial_t *softSerial = &(softSerialPorts[portIndex]); + if ((softSerial->port.mode & MODE_RX) == 0) { + return; + } + if (softSerial->isSearchingForStartBit) { TIM_SetCounter(softSerial->rxTimerHardware->tim, 0); // synchronise bit counter serialICConfig(softSerial->rxTimerHardware->tim, softSerial->rxTimerHardware->channel, softSerial->isInverted ? TIM_ICPolarity_Falling : TIM_ICPolarity_Rising); @@ -324,6 +348,10 @@ void onSerialRxPinChange(uint8_t portIndex, uint16_t capture) uint8_t softSerialTotalBytesWaiting(serialPort_t *instance) { + if ((instance->mode & MODE_RX) == 0) { + return 0; + } + int availableBytes; softSerial_t *softSerial = (softSerial_t *)instance; if (softSerial->port.rxBufferTail == softSerial->port.rxBufferHead) { @@ -350,6 +378,11 @@ static void moveHeadToNextByte(softSerial_t *softSerial) uint8_t softSerialReadByte(serialPort_t *instance) { char b; + + if ((instance->mode & MODE_RX) == 0) { + return 0; + } + if (softSerialTotalBytesWaiting(instance) == 0) { return 0; } @@ -362,6 +395,10 @@ uint8_t softSerialReadByte(serialPort_t *instance) void softSerialWriteByte(serialPort_t *s, uint8_t ch) { + if ((s->mode & MODE_TX) == 0) { + return; + } + s->txBuffer[s->txBufferHead] = ch; s->txBufferHead = (s->txBufferHead + 1) % s->txBufferSize; } @@ -371,6 +408,11 @@ void softSerialSetBaudRate(serialPort_t *s, uint32_t baudRate) // not implemented. } +void softSerialSetMode(serialPort_t *instance, portMode_t mode) +{ + instance->mode = mode; +} + bool isSoftSerialTransmitBufferEmpty(serialPort_t *instance) { return instance->txBufferHead == instance->txBufferTail; @@ -378,10 +420,11 @@ bool isSoftSerialTransmitBufferEmpty(serialPort_t *instance) const struct serialPortVTable softSerialVTable[] = { { - softSerialWriteByte, + softSerialWriteByte, softSerialTotalBytesWaiting, softSerialReadByte, softSerialSetBaudRate, - isSoftSerialTransmitBufferEmpty + isSoftSerialTransmitBufferEmpty, + softSerialSetMode, } }; diff --git a/src/drv_uart.c b/src/drv_uart.c index 7a1727f431..0bdc6253b2 100755 --- a/src/drv_uart.c +++ b/src/drv_uart.c @@ -202,6 +202,12 @@ void uartSetBaudRate(serialPort_t *instance, uint32_t baudRate) s->port.baudRate = baudRate; } +void uartSetMode(serialPort_t *s, portMode_t mode) +{ + // not implemented. +} + + static void uartStartTxDMA(uartPort_t *s) { s->txDMAChannel->CMAR = (uint32_t)&s->port.txBuffer[s->port.txBufferTail]; @@ -273,7 +279,8 @@ const struct serialPortVTable uartVTable[] = { uartTotalBytesWaiting, uartRead, uartSetBaudRate, - isUartTransmitBufferEmpty + isUartTransmitBufferEmpty, + uartSetMode, } }; diff --git a/src/main.c b/src/main.c index 86f18bdfac..b4cfee5972 100755 --- a/src/main.c +++ b/src/main.c @@ -189,7 +189,7 @@ int main(void) if (loopbackPort2) { while (serialTotalBytesWaiting(loopbackPort2)) { uint8_t b = serialRead(loopbackPort2); - serialWrite(loopbackPort1, b); + serialWrite(loopbackPort2, b); //serialWrite(core.mainport, 0x02); //serialWrite(core.mainport, b); }; diff --git a/src/mw.c b/src/mw.c index 7214c36abc..4460bb68ec 100755 --- a/src/mw.c +++ b/src/mw.c @@ -182,7 +182,7 @@ void annexCode(void) LED0_ON; // This will switch to/from 9600 or 115200 baud depending on state. Of course, it should only do it on changes. With telemetry_softserial>0 telemetry is always enabled, also see updateTelemetryState() if (feature(FEATURE_TELEMETRY)) - updateTelemetryState(); + checkTelemetryState(); } #ifdef LEDRING diff --git a/src/telemetry_common.c b/src/telemetry_common.c index a595378367..5c2fee999b 100644 --- a/src/telemetry_common.c +++ b/src/telemetry_common.c @@ -4,6 +4,16 @@ #include "telemetry_frsky.h" #include "telemetry_hott.h" +bool isTelemetryProviderFrSky(void) +{ + return mcfg.telemetry_provider == TELEMETRY_PROVIDER_FRSKY; +} + +bool isTelemetryProviderHoTT(void) +{ + return mcfg.telemetry_provider == TELEMETRY_PROVIDER_HOTT; +} + void initTelemetry(void) { // Sanity check for softserial vs. telemetry port @@ -18,9 +28,7 @@ void initTelemetry(void) core.telemport = core.mainport; } -void updateTelemetryState(void) { - updateFrSkyTelemetryState(); -} +static bool telemetryEnabled = false; bool isTelemetryEnabled(void) { @@ -36,14 +44,45 @@ bool isTelemetryEnabled(void) return telemetryCurrentlyEnabled; } -bool isFrSkyTelemetryEnabled(void) +bool shouldChangeTelemetryStateNow(bool telemetryCurrentlyEnabled) { - return mcfg.telemetry_provider == TELEMETRY_PROVIDER_FRSKY; + return telemetryCurrentlyEnabled != telemetryEnabled; } -bool isHoTTTelemetryEnabled(void) +void configureTelemetryPort(void) { + if (isTelemetryProviderFrSky()) { + configureFrSkyTelemetryPort(); + } + + if (isTelemetryProviderHoTT()) { + configureHoTTTelemetryPort(); + } +} + +void freeTelemetryPort(void) { + if (isTelemetryProviderFrSky()) { + freeFrSkyTelemetryPort(); + } + + if (isTelemetryProviderHoTT()) { + freeHoTTTelemetryPort(); + } +} + +void checkTelemetryState(void) { - return mcfg.telemetry_provider == TELEMETRY_PROVIDER_HOTT; + bool telemetryCurrentlyEnabled = isTelemetryEnabled(); + + if (!shouldChangeTelemetryStateNow(telemetryCurrentlyEnabled)) { + return; + } + + if (telemetryCurrentlyEnabled) + configureTelemetryPort(); + else + freeTelemetryPort(); + + telemetryEnabled = telemetryCurrentlyEnabled; } void handleTelemetry(void) @@ -51,11 +90,11 @@ void handleTelemetry(void) if (!isTelemetryEnabled()) return; - if (isFrSkyTelemetryEnabled()) { + if (isTelemetryProviderFrSky()) { handleFrSkyTelemetry(); } - if (isHoTTTelemetryEnabled()) { + if (isTelemetryProviderHoTT()) { handleHoTTTelemetry(); } } diff --git a/src/telemetry_common.h b/src/telemetry_common.h index defd43320a..5462132b3f 100644 --- a/src/telemetry_common.h +++ b/src/telemetry_common.h @@ -10,7 +10,7 @@ // telemetry void initTelemetry(void); -void updateTelemetryState(void); +void checkTelemetryState(void); void handleTelemetry(void); bool isTelemetryEnabled(void); diff --git a/src/telemetry_frsky.c b/src/telemetry_frsky.c index a551ecde09..8d737d9f42 100644 --- a/src/telemetry_frsky.c +++ b/src/telemetry_frsky.c @@ -215,28 +215,18 @@ static void sendHeading(void) serialize16(0); } -static bool frSkyTelemetryEnabled = false; - -bool shouldChangeTelemetryStateNow(bool frSkyTelemetryCurrentlyEnabled) +void freeFrSkyTelemetryPort(void) { - return frSkyTelemetryCurrentlyEnabled != frSkyTelemetryEnabled; + if (mcfg.telemetry_port == TELEMETRY_PORT_UART) { + serialInit(mcfg.serial_baudrate); + } } -void updateFrSkyTelemetryState(void) +void configureFrSkyTelemetryPort(void) { - bool frSkyTelemetryCurrentlyEnabled = isTelemetryEnabled(); - - if (!shouldChangeTelemetryStateNow(frSkyTelemetryCurrentlyEnabled)) { - return; + if (mcfg.telemetry_port == TELEMETRY_PORT_UART) { + serialInit(9600); } - - if (mcfg.telemetry_port == TELEMETRY_PORT_UART && mcfg.telemetry_provider == TELEMETRY_PROVIDER_FRSKY) { - if (frSkyTelemetryCurrentlyEnabled) - serialInit(9600); - else - serialInit(mcfg.serial_baudrate); - } - frSkyTelemetryEnabled = frSkyTelemetryCurrentlyEnabled; } static uint32_t lastCycleTime = 0; diff --git a/src/telemetry_frsky.h b/src/telemetry_frsky.h index 550b929324..086632253a 100644 --- a/src/telemetry_frsky.h +++ b/src/telemetry_frsky.h @@ -9,6 +9,9 @@ #define TELEMETRY_FRSKY_H_ void handleFrSkyTelemetry(void); -void updateFrSkyTelemetryState(void); +void checkFrSkyTelemetryState(void); + +void configureFrSkyTelemetryPort(void); +void freeFrSkyTelemetryPort(void); #endif /* TELEMETRY_FRSKY_H_ */ diff --git a/src/telemetry_hott.c b/src/telemetry_hott.c index 8bb8b03216..d02cee9712 100644 --- a/src/telemetry_hott.c +++ b/src/telemetry_hott.c @@ -216,9 +216,7 @@ void hottV4FormatAndSendEAMResponse(void) { static void hottV4Respond(uint8_t *data, uint8_t size) { - if (serialTotalBytesWaiting(core.telemport) != 0 ) { - return; // cannot respond since another request came in. - } + serialSetMode(core.telemport, MODE_TX); uint16_t crc = 0; uint8_t i; @@ -235,16 +233,29 @@ static void hottV4Respond(uint8_t *data, uint8_t size) { hottV4SerialWrite(crc & 0xFF); delayMicroseconds(HOTTV4_TX_DELAY); + + serialSetMode(core.telemport, MODE_RX); } static void hottV4SerialWrite(uint8_t c) { serialWrite(core.telemport, c); } +void configureHoTTTelemetryPort(void) { + // TODO set speed here to 19200 + serialSetMode(core.telemport, MODE_RX); +} + +void freeHoTTTelemetryPort(void) { + serialSetMode(core.telemport, MODE_RXTX); +} + void handleHoTTTelemetry(void) { - while (serialTotalBytesWaiting(core.telemport)) { - uint8_t c = serialRead(core.telemport); + uint8_t c; + + while (serialTotalBytesWaiting(core.telemport) > 0) { + c = serialRead(core.telemport); // Protocol specific waiting time // to avoid collisions diff --git a/src/telemetry_hott.h b/src/telemetry_hott.h index 352452cb9f..fef7546860 100644 --- a/src/telemetry_hott.h +++ b/src/telemetry_hott.h @@ -198,5 +198,9 @@ struct { } HoTTV4ElectricAirModule; void handleHoTTTelemetry(void); +void checkTelemetryState(void); + +void configureHoTTTelemetryPort(void); +void freeHoTTTelemetryPort(void); #endif /* TELEMETRY_HOTT_H_ */ From 6b1a6332b94a82bd9e91fd3062f6cd69ee9e8a56 Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Mon, 7 Apr 2014 21:38:50 +0100 Subject: [PATCH 12/24] Ensure that telemetry state is always updated after initialising telemetry so that providers can configure the telemetry port as applicable. --- src/mw.c | 5 ++--- src/telemetry_common.c | 6 ++++++ 2 files changed, 8 insertions(+), 3 deletions(-) diff --git a/src/mw.c b/src/mw.c index 4460bb68ec..463b5951dd 100755 --- a/src/mw.c +++ b/src/mw.c @@ -180,9 +180,8 @@ void annexCode(void) LED0_OFF; if (f.ARMED) LED0_ON; - // This will switch to/from 9600 or 115200 baud depending on state. Of course, it should only do it on changes. With telemetry_softserial>0 telemetry is always enabled, also see updateTelemetryState() - if (feature(FEATURE_TELEMETRY)) - checkTelemetryState(); + + checkTelemetryState(); } #ifdef LEDRING diff --git a/src/telemetry_common.c b/src/telemetry_common.c index 5c2fee999b..cc7031e198 100644 --- a/src/telemetry_common.c +++ b/src/telemetry_common.c @@ -26,6 +26,8 @@ void initTelemetry(void) core.telemport = &(softSerialPorts[1].port); else core.telemport = core.mainport; + + checkTelemetryState(); } static bool telemetryEnabled = false; @@ -71,6 +73,10 @@ void freeTelemetryPort(void) { void checkTelemetryState(void) { + if (!feature(FEATURE_TELEMETRY)) { + return; + } + bool telemetryCurrentlyEnabled = isTelemetryEnabled(); if (!shouldChangeTelemetryStateNow(telemetryCurrentlyEnabled)) { From ee5d7e9d1f6544a8a92388a872da312548c62b23 Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Mon, 7 Apr 2014 21:39:49 +0100 Subject: [PATCH 13/24] Cleanup HoTT protocol structure, verified against latest code in here: https://github.com/obayer/MultiWii-HoTT/blob/master/MultiWii_2_1/HoTTv4.ino --- src/telemetry_hott.h | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/src/telemetry_hott.h b/src/telemetry_hott.h index fef7546860..29f393db22 100644 --- a/src/telemetry_hott.h +++ b/src/telemetry_hott.h @@ -120,19 +120,22 @@ struct { 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 - uint8_t unknow1; // 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 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) + 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 + 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] From c73488b9a8d6ddc391026ad59f8ae6693963f674 Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Mon, 7 Apr 2014 21:41:57 +0100 Subject: [PATCH 14/24] Fix an extra byte being sent between the HoTT data and the checksum. --- src/telemetry_hott.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/telemetry_hott.c b/src/telemetry_hott.c index d02cee9712..60680bd1f4 100644 --- a/src/telemetry_hott.c +++ b/src/telemetry_hott.c @@ -221,7 +221,7 @@ static void hottV4Respond(uint8_t *data, uint8_t size) { uint16_t crc = 0; uint8_t i; - for (i = 0; i < size; i++) { + for (i = 0; i < size - 1; i++) { crc += data[i]; hottV4SerialWrite(data[i]); @@ -242,7 +242,7 @@ static void hottV4SerialWrite(uint8_t c) { } void configureHoTTTelemetryPort(void) { - // TODO set speed here to 19200 + // TODO set speed here to 19200? serialSetMode(core.telemport, MODE_RX); } From 1c0e0618e5e5c6e2856f37deadbcabc1555461fc Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Mon, 7 Apr 2014 21:57:46 +0100 Subject: [PATCH 15/24] Update HoTT physical connection details (only one diode needed). --- src/telemetry_hott.c | 12 ++++-------- 1 file changed, 4 insertions(+), 8 deletions(-) diff --git a/src/telemetry_hott.c b/src/telemetry_hott.c index 60680bd1f4..664941e0cd 100644 --- a/src/telemetry_hott.c +++ b/src/telemetry_hott.c @@ -23,20 +23,16 @@ * the signals don't get mixed up. When baseflight transmits it should not receive it's own transmission. * * Connect as follows: - * HoTT TX/RX -> 1N4148 Diode -(| )- -> Serial RX - * Serial TX -> 1N4148 Diode -(| )- -> 10k Resistor -(||| |) -> HoTT TX/RX + * HoTT TX/RX -> Serial RX (connect directly) + * Serial TX -> 1N4148 Diode -(| )-> HoTT TX/RX (connect via diode) * - * Diodes should be arranged to allow the data signals to flow the right way + * The diode should be arranged to allow the data signals to flow the right way * -(| )- == Diode, | indicates cathode marker. - * 10k Resistor is Brown Black Orange, Gold (5%) - * - * Note the above connections are not 100% reliable, the signal at the HoTT port is not clean, perhaps a - * transistor on the serial RX line is needed? * * As noticed by Skrebber the GR-12 (and probably GR-16/24, too) are based on a PIC 24FJ64GA-002, which digitals pins are 5V tolerant. * * Note: The softserial ports are not listed as 5V tolerant in the STM32F103xx data sheet pinouts and pin description - * section. No 5v/3.3v level shifters are required. The softserial port should not be inverted. + * section. Verify if you require a 5v/3.3v level shifters. The softserial port should not be inverted. * * Technically it is possible to use less components and disable softserial RX when transmitting but that is * not currently supported. From 9b86d0d8335a958a788b4a84bf99912444212ba7 Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Mon, 7 Apr 2014 22:23:11 +0100 Subject: [PATCH 16/24] Update common telemetry code so that it verifies that the telemetry configuration is valid. Internally this uses a flag so that the configuration is not continually verified. --- src/telemetry_common.c | 35 +++++++++++++++++++++++++++++++---- 1 file changed, 31 insertions(+), 4 deletions(-) diff --git a/src/telemetry_common.c b/src/telemetry_common.c index cc7031e198..4300107997 100644 --- a/src/telemetry_common.c +++ b/src/telemetry_common.c @@ -4,6 +4,8 @@ #include "telemetry_frsky.h" #include "telemetry_hott.h" +static bool isTelemetryConfigurationValid = false; // flag used to avoid repeated configuration checks + bool isTelemetryProviderFrSky(void) { return mcfg.telemetry_provider == TELEMETRY_PROVIDER_FRSKY; @@ -14,12 +16,37 @@ bool isTelemetryProviderHoTT(void) return mcfg.telemetry_provider == TELEMETRY_PROVIDER_HOTT; } +bool canUseTelemetryWithCurrentConfiguration(void) { + + if (!feature(FEATURE_TELEMETRY)) { + return false; + } + + if (!feature(FEATURE_SOFTSERIAL)) { + if (mcfg.telemetry_port == TELEMETRY_PORT_SOFTSERIAL_1 || mcfg.telemetry_port == TELEMETRY_PORT_SOFTSERIAL_1) { + // softserial feature must be enabled to use telemetry on softserial ports + return false; + } + } + + if (isTelemetryProviderHoTT()) { + if (mcfg.telemetry_port == TELEMETRY_PORT_UART) { + // HoTT requires a serial port that supports RX/TX mode swapping + return false; + } + } + + return true; +} + void initTelemetry(void) { - // Sanity check for softserial vs. telemetry port + // Force telemetry to uart when softserial disabled if (!feature(FEATURE_SOFTSERIAL)) mcfg.telemetry_port = TELEMETRY_PORT_UART; + isTelemetryConfigurationValid = canUseTelemetryWithCurrentConfiguration(); + if (mcfg.telemetry_port == TELEMETRY_PORT_SOFTSERIAL_1) core.telemport = &(softSerialPorts[0].port); else if (mcfg.telemetry_port == TELEMETRY_PORT_SOFTSERIAL_2) @@ -51,7 +78,7 @@ bool shouldChangeTelemetryStateNow(bool telemetryCurrentlyEnabled) return telemetryCurrentlyEnabled != telemetryEnabled; } -void configureTelemetryPort(void) { +static void configureTelemetryPort(void) { if (isTelemetryProviderFrSky()) { configureFrSkyTelemetryPort(); } @@ -73,7 +100,7 @@ void freeTelemetryPort(void) { void checkTelemetryState(void) { - if (!feature(FEATURE_TELEMETRY)) { + if (!isTelemetryConfigurationValid) { return; } @@ -93,7 +120,7 @@ void checkTelemetryState(void) void handleTelemetry(void) { - if (!isTelemetryEnabled()) + if (!isTelemetryConfigurationValid || !isTelemetryEnabled()) return; if (isTelemetryProviderFrSky()) { From c26d6362b1b5c27c6b2d7c99090b95427b8e74e8 Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Mon, 7 Apr 2014 22:31:20 +0100 Subject: [PATCH 17/24] Rename some telemetry variables and methods to better indicate the intent of the code and thus the readability and maintainability of it. --- src/telemetry_common.c | 24 ++++++++++++------------ src/telemetry_common.h | 1 - 2 files changed, 12 insertions(+), 13 deletions(-) diff --git a/src/telemetry_common.c b/src/telemetry_common.c index 4300107997..1153290dd2 100644 --- a/src/telemetry_common.c +++ b/src/telemetry_common.c @@ -59,23 +59,23 @@ void initTelemetry(void) static bool telemetryEnabled = false; -bool isTelemetryEnabled(void) +bool determineNewTelemetryEnabledState(void) { - bool telemetryCurrentlyEnabled = true; + bool enabled = true; if (mcfg.telemetry_port == TELEMETRY_PORT_UART) { if (!mcfg.telemetry_switch) - telemetryCurrentlyEnabled = f.ARMED; + enabled = f.ARMED; else - telemetryCurrentlyEnabled = rcOptions[BOXTELEMETRY]; + enabled = rcOptions[BOXTELEMETRY]; } - return telemetryCurrentlyEnabled; + return enabled; } -bool shouldChangeTelemetryStateNow(bool telemetryCurrentlyEnabled) +bool shouldChangeTelemetryStateNow(bool newState) { - return telemetryCurrentlyEnabled != telemetryEnabled; + return newState != telemetryEnabled; } static void configureTelemetryPort(void) { @@ -104,23 +104,23 @@ void checkTelemetryState(void) return; } - bool telemetryCurrentlyEnabled = isTelemetryEnabled(); + bool newEnabledState = determineNewTelemetryEnabledState(); - if (!shouldChangeTelemetryStateNow(telemetryCurrentlyEnabled)) { + if (!shouldChangeTelemetryStateNow(newEnabledState)) { return; } - if (telemetryCurrentlyEnabled) + if (newEnabledState) configureTelemetryPort(); else freeTelemetryPort(); - telemetryEnabled = telemetryCurrentlyEnabled; + telemetryEnabled = newEnabledState; } void handleTelemetry(void) { - if (!isTelemetryConfigurationValid || !isTelemetryEnabled()) + if (!isTelemetryConfigurationValid || !determineNewTelemetryEnabledState()) return; if (isTelemetryProviderFrSky()) { diff --git a/src/telemetry_common.h b/src/telemetry_common.h index 5462132b3f..0241d6415e 100644 --- a/src/telemetry_common.h +++ b/src/telemetry_common.h @@ -12,6 +12,5 @@ void initTelemetry(void); void checkTelemetryState(void); void handleTelemetry(void); -bool isTelemetryEnabled(void); #endif /* TELEMETRY_COMMON_H_ */ From 00cdbe343896eb683c633e035b737cf60f806608 Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Mon, 7 Apr 2014 22:44:14 +0100 Subject: [PATCH 18/24] Fixing typo in telemetry port configuration logic. --- src/telemetry_common.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/telemetry_common.c b/src/telemetry_common.c index 1153290dd2..c93643d6a4 100644 --- a/src/telemetry_common.c +++ b/src/telemetry_common.c @@ -23,7 +23,7 @@ bool canUseTelemetryWithCurrentConfiguration(void) { } if (!feature(FEATURE_SOFTSERIAL)) { - if (mcfg.telemetry_port == TELEMETRY_PORT_SOFTSERIAL_1 || mcfg.telemetry_port == TELEMETRY_PORT_SOFTSERIAL_1) { + if (mcfg.telemetry_port == TELEMETRY_PORT_SOFTSERIAL_1 || mcfg.telemetry_port == TELEMETRY_PORT_SOFTSERIAL_2) { // softserial feature must be enabled to use telemetry on softserial ports return false; } From bf59943578ce2743d6d75a1e2ee9ea7dc2a8a502 Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Mon, 7 Apr 2014 23:17:11 +0100 Subject: [PATCH 19/24] Fixing indentation and spacing of imported HoTT code. --- src/telemetry_hott.c | 158 +++++++++++++------------- src/telemetry_hott.h | 256 +++++++++++++++++++++---------------------- 2 files changed, 207 insertions(+), 207 deletions(-) diff --git a/src/telemetry_hott.c b/src/telemetry_hott.c index 664941e0cd..097e5c7185 100644 --- a/src/telemetry_hott.c +++ b/src/telemetry_hott.c @@ -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; diff --git a/src/telemetry_hott.h b/src/telemetry_hott.h index 29f393db22..89f615fb4a 100644 --- a/src/telemetry_hott.h +++ b/src/telemetry_hott.h @@ -33,47 +33,47 @@ #define OFFSET_M3S 120 typedef enum { - HoTTv4NotificationErrorCalibration = 0x01, - HoTTv4NotificationErrorReceiver = 0x02, - HoTTv4NotificationErrorDataBus = 0x03, - HoTTv4NotificationErrorNavigation = 0x04, - HoTTv4NotificationErrorError = 0x05, - HoTTv4NotificationErrorCompass = 0x06, - HoTTv4NotificationErrorSensor = 0x07, - HoTTv4NotificationErrorGPS = 0x08, - HoTTv4NotificationErrorMotor = 0x09, + HoTTv4NotificationErrorCalibration = 0x01, + HoTTv4NotificationErrorReceiver = 0x02, + HoTTv4NotificationErrorDataBus = 0x03, + HoTTv4NotificationErrorNavigation = 0x04, + HoTTv4NotificationErrorError = 0x05, + HoTTv4NotificationErrorCompass = 0x06, + HoTTv4NotificationErrorSensor = 0x07, + HoTTv4NotificationErrorGPS = 0x08, + HoTTv4NotificationErrorMotor = 0x09, - 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, + 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, - 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, + 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; /*----------------------------------------------------------- @@ -86,62 +86,62 @@ Byte 2: 0x8A = GPS Sensor byte (witch data Transmitter wants to get) -----------------------------------------------------------*/ struct { - 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 + 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 - // 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 + // 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 - // 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 + // 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 - 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 + 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 - 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) + 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) - 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 + 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 - 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 + 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; /*----------------------------------------------------------- @@ -153,51 +153,51 @@ Byte 2: 8E = Electric Sensor byte *-----------------------------------------------------------*/ struct { - uint8_t startByte; - uint8_t sensorID; - uint8_t alarmTone; // Alarm */ - uint8_t sensorTextID; - uint8_t alarmInverse1; - uint8_t alarmInverse2; + uint8_t startByte; + uint8_t sensorID; + uint8_t alarmTone; // Alarm */ + uint8_t sensorTextID; + uint8_t alarmInverse1; + uint8_t alarmInverse2; - 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 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; + 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 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; - 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 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 temp1; // Temp 1; Offset of 20. 20 == 0C */ - uint8_t temp2; // Temp 2; 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 */ - uint16_t height; // Height. Offset -500. 500 == 0 */ - uint16_t current; // 1 = 0.1A */ - uint8_t driveVoltageLow; - uint8_t driveVoltageHigh; - uint16_t capacity; // mAh */ - uint16_t m2s; // m2s; 0x48 == 0 */ - uint8_t m3s; // m3s; 0x78 == 0 */ + uint16_t height; // Height. Offset -500. 500 == 0 */ + uint16_t current; // 1 = 0.1A */ + uint8_t driveVoltageLow; + uint8_t driveVoltageHigh; + uint16_t capacity; // mAh */ + uint16_t m2s; // m2s; 0x48 == 0 */ + uint8_t m3s; // m3s; 0x78 == 0 */ - uint16_t rpm; // RPM. 10er steps; 300 == 3000rpm */ - uint8_t minutes; - uint8_t seconds; - uint8_t speed; + uint16_t rpm; // RPM. 10er steps; 300 == 3000rpm */ + uint8_t minutes; + uint8_t seconds; + uint8_t speed; - uint8_t version; - uint8_t endByte; + uint8_t version; + uint8_t endByte; } HoTTV4ElectricAirModule; void handleHoTTTelemetry(void); From ce3b7859da09c76b6386e01c67756dd7980fb350 Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Mon, 7 Apr 2014 23:18:50 +0100 Subject: [PATCH 20/24] Fixing a comma that should have been a semi-colon in the code. Fixing some trailing spaces. --- src/drv_softserial.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/drv_softserial.c b/src/drv_softserial.c index 0758e8f219..44eb7882ed 100644 --- a/src/drv_softserial.c +++ b/src/drv_softserial.c @@ -128,7 +128,7 @@ void resetBuffers(softSerial_t *softSerial) softSerial->port.rxBufferHead = 0; softSerial->port.txBuffer = softSerial->txBuffer; - softSerial->port.txBufferSize = SOFT_SERIAL_BUFFER_SIZE, + softSerial->port.txBufferSize = SOFT_SERIAL_BUFFER_SIZE; softSerial->port.txBufferTail = 0; softSerial->port.txBufferHead = 0; } @@ -286,7 +286,7 @@ void extractAndStoreRxByte(softSerial_t *softSerial) softSerial->receiveErrors++; return; } - + uint8_t rxByte = (softSerial->internalRxBuffer >> 1) & 0xFF; softSerial->port.rxBuffer[softSerial->port.rxBufferTail] = rxByte; updateBufferIndex(softSerial); From 24d162dc3e091b644c956c0ecffb0514d1f64acd Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Mon, 7 Apr 2014 23:20:35 +0100 Subject: [PATCH 21/24] Fixing code style on some HoTT code. --- src/telemetry_hott.c | 22 ++++++++++++++-------- 1 file changed, 14 insertions(+), 8 deletions(-) diff --git a/src/telemetry_hott.c b/src/telemetry_hott.c index 097e5c7185..880957260f 100644 --- a/src/telemetry_hott.c +++ b/src/telemetry_hott.c @@ -137,7 +137,8 @@ void hottV4GPSUpdate(void) * Writes cell 1-4 high, low values and if not available * calculates vbat. */ -static void hottV4EAMUpdateBattery() { +static void hottV4EAMUpdateBattery() +{ #if 0 HoTTV4ElectricAirModule.cell1L = 4.2f * 10 * 5; // 2mv step HoTTV4ElectricAirModule.cell1H = 0; @@ -168,7 +169,8 @@ static void hottV4EAMUpdateBattery() { #endif } -static void hottV4EAMUpdateTemperatures() { +static void hottV4EAMUpdateTemperatures() +{ HoTTV4ElectricAirModule.temp1 = 20 + 0; HoTTV4ElectricAirModule.temp2 = 20; @@ -184,7 +186,8 @@ static void hottV4EAMUpdateTemperatures() { /** * Sends HoTTv4 capable EAM telemetry frame. */ -void hottV4FormatAndSendEAMResponse(void) { +void hottV4FormatAndSendEAMResponse(void) +{ memset(&HoTTV4ElectricAirModule, 0, sizeof(HoTTV4ElectricAirModule)); /** Minimum data set for EAM */ @@ -210,7 +213,8 @@ void hottV4FormatAndSendEAMResponse(void) { hottV4Respond((uint8_t*)&HoTTV4ElectricAirModule, sizeof(HoTTV4ElectricAirModule)); } -static void hottV4Respond(uint8_t *data, uint8_t size) { +static void hottV4Respond(uint8_t *data, uint8_t size) +{ serialSetMode(core.telemport, MODE_TX); @@ -233,16 +237,19 @@ static void hottV4Respond(uint8_t *data, uint8_t size) { serialSetMode(core.telemport, MODE_RX); } -static void hottV4SerialWrite(uint8_t c) { +static void hottV4SerialWrite(uint8_t c) +{ serialWrite(core.telemport, c); } -void configureHoTTTelemetryPort(void) { +void configureHoTTTelemetryPort(void) +{ // TODO set speed here to 19200? serialSetMode(core.telemport, MODE_RX); } -void freeHoTTTelemetryPort(void) { +void freeHoTTTelemetryPort(void) +{ serialSetMode(core.telemport, MODE_RXTX); } @@ -268,4 +275,3 @@ void handleHoTTTelemetry(void) } } - From 6a4614e1166763c839c58dadbe0c99db06dd6a78 Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Mon, 7 Apr 2014 23:40:07 +0100 Subject: [PATCH 22/24] Cleanup comment imported HoTT code, comment style, incorrect comments, spacing. --- src/telemetry_hott.c | 43 ++++++++++++++++++++----------------------- 1 file changed, 20 insertions(+), 23 deletions(-) diff --git a/src/telemetry_hott.c b/src/telemetry_hott.c index 880957260f..af791841e8 100644 --- a/src/telemetry_hott.c +++ b/src/telemetry_hott.c @@ -68,31 +68,30 @@ void hottV4FormatAndSendGPSResponse(void) { memset(&HoTTV4GPSModule, 0, sizeof(HoTTV4GPSModule)); - /** Minimum data set for EAM */ + // 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 */ + // Reset alarms HoTTV4GPSModule.alarmTone = 0x0; HoTTV4GPSModule.alarmInverse1 = 0x0; hottV4GPSUpdate(); - // Send data from output buffer hottV4Respond((uint8_t*)&HoTTV4GPSModule, sizeof(HoTTV4GPSModule)); } void hottV4GPSUpdate(void) { - //number of Satelites + // Number of Satelites HoTTV4GPSModule.GPSNumSat=GPS_numSat; if (f.GPS_FIX > 0) { - /** GPS fix */ + // GPS fix HoTTV4GPSModule.GPS_fix = 0x66; // Displays a 'f' for fix - //latitude + + // latitude HoTTV4GPSModule.LatitudeNS=(GPS_coord[LAT]<0); uint8_t deg = GPS_coord[LAT] / 100000; uint32_t sec = (GPS_coord[LAT] - (deg * 100000)) * 6; @@ -103,7 +102,8 @@ void hottV4GPSUpdate(void) HoTTV4GPSModule.LatitudeMinHigh = degMin >> 8; HoTTV4GPSModule.LatitudeSecLow = sec; HoTTV4GPSModule.LatitudeSecHigh = sec >> 8; - //latitude + + // longitude HoTTV4GPSModule.longitudeEW=(GPS_coord[LON]<0); deg = GPS_coord[LON] / 100000; sec = (GPS_coord[LON] - (deg * 100000)) * 6; @@ -114,21 +114,23 @@ void hottV4GPSUpdate(void) HoTTV4GPSModule.longitudeMinHigh = degMin >> 8; HoTTV4GPSModule.longitudeSecLow = sec; 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 HoTTV4GPSModule.GPSSpeedLow = speed & 0x00FF; HoTTV4GPSModule.GPSSpeedHigh = speed >> 8; - /** Distance to home */ + + // Distance to home HoTTV4GPSModule.distanceLow = GPS_distanceToHome & 0x00FF; HoTTV4GPSModule.distanceHigh = GPS_distanceToHome >> 8; - /** Altitude */ + + // Altitude HoTTV4GPSModule.altitudeLow = GPS_altitude & 0x00FF; HoTTV4GPSModule.altitudeHigh = GPS_altitude >> 8; - /** Altitude */ + + // Direction to home HoTTV4GPSModule.HomeDirection = GPS_directionToHome; - } - else - { + } else { HoTTV4GPSModule.GPS_fix = 0x20; // Displays a ' ' to show nothing or clear the old value } } @@ -190,14 +192,13 @@ void hottV4FormatAndSendEAMResponse(void) { memset(&HoTTV4ElectricAirModule, 0, sizeof(HoTTV4ElectricAirModule)); - /** Minimum data set for EAM */ + // 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 */ + // Reset alarms HoTTV4ElectricAirModule.alarmTone = 0x0; HoTTV4ElectricAirModule.alarmInverse1 = 0x0; @@ -209,13 +210,11 @@ void hottV4FormatAndSendEAMResponse(void) HoTTV4ElectricAirModule.m2s = OFFSET_M2S; HoTTV4ElectricAirModule.m3s = OFFSET_M3S; - // Send data from output buffer hottV4Respond((uint8_t*)&HoTTV4ElectricAirModule, sizeof(HoTTV4ElectricAirModule)); } static void hottV4Respond(uint8_t *data, uint8_t size) { - serialSetMode(core.telemport, MODE_TX); uint16_t crc = 0; @@ -229,7 +228,6 @@ static void hottV4Respond(uint8_t *data, uint8_t size) delayMicroseconds(HOTTV4_TX_DELAY); } - // Write package checksum hottV4SerialWrite(crc & 0xFF); delayMicroseconds(HOTTV4_TX_DELAY); @@ -260,8 +258,7 @@ void handleHoTTTelemetry(void) while (serialTotalBytesWaiting(core.telemport) > 0) { c = serialRead(core.telemport); - // Protocol specific waiting time - // to avoid collisions + // Protocol specific waiting time to avoid collisions delay(5); switch (c) { From 993edc4e20b211ebe9f67c1e4c6684aeb249a8f2 Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Mon, 7 Apr 2014 23:58:57 +0100 Subject: [PATCH 23/24] More HoTT code style cleanups. --- src/telemetry_hott.c | 4 ++-- src/telemetry_hott.h | 32 ++++++++++++++++---------------- 2 files changed, 18 insertions(+), 18 deletions(-) diff --git a/src/telemetry_hott.c b/src/telemetry_hott.c index af791841e8..1569c6ddd3 100644 --- a/src/telemetry_hott.c +++ b/src/telemetry_hott.c @@ -139,7 +139,7 @@ void hottV4GPSUpdate(void) * Writes cell 1-4 high, low values and if not available * calculates vbat. */ -static void hottV4EAMUpdateBattery() +static void hottV4EAMUpdateBattery(void) { #if 0 HoTTV4ElectricAirModule.cell1L = 4.2f * 10 * 5; // 2mv step @@ -171,7 +171,7 @@ static void hottV4EAMUpdateBattery() #endif } -static void hottV4EAMUpdateTemperatures() +static void hottV4EAMUpdateTemperatures(void) { HoTTV4ElectricAirModule.temp1 = 20 + 0; HoTTV4ElectricAirModule.temp2 = 20; diff --git a/src/telemetry_hott.h b/src/telemetry_hott.h index 89f615fb4a..f808defecf 100644 --- a/src/telemetry_hott.h +++ b/src/telemetry_hott.h @@ -8,7 +8,7 @@ #ifndef TELEMETRY_HOTT_H_ #define TELEMETRY_HOTT_H_ -/* ###### HoTT module specifications ###### */ +/* HoTT module specifications */ #define HOTTV4_GENERAL_AIR_SENSOR_ID 0xD0 @@ -76,14 +76,14 @@ typedef enum { 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 ------------------------------------------------------------*/ +/** + * 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 + */ struct { uint8_t startByte; // Byte 1: 0x7C = Start byte data @@ -144,13 +144,13 @@ struct { uint8_t endByte; // Byte 44: 0x7D End byte } HoTTV4GPSModule; -/*----------------------------------------------------------- -EAM (Electric Air Module) 33620 -EmpfängerElectric Sensor -Byte 1: 80 = Receiver byte -Byte 2: 8E = Electric Sensor byte -5ms Idle Line! - *-----------------------------------------------------------*/ +/** + * EAM (Electric Air Module) 33620 + * EmpfängerElectric Sensor + * Byte 1: 80 = Receiver byte + * Byte 2: 8E = Electric Sensor byte + * 5ms Idle Line! +*/ struct { uint8_t startByte; From 1838703853c94ab7752892e3d736be9b2f43de1b Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Tue, 8 Apr 2014 00:00:21 +0100 Subject: [PATCH 24/24] Code style cleanups. --- src/telemetry_common.c | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/src/telemetry_common.c b/src/telemetry_common.c index c93643d6a4..6302a1855f 100644 --- a/src/telemetry_common.c +++ b/src/telemetry_common.c @@ -16,7 +16,8 @@ bool isTelemetryProviderHoTT(void) return mcfg.telemetry_provider == TELEMETRY_PROVIDER_HOTT; } -bool canUseTelemetryWithCurrentConfiguration(void) { +bool canUseTelemetryWithCurrentConfiguration(void) +{ if (!feature(FEATURE_TELEMETRY)) { return false; @@ -78,7 +79,8 @@ bool shouldChangeTelemetryStateNow(bool newState) return newState != telemetryEnabled; } -static void configureTelemetryPort(void) { +static void configureTelemetryPort(void) +{ if (isTelemetryProviderFrSky()) { configureFrSkyTelemetryPort(); } @@ -88,7 +90,8 @@ static void configureTelemetryPort(void) { } } -void freeTelemetryPort(void) { +void freeTelemetryPort(void) +{ if (isTelemetryProviderFrSky()) { freeFrSkyTelemetryPort(); }