mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-13 03:19:58 +03:00
IBUS telemetry new features (#1495)
* ibus_telemetry_type 3,4,5 * Measure value * Update ibus_shared.c * Update ibus.c * Update barometer.h * Update barometer.c * Update ibus_shared.c * Missing LAUNCH in getFlightModeForTelemetry * Update barometer.c * Speed is in mph - change to km/h * Climb rate signed and no divide * Reorder values and support new oficial version * Add Gps alt 4 byte and capacity (fuel) * support new oficial version * Update doc * Update barometer.h * Update ibus.c * Update ibus_shared.c * Update ibus_shared.h
This commit is contained in:
parent
a62b073aa6
commit
28a8fd0981
5 changed files with 414 additions and 109 deletions
|
@ -285,11 +285,46 @@ Example: 12803 is 12 satelites, Fix3D, FixHome, 0-9m HDOP, Angle Mode
|
|||
|
||||
ibus_telemetry_type
|
||||
|
||||
0.Standard sensor type are used (Temp,Rpm,ExtV). Each transmitter should support this. (FS-i6, FS-i6S)
|
||||
0.Standard sensor type are used (Temp,Rpm,ExtV). Each transmitter should support this. (FS-i6, FS-i6S).
|
||||
|
||||
1.This same as 0, but GPS ground speed (sensor 16) is of type Speed in km/h. (FS-i6 10ch_MOD_i6_Programmer_V1_5.exe from https://github.com/benb0jangles/FlySky-i6-Mod-)
|
||||
1.This same as 0, but GPS ground speed (sensor 16) is of type Speed in km/h. (FS-i6 10ch_MOD_i6_Programmer_V1_5.exe from https://github.com/benb0jangles/FlySky-i6-Mod-).
|
||||
|
||||
2.This same as 1, but GPS altitude (sensor 11) is of type ALT in m. (FS-i6 10ch_Timer_MOD_i6_Programmer_V1_4.exe from https://github.com/benb0jangles/FlySky-i6-Mod-)
|
||||
2.This same as 1, but GPS altitude (sensor 11) is of type ALT in m. (FS-i6 10ch_Timer_MOD_i6_Programmer_V1_4.exe from https://github.com/benb0jangles/FlySky-i6-Mod-).
|
||||
|
||||
3.This same as 2, but each sensor have its own sensor id. (FS-i6 10ch_Mavlink_MOD_i6_Programmer_V1_.exe from https://github.com/benb0jangles/FlySky-i6-Mod-):
|
||||
sensor 4 is of type S85,
|
||||
sensor 5 is of type ACC_Z,
|
||||
sensor 6 is of type CURRENT,
|
||||
sensor 7 is of type ALT,
|
||||
sensor 8 is of type HEADING,
|
||||
sensor 9 is of type DIST,
|
||||
sensor 10 is of type COG,
|
||||
sensor 10 is of type GALT,
|
||||
sensor 12 is of type GPS_LON,
|
||||
sensor 13 is of type GPS_LAT,
|
||||
sensor 14 is of type ACC_X,
|
||||
sensor 15 is of type ACC_Y,
|
||||
sensor 16 is of type SPEED.
|
||||
|
||||
4.This same as 3, but support 4 byte sensors. (fix_updater_03_16_21_33_1 from https://github.com/qba667/FlySkyI6/tree/master/release):
|
||||
sensor 7 is 4byte ALT, 12 is PRESURE or PITOT_SPEED if avaliable, 13 is GPS_STATUS, 14 is 4byte GPS_LON, 15 is 4byte GPS_LAT.
|
||||
This required a receiver with new firmware that support SNR, RSSI and long frames (For FS-IA6B since August 2016 or need upgrade to wersion 1.6 https://github.com/povlhp/FlySkyRxFirmware).
|
||||
|
||||
5.This same as 4, but sensor 3 is ARMED, 4 is MODE, 12 is CLIMB.
|
||||
|
||||
6.For hali9_updater_04_21_23_13.bin from https://www.rcgroups.com/forums/showthread.php?2486545-FlySky-FS-i6-8-channels-firmware-patch%21/page118 or https://github.com/benb0jangles/FlySky-i6-Mod-/tree/master/10ch%20qba667_hali9%20Updater sensor 4 is of type CURRENT, sensor 5 is of type HEADING, sensor 6 is of type COG, sensor 7 is of type CLIMB, sensor 8 is of type YAW, sensor 9 is of type DIST, sensor 10 is of type PRESURE or PITOT_SPEED if avaliable, sensor 11 is of type SPEED, sensor 12 is of type GPS_LAT, sensor 13 is of type GPS_LON, sensor 14 is of type GALT, sensor 15 is of type ALT, sensor 16 is of type S85.
|
||||
|
||||
7.This same as 6, but sensor 3 is GPS_STATUS, 10 is ARMED, 16 is MODE.
|
||||
|
||||
131.This same as 3, but sensor 16 (type SPEED) is in m/s.
|
||||
|
||||
132.This same as 4, but sensor 16 (type SPEED) is in m/s.
|
||||
|
||||
133.This same as 5, but sensor 16 (type SPEED) is in m/s.
|
||||
|
||||
134.This same as 6, but sensor 11 (type SPEED) is in m/s.
|
||||
|
||||
135.This same as 7, but sensor 11 (type SPEED) is in m/s.
|
||||
|
||||
### RX hardware
|
||||
|
||||
|
@ -304,7 +339,7 @@ Note that the FlySky/Turnigy FS-iA4B 4-Channel Receiver (http://www.flysky-cn.co
|
|||
|
||||
Case:
|
||||
|
||||
A. For use only IBUS RX connect directly Flysky IBUS-SERVO to FC-UART-TX.
|
||||
A. For use only IBUS RX connect directly Flysky IBUS-SERVO to FC-UART-RX.
|
||||
In configurator set RX on selected port, set receiver mode to RX_SERIAL and Receiver provider to IBUS.
|
||||
|
||||
B. For use only IBUS telemetry connect directly Flysky IBUS-SENS to FC-UART-TX.
|
||||
|
|
|
@ -117,5 +117,8 @@ flightModeForTelemetry_e getFlightModeForTelemetry(void)
|
|||
if (FLIGHT_MODE(HORIZON_MODE))
|
||||
return FLM_HORIZON;
|
||||
|
||||
if (FLIGHT_MODE(NAV_LAUNCH_MODE))
|
||||
return FLM_LAUNCH;
|
||||
|
||||
return FLM_ACRO;
|
||||
}
|
||||
}
|
||||
|
|
|
@ -184,10 +184,80 @@ static void pushOntoTail(uint8_t buffer[IBUS_MIN_LEN], size_t bufferLength, uint
|
|||
void initIbusTelemetry(void) {
|
||||
ibusSerialPortConfig = findSerialPortConfig(FUNCTION_TELEMETRY_IBUS);
|
||||
uint8_t type = telemetryConfig()->ibusTelemetryType;
|
||||
#if defined(GPS)
|
||||
if (type == 1 || type == 2) changeTypeIbusTelemetry(15, IBUS_MEAS_TYPE_SPE);
|
||||
if (type == 2) changeTypeIbusTelemetry(10, IBUS_MEAS_TYPE_ALT);
|
||||
uint8_t speed = type & 0x80;
|
||||
type = type & 0x7F;
|
||||
if (type == 3) {
|
||||
changeTypeIbusTelemetry(3, IBUS_MEAS_TYPE_S85, IBUS_MEAS_VALUE_STATUS);
|
||||
changeTypeIbusTelemetry(4, IBUS_MEAS_TYPE_ACC_Z, IBUS_MEAS_VALUE_ACC_Z);
|
||||
changeTypeIbusTelemetry(5, IBUS_MEAS_TYPE_CURRENT, IBUS_MEAS_VALUE_CURRENT);
|
||||
changeTypeIbusTelemetry(6, IBUS_MEAS_TYPE_ALT, IBUS_MEAS_VALUE_ALT);
|
||||
changeTypeIbusTelemetry(7, IBUS_MEAS_TYPE_HEADING, IBUS_MEAS_VALUE_HEADING);
|
||||
changeTypeIbusTelemetry(8, IBUS_MEAS_TYPE_DIST, IBUS_MEAS_VALUE_DIST);
|
||||
changeTypeIbusTelemetry(9, IBUS_MEAS_TYPE_COG, IBUS_MEAS_VALUE_COG);
|
||||
changeTypeIbusTelemetry(11,IBUS_MEAS_TYPE_GPS_LON, IBUS_MEAS_VALUE_GPS_LON2);
|
||||
changeTypeIbusTelemetry(12,IBUS_MEAS_TYPE_GPS_LAT, IBUS_MEAS_VALUE_GPS_LAT2);
|
||||
changeTypeIbusTelemetry(13,IBUS_MEAS_TYPE_ACC_X, IBUS_MEAS_VALUE_GPS_LON1);
|
||||
changeTypeIbusTelemetry(14,IBUS_MEAS_TYPE_ACC_Y, IBUS_MEAS_VALUE_GPS_LAT1);
|
||||
}
|
||||
if (type == 4) {
|
||||
changeTypeIbusTelemetry(3, IBUS_MEAS_TYPE_S85, IBUS_MEAS_VALUE_STATUS);
|
||||
#ifdef PITOT
|
||||
if (sensors(SENSOR_PITOT)) changeTypeIbusTelemetry(11,IBUS_MEAS_TYPE_VSPEED, IBUS_MEAS_VALUE_VSPEED);
|
||||
else
|
||||
#endif
|
||||
changeTypeIbusTelemetry(11,IBUS_MEAS_TYPE_PRES, IBUS_MEAS_VALUE_PRES);
|
||||
}
|
||||
if (type == 5) {
|
||||
changeTypeIbusTelemetry(2, IBUS_MEAS_TYPE_ARMED, IBUS_MEAS_VALUE_ARMED);
|
||||
changeTypeIbusTelemetry(3, IBUS_MEAS_TYPE_MODE, IBUS_MEAS_VALUE_MODE);
|
||||
changeTypeIbusTelemetry(11,IBUS_MEAS_TYPE_CLIMB, IBUS_MEAS_VALUE_CLIMB);
|
||||
}
|
||||
if (type == 4 || type == 5) {
|
||||
changeTypeIbusTelemetry(4, IBUS_MEAS_TYPE_ACC_Z, IBUS_MEAS_VALUE_ACC_Z);
|
||||
changeTypeIbusTelemetry(5, IBUS_MEAS_TYPE_CURRENT, IBUS_MEAS_VALUE_CURRENT);
|
||||
changeTypeIbusTelemetry(6, IBUS_MEAS_TYPE_S8A, IBUS_MEAS_VALUE_ALT4);
|
||||
changeTypeIbusTelemetry(7, IBUS_MEAS_TYPE_HEADING, IBUS_MEAS_VALUE_HEADING);
|
||||
changeTypeIbusTelemetry(8, IBUS_MEAS_TYPE_DIST, IBUS_MEAS_VALUE_DIST);
|
||||
changeTypeIbusTelemetry(9, IBUS_MEAS_TYPE_COG, IBUS_MEAS_VALUE_COG);
|
||||
changeTypeIbusTelemetry(12,IBUS_MEAS_TYPE_GPS_STATUS, IBUS_MEAS_VALUE_GPS_STATUS);
|
||||
changeTypeIbusTelemetry(13,IBUS_MEAS_TYPE_S88, IBUS_MEAS_VALUE_GPS_LON);
|
||||
changeTypeIbusTelemetry(14,IBUS_MEAS_TYPE_S89, IBUS_MEAS_VALUE_GPS_LAT);
|
||||
}
|
||||
if (type == 2 || type == 3 || type == 4 || type == 5)
|
||||
changeTypeIbusTelemetry(10, IBUS_MEAS_TYPE_GALT, IBUS_MEAS_VALUE_GALT);
|
||||
if (type == 1 || type == 2 || type == 3 || type == 4 || type == 5)
|
||||
changeTypeIbusTelemetry(15, IBUS_MEAS_TYPE_SPE, IBUS_MEAS_VALUE_SPE);
|
||||
if ((type == 3 || type == 4 || type == 5) && speed)
|
||||
changeTypeIbusTelemetry(15,IBUS_MEAS_TYPE_SPEED, IBUS_MEAS_VALUE_SPEED);
|
||||
if (type == 6) {
|
||||
#ifdef PITOT
|
||||
if (sensors(SENSOR_PITOT)) changeTypeIbusTelemetry(9,IBUS_MEAS_TYPE1_VERTICAL_SPEED, IBUS_MEAS_VALUE_VSPEED);
|
||||
else
|
||||
#endif
|
||||
changeTypeIbusTelemetry(9, IBUS_MEAS_TYPE1_PRES, IBUS_MEAS_VALUE_PRES);
|
||||
changeTypeIbusTelemetry(15, IBUS_MEAS_TYPE1_S85, IBUS_MEAS_VALUE_STATUS);
|
||||
}
|
||||
if (type == 7) {
|
||||
changeTypeIbusTelemetry(2, IBUS_MEAS_TYPE1_GPS_STATUS, IBUS_MEAS_VALUE_GPS_STATUS);
|
||||
changeTypeIbusTelemetry(9, IBUS_MEAS_TYPE1_ARMED, IBUS_MEAS_VALUE_ARMED);
|
||||
changeTypeIbusTelemetry(15,IBUS_MEAS_TYPE1_FLIGHT_MODE, IBUS_MEAS_VALUE_MODE);
|
||||
}
|
||||
if (type == 6 || type == 7) {
|
||||
if (batteryConfig()->currentMeterType == CURRENT_SENSOR_VIRTUAL)
|
||||
changeTypeIbusTelemetry(3, IBUS_MEAS_TYPE1_FUEL, IBUS_MEAS_VALUE_FUEL);
|
||||
else changeTypeIbusTelemetry(3, IBUS_MEAS_TYPE1_BAT_CURR, IBUS_MEAS_VALUE_CURRENT);
|
||||
changeTypeIbusTelemetry(4, IBUS_MEAS_TYPE1_CMP_HEAD, IBUS_MEAS_VALUE_HEADING);
|
||||
changeTypeIbusTelemetry(6, IBUS_MEAS_TYPE1_CLIMB_RATE, IBUS_MEAS_VALUE_CLIMB);
|
||||
changeTypeIbusTelemetry(5, IBUS_MEAS_TYPE1_COG, IBUS_MEAS_VALUE_COG);
|
||||
changeTypeIbusTelemetry(7, IBUS_MEAS_TYPE1_YAW, IBUS_MEAS_VALUE_ACC_Z);
|
||||
changeTypeIbusTelemetry(8, IBUS_MEAS_TYPE1_GPS_DIST, IBUS_MEAS_VALUE_DIST);
|
||||
if (speed) changeTypeIbusTelemetry(10,IBUS_MEAS_TYPE1_GROUND_SPEED, IBUS_MEAS_VALUE_SPEED);
|
||||
else changeTypeIbusTelemetry(10, IBUS_MEAS_TYPE1_SPE, IBUS_MEAS_VALUE_SPE);
|
||||
changeTypeIbusTelemetry(11,IBUS_MEAS_TYPE1_GPS_LAT, IBUS_MEAS_VALUE_GPS_LAT);
|
||||
changeTypeIbusTelemetry(12,IBUS_MEAS_TYPE1_GPS_LON, IBUS_MEAS_VALUE_GPS_LON);
|
||||
changeTypeIbusTelemetry(13,IBUS_MEAS_TYPE1_GPS_ALT, IBUS_MEAS_VALUE_GALT4);
|
||||
changeTypeIbusTelemetry(14,IBUS_MEAS_TYPE1_ALT, IBUS_MEAS_VALUE_ALT4);
|
||||
}
|
||||
ibusPortSharing = determinePortSharing(ibusSerialPortConfig, FUNCTION_TELEMETRY_IBUS);
|
||||
ibusTelemetryEnabled = false;
|
||||
}
|
||||
|
|
|
@ -39,6 +39,7 @@
|
|||
#include "sensors/acceleration.h"
|
||||
#include "sensors/battery.h"
|
||||
#include "sensors/sensors.h"
|
||||
#include "sensors/pitotmeter.h"
|
||||
|
||||
#include "flight/imu.h"
|
||||
#include "flight/failsafe.h"
|
||||
|
@ -60,27 +61,28 @@ typedef enum {
|
|||
IBUS_COMMAND_MEASUREMENT = 0xA0
|
||||
} ibusCommand_e;
|
||||
|
||||
static uint8_t SENSOR_ADDRESS_TYPE_LOOKUP[] = {
|
||||
IBUS_MEAS_TYPE_INTERNAL_VOLTAGE, // Address 0, sensor 1, not usable since it is reserved for internal voltage
|
||||
IBUS_MEAS_TYPE_EXTERNAL_VOLTAGE, // Address 1 ,sensor 2, VBAT
|
||||
IBUS_MEAS_TYPE_TEMPERATURE, // Address 2, sensor 3, Baro/Gyro Temp
|
||||
IBUS_MEAS_TYPE_RPM, // Address 3, sensor 4, Status AS RPM
|
||||
IBUS_MEAS_TYPE_RPM, // Address 4, sensor 5, MAG_COURSE in deg AS RPM
|
||||
IBUS_MEAS_TYPE_EXTERNAL_VOLTAGE, // Address 5, sensor 6, Current in A AS ExtV
|
||||
IBUS_MEAS_TYPE_EXTERNAL_VOLTAGE // Address 6, sensor 7, Baro Alt in cm AS ExtV
|
||||
#if defined(GPS)
|
||||
,IBUS_MEAS_TYPE_RPM, // Address 7, sensor 8, HOME_DIR in deg AS RPM
|
||||
IBUS_MEAS_TYPE_RPM, // Address 8, sensor 9, HOME_DIST in m AS RPM
|
||||
IBUS_MEAS_TYPE_RPM, // Address 9, sensor 10,GPS_COURSE in deg AS RPM
|
||||
IBUS_MEAS_TYPE_RPM, // Address 10,sensor 11,GPS_ALT in m AS RPM
|
||||
IBUS_MEAS_TYPE_RPM, // Address 11,sensor 12,GPS_LAT2 AS RPM 5678
|
||||
IBUS_MEAS_TYPE_RPM, // Address 12,sensor 13,GPS_LON2 AS RPM 6789
|
||||
IBUS_MEAS_TYPE_EXTERNAL_VOLTAGE, // Address 13,sensor 14,GPS_LAT1 AS ExtV -12.45 (-12.3456789 N)
|
||||
IBUS_MEAS_TYPE_EXTERNAL_VOLTAGE, // Address 14,sensor 15,GPS_LON1 AS ExtV -123.45 (-123.4567890 E)
|
||||
IBUS_MEAS_TYPE_RPM // Address 15,sensor 16,GPS_SPEED in km/h AS RPM
|
||||
#endif
|
||||
//IBUS_MEAS_TYPE_TX_VOLTAGE,
|
||||
//IBUS_MEAS_TYPE_ERR
|
||||
typedef struct IBUS_SENSOR {
|
||||
uint8_t type;
|
||||
uint8_t size;
|
||||
uint8_t value;
|
||||
} IBUS_SENSOR;
|
||||
static IBUS_SENSOR SENSOR_ADDRESS_TYPE_LOOKUP[] = {
|
||||
{.type = IBUS_MEAS_TYPE_INTERNAL_VOLTAGE, .size = 2, .value = IBUS_MEAS_VALUE_NONE }, // Address 0, sensor 1, not usable since it is reserved for internal voltage
|
||||
{.type = IBUS_MEAS_TYPE_EXTERNAL_VOLTAGE, .size = 2, .value = IBUS_MEAS_VALUE_EXTERNAL_VOLTAGE }, // Address 1 ,sensor 2, VBAT
|
||||
{.type = IBUS_MEAS_TYPE_TEMPERATURE, .size = 2, .value = IBUS_MEAS_VALUE_TEMPERATURE }, // Address 2, sensor 3, Baro/Gyro Temp
|
||||
{.type = IBUS_MEAS_TYPE_RPM, .size = 2, .value = IBUS_MEAS_VALUE_STATUS }, // Address 3, sensor 4, Status AS RPM
|
||||
{.type = IBUS_MEAS_TYPE_RPM, .size = 2, .value = IBUS_MEAS_VALUE_ACC_Z }, // Address 4, sensor 5, MAG_COURSE in deg AS RPM
|
||||
{.type = IBUS_MEAS_TYPE_EXTERNAL_VOLTAGE, .size = 2, .value = IBUS_MEAS_VALUE_CURRENT }, // Address 5, sensor 6, Current in A AS ExtV
|
||||
{.type = IBUS_MEAS_TYPE_EXTERNAL_VOLTAGE, .size = 2, .value = IBUS_MEAS_VALUE_ALT }, // Address 6, sensor 7, Baro Alt in cm AS ExtV
|
||||
{.type = IBUS_MEAS_TYPE_RPM, .size = 2, .value = IBUS_MEAS_VALUE_HEADING }, // Address 7, sensor 8, HOME_DIR in deg AS RPM
|
||||
{.type = IBUS_MEAS_TYPE_RPM, .size = 2, .value = IBUS_MEAS_VALUE_DIST }, // Address 8, sensor 9, HOME_DIST in m AS RPM
|
||||
{.type = IBUS_MEAS_TYPE_RPM, .size = 2, .value = IBUS_MEAS_VALUE_COG }, // Address 9, sensor 10,GPS_COURSE in deg AS RPM
|
||||
{.type = IBUS_MEAS_TYPE_RPM, .size = 2, .value = IBUS_MEAS_VALUE_GALT }, // Address 10,sensor 11,GPS_ALT in m AS RPM (ALT m)
|
||||
{.type = IBUS_MEAS_TYPE_RPM, .size = 2, .value = IBUS_MEAS_VALUE_GPS_LAT2 }, // Address 11,sensor 12,GPS_LAT2 AS RPM 5678 (-12.3456789 N)
|
||||
{.type = IBUS_MEAS_TYPE_RPM, .size = 2, .value = IBUS_MEAS_VALUE_GPS_LON2 }, // Address 12,sensor 13,GPS_LON2 AS RPM 6789 (-123.4567890 E)
|
||||
{.type = IBUS_MEAS_TYPE_EXTERNAL_VOLTAGE, .size = 2, .value = IBUS_MEAS_VALUE_GPS_LAT1 }, // Address 13,sensor 14,GPS_LAT1 AS ExtV -12.45 (-12.3456789 N)
|
||||
{.type = IBUS_MEAS_TYPE_EXTERNAL_VOLTAGE, .size = 2, .value = IBUS_MEAS_VALUE_GPS_LON1 }, // Address 14,sensor 15,GPS_LON1 AS ExtV -123.45 (-123.4567890 E)
|
||||
{.type = IBUS_MEAS_TYPE_RPM, .size = 2, .value = IBUS_MEAS_VALUE_SPE } // Address 15,sensor 16,GPS_SPEED in km/h AS RPM (SPE km\h)
|
||||
};
|
||||
|
||||
static serialPort_t *ibusSerialPort = NULL;
|
||||
|
@ -101,12 +103,19 @@ static uint8_t sendIbusCommand(ibusAddress_t address) {
|
|||
}
|
||||
|
||||
static uint8_t sendIbusSensorType(ibusAddress_t address) {
|
||||
uint8_t sendBuffer[] = { 0x06, IBUS_COMMAND_SENSOR_TYPE | address, SENSOR_ADDRESS_TYPE_LOOKUP[address], 0x02, 0x0, 0x0 };
|
||||
uint8_t sendBuffer[] = { 0x06, IBUS_COMMAND_SENSOR_TYPE | address, SENSOR_ADDRESS_TYPE_LOOKUP[address].type, SENSOR_ADDRESS_TYPE_LOOKUP[address].size, 0x0, 0x0 };
|
||||
return transmitIbusPacket(sendBuffer, sizeof sendBuffer);
|
||||
}
|
||||
|
||||
static uint8_t sendIbusMeasurement(ibusAddress_t address, uint16_t measurement) {
|
||||
uint8_t sendBuffer[] = { 0x06, IBUS_COMMAND_MEASUREMENT | address, measurement & 0xFF, measurement >> 8, 0x0, 0x0 };
|
||||
static uint8_t sendIbusMeasurement2(ibusAddress_t address, uint16_t measurement) {
|
||||
uint8_t sendBuffer[] = { 0x06, IBUS_COMMAND_MEASUREMENT | address, measurement & 0xFF, (measurement >> 8) & 0xFF, 0x0, 0x0 };
|
||||
return transmitIbusPacket(sendBuffer, sizeof sendBuffer);
|
||||
}
|
||||
|
||||
static uint8_t sendIbusMeasurement4(ibusAddress_t address, int32_t measurement) {
|
||||
uint8_t sendBuffer[] = { 0x08, IBUS_COMMAND_MEASUREMENT | address,
|
||||
measurement & 0xFF, (measurement >> 8) & 0xFF, (measurement >> 16) & 0xFF, (measurement >> 24) & 0xFF,
|
||||
0x0, 0x0 };
|
||||
return transmitIbusPacket(sendBuffer, sizeof sendBuffer);
|
||||
}
|
||||
|
||||
|
@ -119,76 +128,149 @@ static ibusAddress_t getAddress(uint8_t ibusPacket[static IBUS_MIN_LEN]) {
|
|||
}
|
||||
|
||||
// MANUAL, ACRO, ANGLE, HRZN, ALTHOLD, POSHOLD, RTH, WP, LAUNCH, FAILSAFE
|
||||
static uint8_t flightModeToIBusTelemetryMode[FLM_COUNT] = { 0, 1, 3, 2, 5, 6, 7, 4, 8, 9 };
|
||||
|
||||
static uint8_t flightModeToIBusTelemetryMode1[FLM_COUNT] = { 0, 1, 3, 2, 5, 6, 7, 4, 8, 9 };
|
||||
static uint8_t flightModeToIBusTelemetryMode2[FLM_COUNT] = { 5, 1, 0, 7, 2, 8, 6, 3, 4, 9 };
|
||||
static uint8_t dispatchMeasurementRequest(ibusAddress_t address) {
|
||||
if (address == 1) { //2. VBAT
|
||||
return sendIbusMeasurement(address, vbat * 10);
|
||||
} else if (address == 2) { //3. BARO_TEMP\GYRO_TEMP
|
||||
if (sensors(SENSOR_BARO)) {
|
||||
return sendIbusMeasurement(address, (uint16_t) ((baro.baroTemperature + 50) / 10 + IBUS_TEMPERATURE_OFFSET)); //int32_t
|
||||
} else {
|
||||
/*
|
||||
* There is no temperature data
|
||||
* assuming (baro.baroTemperature + 50) / 10
|
||||
* 0 degrees (no sensor) equals 50 / 10 = 5
|
||||
*/
|
||||
return sendIbusMeasurement(address, (uint16_t) (5 + IBUS_TEMPERATURE_OFFSET)); //int16_t
|
||||
#if defined(GPS)
|
||||
uint8_t fix = 0;
|
||||
if (sensors(SENSOR_GPS)) {
|
||||
if (gpsSol.fixType == GPS_NO_FIX) fix = 1;
|
||||
else if (gpsSol.fixType == GPS_FIX_2D) fix = 2;
|
||||
else if (gpsSol.fixType == GPS_FIX_3D) fix = 3;
|
||||
}
|
||||
#endif
|
||||
if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_TEMPERATURE) { //BARO_TEMP\GYRO_TEMP
|
||||
if (sensors(SENSOR_BARO)) return sendIbusMeasurement2(address, (uint16_t) ((baro.baroTemperature + 50) / 10 + IBUS_TEMPERATURE_OFFSET)); //int32_t
|
||||
else {
|
||||
/*
|
||||
* There is no temperature data
|
||||
* assuming (baro.baroTemperature + 50) / 10
|
||||
* 0 degrees (no sensor) equals 50 / 10 = 5
|
||||
*/
|
||||
return sendIbusMeasurement2(address, (uint16_t) (5 + IBUS_TEMPERATURE_OFFSET)); //int16_t
|
||||
}
|
||||
} else if (address == 3) { //4. STATUS (sat num AS #0, FIX AS 0, HDOP AS 0, Mode AS 0)
|
||||
int16_t status = flightModeToIBusTelemetryMode[getFlightModeForTelemetry()];
|
||||
} else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_RPM) {
|
||||
return sendIbusMeasurement2(address, (uint16_t) (rcCommand[THROTTLE]));
|
||||
} else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_EXTERNAL_VOLTAGE) { //VBAT
|
||||
return sendIbusMeasurement2(address, vbat * 10);
|
||||
} else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_CURRENT) { //CURR in 10*mA, 1 = 10 mA
|
||||
if (feature(FEATURE_CURRENT_METER)) return sendIbusMeasurement2(address, (uint16_t) amperage); //int32_t
|
||||
else return sendIbusMeasurement2(address, 0);
|
||||
} else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_FUEL) { //capacity in mAh
|
||||
if (feature(FEATURE_CURRENT_METER)) return sendIbusMeasurement2(address, (uint16_t) mAhDrawn); //int32_t
|
||||
else return sendIbusMeasurement2(address, 0);
|
||||
} else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_CLIMB) {
|
||||
return sendIbusMeasurement2(address, (int16_t) (getEstimatedActualVelocity(Z))); //
|
||||
} else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_ACC_Z) { //MAG_COURSE 0-360*, 0=north
|
||||
return sendIbusMeasurement2(address, (uint16_t) (attitude.values.yaw * 10)); //in ddeg -> cdeg, 1ddeg = 10cdeg
|
||||
} else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_ACC_Y) { //PITCH in
|
||||
return sendIbusMeasurement2(address, (uint16_t) (-attitude.values.pitch * 10)); //in ddeg -> cdeg, 1ddeg = 10cdeg
|
||||
} else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_ACC_X) { //ROLL in
|
||||
return sendIbusMeasurement2(address, (uint16_t) (attitude.values.roll * 10)); //in ddeg -> cdeg, 1ddeg = 10cdeg
|
||||
} else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_VSPEED) { //Speed cm/s
|
||||
#ifdef PITOT
|
||||
if (sensors(SENSOR_PITOT)) return sendIbusMeasurement2(address, (uint16_t) (pitot.airSpeed)); //int32_t
|
||||
else
|
||||
#endif
|
||||
return sendIbusMeasurement2(address, 0);
|
||||
} else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_ARMED) { //motorArmed
|
||||
if (ARMING_FLAG(ARMED)) return sendIbusMeasurement2(address, 0);
|
||||
else return sendIbusMeasurement2(address, 1);
|
||||
} else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_MODE) {
|
||||
uint16_t flightMode = flightModeToIBusTelemetryMode2[getFlightModeForTelemetry()];
|
||||
return sendIbusMeasurement2(address, flightMode);
|
||||
} else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_PRES) { //PRESSURE in dPa -> 9876 is 987.6 hPa
|
||||
if (sensors(SENSOR_BARO)) return sendIbusMeasurement2(address, (int16_t) (baro.baroPressure / 10)); //int32_t
|
||||
else return sendIbusMeasurement2(address, 0);
|
||||
} else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_ALT) { //BARO_ALT in cm => m
|
||||
if (sensors(SENSOR_BARO)) return sendIbusMeasurement2(address, (uint16_t) baro.BaroAlt); //int32_t
|
||||
else return sendIbusMeasurement2(address, 0);
|
||||
} else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_ALT4) { //BARO_ALT //In cm => m
|
||||
if (sensors(SENSOR_BARO)) return sendIbusMeasurement4(address, (int32_t) baro.BaroAlt); //int32_t
|
||||
else return sendIbusMeasurement4(address, 0);
|
||||
} else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_STATUS) { //STATUS sat num AS #0, FIX AS 0, HDOP AS 0, Mode AS 0
|
||||
uint16_t status = flightModeToIBusTelemetryMode1[getFlightModeForTelemetry()];
|
||||
#if defined(GPS)
|
||||
if (sensors(SENSOR_GPS)) {
|
||||
status += gpsSol.numSat * 1000;
|
||||
if (gpsSol.fixType == GPS_NO_FIX) status += 100;
|
||||
else if (gpsSol.fixType == GPS_FIX_2D) status += 200;
|
||||
else if (gpsSol.fixType == GPS_FIX_3D) status += 300;
|
||||
if (STATE(GPS_FIX_HOME)) status += 500; {
|
||||
status += constrain(gpsSol.hdop / 1000, 0, 9) * 10;
|
||||
}
|
||||
status += fix * 100;
|
||||
if (STATE(GPS_FIX_HOME)) status += 500;
|
||||
status += constrain(gpsSol.hdop / 1000, 0, 9) * 10;
|
||||
}
|
||||
#endif
|
||||
return sendIbusMeasurement(address, (uint16_t) status);
|
||||
} else if (address == 4) { //5. MAG_COURSE (0-360*, 0=north) //In ddeg ==> deg, 10ddeg = 1deg
|
||||
return sendIbusMeasurement(address, (uint16_t) (attitude.values.yaw / 10));
|
||||
} else if (address == 5) { //6. CURR //In 10*mA, 1 = 10 mA
|
||||
if (feature(FEATURE_CURRENT_METER)) return sendIbusMeasurement(address, (uint16_t) amperage); //int32_t
|
||||
else return sendIbusMeasurement(address, 0);
|
||||
} else if (address == 6) { //7. BARO_ALT //In cm => m
|
||||
if (sensors(SENSOR_BARO)) return sendIbusMeasurement(address, (uint16_t) baro.BaroAlt); //int32_t
|
||||
else return sendIbusMeasurement(address, 0);
|
||||
}
|
||||
return sendIbusMeasurement2(address, status);
|
||||
} else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_HEADING) { //HOME_DIR 0-360deg
|
||||
#if defined(GPS)
|
||||
else if (address == 7) { //8. HOME_DIR (0-360deg, 0=head)
|
||||
if (sensors(SENSOR_GPS)) return sendIbusMeasurement(address, (uint16_t) GPS_directionToHome); //int16_t
|
||||
else return sendIbusMeasurement(address, 0);
|
||||
} else if (address == 8) { //9. HOME_DIST //In m
|
||||
if (sensors(SENSOR_GPS)) return sendIbusMeasurement(address, (uint16_t) GPS_distanceToHome); //uint16_t
|
||||
else return sendIbusMeasurement(address, 0);
|
||||
} else if (address == 9) { //10.GPS_COURSE (0-360deg, 0=north)
|
||||
if (sensors(SENSOR_GPS)) return sendIbusMeasurement(address, (uint16_t) (gpsSol.groundCourse / 10)); //int16_t
|
||||
else return sendIbusMeasurement(address, 0);
|
||||
} else if (address == 10) { //11. GPS_ALT //In cm => m
|
||||
if (sensors(SENSOR_GPS) && STATE(GPS_FIX)) return sendIbusMeasurement(address, (uint16_t) (gpsSol.llh.alt / 100));
|
||||
else return sendIbusMeasurement(address, 0);
|
||||
} else if (address == 11) { //12. GPS_LAT2 //Lattitude * 1e+7
|
||||
if (sensors(SENSOR_GPS)) return sendIbusMeasurement(address, (uint16_t) ((gpsSol.llh.lat % 100000)/10));
|
||||
else return sendIbusMeasurement(address, 0);
|
||||
} else if (address == 12) { //13. GPS_LON2 //Longitude * 1e+7
|
||||
if (sensors(SENSOR_GPS)) return sendIbusMeasurement(address, (uint16_t) ((gpsSol.llh.lon % 100000)/10));
|
||||
else return sendIbusMeasurement(address, 0);
|
||||
} else if (address == 13) { //14. GPS_LAT1 //Lattitude * 1e+7
|
||||
if (sensors(SENSOR_GPS)) return sendIbusMeasurement(address, (uint16_t) (gpsSol.llh.lat / 100000));
|
||||
else return sendIbusMeasurement(address, 0);
|
||||
} else if (address == 14) { //15. GPS_LON1 //Longitude * 1e+7
|
||||
if (sensors(SENSOR_GPS)) return sendIbusMeasurement(address, (uint16_t) (gpsSol.llh.lon / 100000));
|
||||
else return sendIbusMeasurement(address, 0);
|
||||
} else if (address == 15) { //16. GPS_SPEED //In cm/s => km/h, 1cm/s = 0.0194384449 knots
|
||||
if (sensors(SENSOR_GPS)) return sendIbusMeasurement(address, (uint16_t) gpsSol.groundSpeed * 1944 / 10000); //int16_t
|
||||
else return sendIbusMeasurement(address, 0);
|
||||
}
|
||||
if (sensors(SENSOR_GPS)) return sendIbusMeasurement2(address, (uint16_t) GPS_directionToHome); else //int16_t
|
||||
#endif
|
||||
else return 0;
|
||||
return sendIbusMeasurement2(address, 0);
|
||||
} else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_DIST) { //HOME_DIST in m
|
||||
#if defined(GPS)
|
||||
if (sensors(SENSOR_GPS)) return sendIbusMeasurement2(address, (uint16_t) GPS_distanceToHome); else //uint16_t
|
||||
#endif
|
||||
return sendIbusMeasurement2(address, 0);
|
||||
} else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_SPE) { //GPS_SPEED in cm/s => km/h, 1cm/s = 0.036 km/h
|
||||
#if defined(GPS)
|
||||
if (sensors(SENSOR_GPS)) return sendIbusMeasurement2(address, (uint16_t) gpsSol.groundSpeed * 36 / 100); else //int16_t
|
||||
#endif
|
||||
return sendIbusMeasurement2(address, 0);
|
||||
} else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_SPEED) {//SPEED in cm/s
|
||||
#if defined(GPS)
|
||||
if (sensors(SENSOR_GPS)) return sendIbusMeasurement2(address, (uint16_t) gpsSol.groundSpeed); //int16_t
|
||||
#endif
|
||||
return sendIbusMeasurement2(address, 0);
|
||||
} else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_COG) { //GPS_COURSE (0-360deg, 0=north)
|
||||
#if defined(GPS)
|
||||
if (sensors(SENSOR_GPS)) return sendIbusMeasurement2(address, (uint16_t) (gpsSol.groundCourse / 10)); else //int16_t
|
||||
#endif
|
||||
return sendIbusMeasurement2(address, 0);
|
||||
} else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_GPS_STATUS) { //GPS_STATUS fix sat
|
||||
#if defined(GPS)
|
||||
if (sensors(SENSOR_GPS)) return sendIbusMeasurement2(address, (((uint16_t)fix)<<8) + gpsSol.numSat); else //uint8_t, uint8_t
|
||||
#endif
|
||||
return sendIbusMeasurement2(address, 0);
|
||||
} else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_GPS_LAT) { //4byte
|
||||
#if defined(GPS)
|
||||
if (sensors(SENSOR_GPS)) return sendIbusMeasurement4(address, (int32_t)gpsSol.llh.lat); else //int32_t
|
||||
#endif
|
||||
return sendIbusMeasurement4(address, 0);
|
||||
} else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_GPS_LON) { //4byte
|
||||
#if defined(GPS)
|
||||
if (sensors(SENSOR_GPS)) return sendIbusMeasurement4(address, (int32_t)gpsSol.llh.lon); else //int32_t
|
||||
#endif
|
||||
return sendIbusMeasurement4(address, 0);
|
||||
} else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_GPS_LAT1) { //GPS_LAT1 //Lattitude * 1e+7
|
||||
#if defined(GPS)
|
||||
if (sensors(SENSOR_GPS)) return sendIbusMeasurement2(address, (uint16_t) (gpsSol.llh.lat / 100000)); else
|
||||
#endif
|
||||
return sendIbusMeasurement2(address, 0);
|
||||
} else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_GPS_LON1) { //GPS_LON1 //Longitude * 1e+7
|
||||
#if defined(GPS)
|
||||
if (sensors(SENSOR_GPS)) return sendIbusMeasurement2(address, (uint16_t) (gpsSol.llh.lon / 100000)); else
|
||||
#endif
|
||||
return sendIbusMeasurement2(address, 0);
|
||||
} else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_GPS_LAT2) { //GPS_LAT2 //Lattitude * 1e+7
|
||||
#if defined(GPS)
|
||||
if (sensors(SENSOR_GPS)) return sendIbusMeasurement2(address, (uint16_t) ((gpsSol.llh.lat % 100000)/10));
|
||||
#endif
|
||||
return sendIbusMeasurement2(address, 0);
|
||||
} else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_GPS_LON2) { //GPS_LON2 //Longitude * 1e+7
|
||||
#if defined(GPS)
|
||||
if (sensors(SENSOR_GPS)) return sendIbusMeasurement2(address, (uint16_t) ((gpsSol.llh.lon % 100000)/10)); else
|
||||
#endif
|
||||
return sendIbusMeasurement2(address, 0);
|
||||
} else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_GALT4) { //GPS_ALT //In cm => m
|
||||
#if defined(GPS)
|
||||
if (sensors(SENSOR_GPS)) return sendIbusMeasurement4(address, (int32_t) (gpsSol.llh.alt)); else //int32_t
|
||||
#endif
|
||||
return sendIbusMeasurement4(address, 0);
|
||||
} else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_GALT) { //GPS_ALT //In cm => m
|
||||
#if defined(GPS)
|
||||
if (sensors(SENSOR_GPS)) return sendIbusMeasurement2(address, (uint16_t) (gpsSol.llh.alt / 100)); else //int32_t
|
||||
#endif
|
||||
return sendIbusMeasurement2(address, 0);
|
||||
}
|
||||
else return 0;
|
||||
}
|
||||
|
||||
uint8_t respondToIbusRequest(uint8_t ibusPacket[static IBUS_RX_BUF_LEN]) {
|
||||
|
@ -209,8 +291,13 @@ void initSharedIbusTelemetry(serialPort_t *port) {
|
|||
ibusSerialPort = port;
|
||||
}
|
||||
|
||||
void changeTypeIbusTelemetry(uint8_t id, uint8_t type) {
|
||||
SENSOR_ADDRESS_TYPE_LOOKUP[id] = type;
|
||||
void changeTypeIbusTelemetry(uint8_t id, uint8_t type, uint8_t value) {
|
||||
SENSOR_ADDRESS_TYPE_LOOKUP[id].type = type;
|
||||
SENSOR_ADDRESS_TYPE_LOOKUP[id].value = value;
|
||||
if (value == IBUS_MEAS_VALUE_GPS) SENSOR_ADDRESS_TYPE_LOOKUP[id].size = 14;
|
||||
else if (value == IBUS_MEAS_VALUE_GPS_LAT || value == IBUS_MEAS_VALUE_GPS_LON || value == IBUS_MEAS_VALUE_ALT4 || value == IBUS_MEAS_VALUE_GALT4)
|
||||
SENSOR_ADDRESS_TYPE_LOOKUP[id].size = 4;
|
||||
else SENSOR_ADDRESS_TYPE_LOOKUP[id].size = 2;
|
||||
}
|
||||
|
||||
#endif //defined(TELEMETRY) && defined(TELEMETRY_IBUS)
|
||||
|
|
|
@ -19,10 +19,10 @@
|
|||
|
||||
#include "io/serial.h"
|
||||
|
||||
#define IBUS_CHECKSUM_SIZE (2)
|
||||
#define IBUS_TASK_PERIOD_US (500)
|
||||
#define IBUS_BAUDRATE (115200)
|
||||
#define IBUS_CYCLE_TIME_MS (8)
|
||||
#define IBUS_CHECKSUM_SIZE (2)
|
||||
#define IBUS_MIN_LEN (2 + IBUS_CHECKSUM_SIZE)
|
||||
#define IBUS_MAX_TX_LEN (6)
|
||||
#define IBUS_MAX_RX_LEN (4)
|
||||
|
@ -31,24 +31,134 @@
|
|||
#if defined(TELEMETRY) && defined(TELEMETRY_IBUS)
|
||||
|
||||
typedef enum {
|
||||
IBUS_MEAS_TYPE_INTERNAL_VOLTAGE = 0x00, // Internal Voltage
|
||||
IBUS_MEAS_TYPE_TEMPERATURE = 0x01, // Temperature -##0.0 C, 0=-40.0 C, 400=0.0 C, 65535=6513.5 C
|
||||
IBUS_MEAS_TYPE_RPM = 0x02, // Rotation RPM, ####0RPM, 0=0RPM, 65535=65535RPM
|
||||
IBUS_MEAS_TYPE_EXTERNAL_VOLTAGE = 0x03, // External Voltage, -##0.00V, 0=0.00V, 32767=327.67V, 32768=na, 32769=-327.67V, 65535=-0.01V
|
||||
IBUS_MEAS_TYPE_INTERNAL_VOLTAGE = 0x00, //0 Internal Voltage
|
||||
IBUS_MEAS_TYPE_TEMPERATURE = 0x01, //0 Temperature -##0.0 C, 0=-40.0 C, 400=0.0 C, 65535=6513.5 C
|
||||
IBUS_MEAS_TYPE_RPM = 0x02, //0 Rotation RPM, ####0RPM, 0=0RPM, 65535=65535RPM
|
||||
IBUS_MEAS_TYPE_EXTERNAL_VOLTAGE = 0x03, //0 External Voltage, -##0.00V, 0=0.00V, 32767=327.67V, 32768=na, 32769=-327.67V, 65535=-0.01V
|
||||
IBUS_MEAS_TYPE_HEADING = 0x04, //3
|
||||
IBUS_MEAS_TYPE_CURRENT = 0x05, //3
|
||||
IBUS_MEAS_TYPE_CLIMB = 0x06, //3
|
||||
IBUS_MEAS_TYPE_ACC_Z = 0x07, //3
|
||||
IBUS_MEAS_TYPE_ACC_Y = 0x08, //3
|
||||
IBUS_MEAS_TYPE_ACC_X = 0x09, //3
|
||||
IBUS_MEAS_TYPE_VSPEED = 0x0a, //3
|
||||
IBUS_MEAS_TYPE_SPEED = 0x0b, //3
|
||||
IBUS_MEAS_TYPE_DIST = 0x0c, //3
|
||||
IBUS_MEAS_TYPE_ARMED = 0x0d, //3
|
||||
IBUS_MEAS_TYPE_MODE = 0x0e, //3
|
||||
//IBUS_MEAS_TYPE_RESERVED = 0x0f, //3
|
||||
IBUS_MEAS_TYPE_PRES = 0x41, // Pressure, not work
|
||||
IBUS_MEAS_TYPE_ODO1 = 0x7c, // Odometer1, 0.0km, 0.0 only
|
||||
IBUS_MEAS_TYPE_ODO2 = 0x7d, // Odometer2, 0.0km, 0.0 only
|
||||
IBUS_MEAS_TYPE_SPE = 0x7e, // Speed km/h, ###0km/h, 0=0Km/h, 1000=100Km/h
|
||||
IBUS_MEAS_TYPE_ALT = 0xf9, // Altitude m, not work
|
||||
IBUS_MEAS_TYPE_SNR = 0xfa, // SNR, not work
|
||||
IBUS_MEAS_TYPE_NOISE = 0xfb, // Noise, not work
|
||||
IBUS_MEAS_TYPE_RSSI = 0xfc, // RSSI, not work
|
||||
IBUS_MEAS_TYPE_ERR = 0xfe // Error rate, #0%
|
||||
//IBUS_MEAS_TYPE_ODO1 = 0x7c, // Odometer1, 0.0km, 0.0 only
|
||||
//IBUS_MEAS_TYPE_ODO2 = 0x7d, // Odometer2, 0.0km, 0.0 only
|
||||
IBUS_MEAS_TYPE_SPE = 0x7e, //1 Speed km/h, ###0km/h, 0=0Km/h, 1000=100Km/h
|
||||
IBUS_MEAS_TYPE_COG = 0x80, //3 2byte course deg * 100, 0.0..359.99
|
||||
IBUS_MEAS_TYPE_GPS_STATUS = 0x81, //3 2byte special parse byte by byte
|
||||
IBUS_MEAS_TYPE_GPS_LON = 0x82, //3 4byte signed WGS84 in deg * 1E7, format into %u?%02u'%02u
|
||||
IBUS_MEAS_TYPE_GPS_LAT = 0x83, //3 4byte signed WGS84 in deg * 1E7
|
||||
IBUS_MEAS_TYPE_ALT = 0x84, //3 2byte signed barometer alt
|
||||
IBUS_MEAS_TYPE_S85 = 0x85, //3
|
||||
IBUS_MEAS_TYPE_S86 = 0x86, //3
|
||||
IBUS_MEAS_TYPE_S87 = 0x87, //3
|
||||
IBUS_MEAS_TYPE_S88 = 0x88, //3
|
||||
IBUS_MEAS_TYPE_S89 = 0x89, //3
|
||||
IBUS_MEAS_TYPE_S8A = 0x8A, //3
|
||||
IBUS_MEAS_TYPE_GALT = 0xf9, //2 Altitude m, not work
|
||||
//IBUS_MEAS_TYPE_SNR = 0xfa, // SNR, not work
|
||||
//IBUS_MEAS_TYPE_NOISE = 0xfb, // Noise, not work
|
||||
//IBUS_MEAS_TYPE_RSSI = 0xfc, // RSSI, not work
|
||||
IBUS_MEAS_TYPE_GPS = 0xfd // 1byte fix 1byte satellites 4byte LAT 4byte LON 4byte alt, return UNKNOWN sensor and no formating
|
||||
//IBUS_MEAS_TYPE_ERR = 0xfe //0 Error rate, #0%
|
||||
} ibusSensorType_e;
|
||||
|
||||
typedef enum {
|
||||
IBUS_MEAS_TYPE1_INTV = 0x00,
|
||||
IBUS_MEAS_TYPE1_TEM = 0x01,
|
||||
IBUS_MEAS_TYPE1_MOT = 0x02,
|
||||
IBUS_MEAS_TYPE1_EXTV = 0x03,
|
||||
IBUS_MEAS_TYPE1_CELL = 0x04,
|
||||
IBUS_MEAS_TYPE1_BAT_CURR = 0x05,
|
||||
IBUS_MEAS_TYPE1_FUEL = 0x06,
|
||||
IBUS_MEAS_TYPE1_RPM = 0x07,
|
||||
IBUS_MEAS_TYPE1_CMP_HEAD = 0x08,
|
||||
IBUS_MEAS_TYPE1_CLIMB_RATE = 0x09,
|
||||
IBUS_MEAS_TYPE1_COG = 0x0a,
|
||||
IBUS_MEAS_TYPE1_GPS_STATUS = 0x0b,
|
||||
IBUS_MEAS_TYPE1_ACC_X = 0x0c,
|
||||
IBUS_MEAS_TYPE1_ACC_Y = 0x0d,
|
||||
IBUS_MEAS_TYPE1_ACC_Z = 0x0e,
|
||||
IBUS_MEAS_TYPE1_ROLL = 0x0f,
|
||||
IBUS_MEAS_TYPE1_PITCH = 0x10,
|
||||
IBUS_MEAS_TYPE1_YAW = 0x11,
|
||||
IBUS_MEAS_TYPE1_VERTICAL_SPEED = 0x12,
|
||||
IBUS_MEAS_TYPE1_GROUND_SPEED = 0x13,
|
||||
IBUS_MEAS_TYPE1_GPS_DIST = 0x14,
|
||||
IBUS_MEAS_TYPE1_ARMED = 0x15,
|
||||
IBUS_MEAS_TYPE1_FLIGHT_MODE = 0x16,
|
||||
IBUS_MEAS_TYPE1_PRES = 0x41,
|
||||
//IBUS_MEAS_TYPE1_ODO1 = 0x7c,
|
||||
//IBUS_MEAS_TYPE1_ODO2 = 0x7d,
|
||||
IBUS_MEAS_TYPE1_SPE = 0x7e,
|
||||
//IBUS_MEAS_TYPE1_TX_V = 0x7f,
|
||||
IBUS_MEAS_TYPE1_GPS_LAT = 0x80,
|
||||
IBUS_MEAS_TYPE1_GPS_LON = 0x81,
|
||||
IBUS_MEAS_TYPE1_GPS_ALT = 0x82,
|
||||
IBUS_MEAS_TYPE1_ALT = 0x83,
|
||||
IBUS_MEAS_TYPE1_S84 = 0x84,
|
||||
IBUS_MEAS_TYPE1_S85 = 0x85,
|
||||
IBUS_MEAS_TYPE1_S86 = 0x86,
|
||||
IBUS_MEAS_TYPE1_S87 = 0x87,
|
||||
IBUS_MEAS_TYPE1_S88 = 0x88,
|
||||
IBUS_MEAS_TYPE1_S89 = 0x89,
|
||||
IBUS_MEAS_TYPE1_S8a = 0x8a
|
||||
//IBUS_MEAS_TYPE1_SNR = 0xfa,
|
||||
//IBUS_MEAS_TYPE1_NOISE = 0xfb,
|
||||
//IBUS_MEAS_TYPE1_RSSI = 0xfc,
|
||||
//IBUS_MEAS_TYPE1_ERR = 0xfe
|
||||
} ibusSensorType1_e;
|
||||
|
||||
typedef enum {
|
||||
IBUS_MEAS_VALUE_NONE = 0x00, //2
|
||||
IBUS_MEAS_VALUE_TEMPERATURE = 0x01, //2
|
||||
IBUS_MEAS_VALUE_MOT = 0x02, //2
|
||||
IBUS_MEAS_VALUE_EXTERNAL_VOLTAGE = 0x03, //2
|
||||
IBUS_MEAS_VALUE_CELL = 0x04, //2
|
||||
IBUS_MEAS_VALUE_CURRENT = 0x05, //2
|
||||
IBUS_MEAS_VALUE_FUEL = 0x06, //2
|
||||
IBUS_MEAS_VALUE_RPM = 0x07, //2
|
||||
IBUS_MEAS_VALUE_HEADING = 0x08, //2
|
||||
IBUS_MEAS_VALUE_CLIMB = 0x09, //2
|
||||
IBUS_MEAS_VALUE_COG = 0x0a, //2
|
||||
IBUS_MEAS_VALUE_GPS_STATUS = 0x0b, //2
|
||||
IBUS_MEAS_VALUE_ACC_X = 0x0c, //2
|
||||
IBUS_MEAS_VALUE_ACC_Y = 0x0d, //2
|
||||
IBUS_MEAS_VALUE_ACC_Z = 0x0e, //2
|
||||
IBUS_MEAS_VALUE_ROLL = 0x0f, //2
|
||||
IBUS_MEAS_VALUE_PITCH = 0x10, //2
|
||||
IBUS_MEAS_VALUE_YAW = 0x11, //2
|
||||
IBUS_MEAS_VALUE_VSPEED = 0x12, //2
|
||||
IBUS_MEAS_VALUE_SPEED = 0x13, //2
|
||||
IBUS_MEAS_VALUE_DIST = 0x14, //2
|
||||
IBUS_MEAS_VALUE_ARMED = 0x15, //2
|
||||
IBUS_MEAS_VALUE_MODE = 0x16, //2
|
||||
IBUS_MEAS_VALUE_PRES = 0x41, //2
|
||||
IBUS_MEAS_VALUE_SPE = 0x7e, //2
|
||||
IBUS_MEAS_VALUE_GPS_LAT = 0x80, //4
|
||||
IBUS_MEAS_VALUE_GPS_LON = 0x81, //4
|
||||
IBUS_MEAS_VALUE_GALT4 = 0x82, //4
|
||||
IBUS_MEAS_VALUE_ALT4 = 0x83, //4
|
||||
IBUS_MEAS_VALUE_GALT = 0x84, //2
|
||||
IBUS_MEAS_VALUE_ALT = 0x85, //2
|
||||
IBUS_MEAS_VALUE_STATUS = 0x87, //2
|
||||
IBUS_MEAS_VALUE_GPS_LAT1 = 0x88, //2
|
||||
IBUS_MEAS_VALUE_GPS_LON1 = 0x89, //2
|
||||
IBUS_MEAS_VALUE_GPS_LAT2 = 0x90, //2
|
||||
IBUS_MEAS_VALUE_GPS_LON2 = 0x91, //2
|
||||
IBUS_MEAS_VALUE_GPS = 0xfd //14 1byte fix 1byte satellites 4byte LAT 4byte LON 4byte alt
|
||||
} ibusSensorValue_e;
|
||||
|
||||
uint8_t respondToIbusRequest(uint8_t ibusPacket[static IBUS_RX_BUF_LEN]);
|
||||
void initSharedIbusTelemetry(serialPort_t *port);
|
||||
void changeTypeIbusTelemetry(uint8_t id, uint8_t type);
|
||||
void changeTypeIbusTelemetry(uint8_t id, uint8_t type, uint8_t value);
|
||||
|
||||
#endif //defined(TELEMETRY) && defined(TELEMETRY_IBUS)
|
||||
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue