Fix HoTT telemetry to use a 3ms delay between each transmitted byte.
This has fixed HoTT telemety data on my GR-24, previously it was a bit intermittent. This commit also marks a test-point, HoTT works on UART2. Reference: https://code.google.com/p/hott-for-ardupilot/source/browse/APM/Hott.pde#510
This commit is contained in:
parent
0b424807df
commit
420ba7d2c9
|
@ -102,6 +102,19 @@ set gps_passthrough_baudrate = 19200
|
|||
save
|
||||
```
|
||||
|
||||
e) HoTT Telemetry via UART2
|
||||
|
||||
- MSP,CLI,GPS PASSTHROUGH on UART1
|
||||
- HoTT telemetry on UART2
|
||||
|
||||
```
|
||||
feature -RX_PARALLEL_PWM
|
||||
feature RX_PPM
|
||||
feature TELEMETRY
|
||||
set serial_port_2_scenario = 4
|
||||
set telemetry_provider = 1
|
||||
```
|
||||
|
||||
## FrSky telemetry
|
||||
|
||||
FrSky telemetry signals are inverted. To connect a cleanflight capable board to an FrSKy receiver you have some options.
|
||||
|
|
|
@ -168,8 +168,8 @@ void hottV4GPSUpdate(void)
|
|||
static void hottV4EAMUpdateBattery(void)
|
||||
{
|
||||
#if 0
|
||||
HoTTV4ElectricAirModule.cell1L = 4.2f * 10 * 5; // 2mv step
|
||||
HoTTV4ElectricAirModule.cell1H = 0;
|
||||
HoTTV4ElectricAirModule.cell1L = 3.30f * 10 * 5; // 2mv step - 3.30v
|
||||
HoTTV4ElectricAirModule.cell1H = 4.20f * 10 * 5; // 2mv step - 4.20v
|
||||
|
||||
HoTTV4ElectricAirModule.cell2L = 0;
|
||||
HoTTV4ElectricAirModule.cell2H = 0;
|
||||
|
|
|
@ -19,7 +19,7 @@
|
|||
#define HOTTV4_GPS_SENSOR_TEXT_ID 0xA0 // GPS Module ID
|
||||
|
||||
#define HOTTV4_RXTX 4
|
||||
#define HOTTV4_TX_DELAY 1000
|
||||
#define HOTTV4_TX_DELAY 3000
|
||||
|
||||
#define HOTTV4_BUTTON_DEC 0xEB
|
||||
#define HOTTV4_BUTTON_INC 0xED
|
||||
|
@ -85,7 +85,7 @@ typedef enum {
|
|||
* 5ms delay
|
||||
*/
|
||||
|
||||
typedef struct HoTTV4GPSModule_t {
|
||||
typedef struct HoTTV4GPSModule_s {
|
||||
uint8_t startByte; // Byte 1: 0x7C = Start byte data
|
||||
uint8_t sensorID; // Byte 2: 0x8A = GPS Sensor
|
||||
uint8_t alarmTone; // Byte 3: 0…= warning beeps
|
||||
|
@ -152,11 +152,15 @@ typedef struct HoTTV4GPSModule_t {
|
|||
* 5ms Idle Line!
|
||||
*/
|
||||
|
||||
typedef struct HoTTV4ElectricAirModule_t {
|
||||
typedef struct HoTTV4ElectricAirModule_s {
|
||||
uint8_t startByte;
|
||||
|
||||
uint8_t sensorID;
|
||||
|
||||
uint8_t alarmTone; // Alarm */
|
||||
|
||||
uint8_t sensorTextID;
|
||||
|
||||
uint8_t alarmInverse1;
|
||||
uint8_t alarmInverse2;
|
||||
|
||||
|
@ -167,6 +171,7 @@ typedef struct HoTTV4ElectricAirModule_t {
|
|||
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;
|
||||
|
@ -177,6 +182,7 @@ typedef struct HoTTV4ElectricAirModule_t {
|
|||
|
||||
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 */
|
||||
|
||||
|
@ -184,19 +190,25 @@ typedef struct HoTTV4ElectricAirModule_t {
|
|||
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;
|
||||
uint16_t speed;
|
||||
|
||||
uint8_t endByte;
|
||||
} HoTTV4ElectricAirModule_t;
|
||||
|
||||
|
|
Loading…
Reference in New Issue