Blackbox device type 'file' (SITL) considered working when file handler is available
[inav.git] / src / main / telemetry / ibus_shared.h
blob6e0692f1b862497961c7c52e7804d2e1d654434c
1 /*
2 * This file is part of Cleanflight.
4 * Cleanflight is free software: you can redistribute it and/or modify
5 * it under the terms of the GNU General Public License as published by
6 * the Free Software Foundation, either version 3 of the License, or
7 * (at your option) any later version.
9 * Cleanflight is distributed in the hope that it will be useful,
10 * but WITHOUT ANY WARRANTY; without even the implied warranty of
11 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 * GNU General Public License for more details.
14 * You should have received a copy of the GNU General Public License
15 * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
18 #pragma once
20 #include "io/serial.h"
22 #define IBUS_TASK_PERIOD_US (500)
23 #define IBUS_BAUDRATE (115200)
24 #define IBUS_CYCLE_TIME_MS (8)
25 #define IBUS_CHECKSUM_SIZE (2)
26 #define IBUS_MIN_LEN (2 + IBUS_CHECKSUM_SIZE)
27 #define IBUS_MAX_TX_LEN (6)
28 #define IBUS_MAX_RX_LEN (4)
29 #define IBUS_RX_BUF_LEN (IBUS_MAX_RX_LEN)
31 #if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_IBUS)
33 typedef enum {
34 IBUS_MEAS_TYPE_INTERNAL_VOLTAGE = 0x00, //0 Internal Voltage
35 IBUS_MEAS_TYPE_TEMPERATURE = 0x01, //0 Temperature -##0.0 C, 0=-40.0 C, 400=0.0 C, 65535=6513.5 C
36 IBUS_MEAS_TYPE_RPM = 0x02, //0 Rotation RPM, ####0RPM, 0=0RPM, 65535=65535RPM
37 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
38 IBUS_MEAS_TYPE_HEADING = 0x04, //3
39 IBUS_MEAS_TYPE_CURRENT = 0x05, //3
40 IBUS_MEAS_TYPE_CLIMB = 0x06, //3
41 IBUS_MEAS_TYPE_ACC_Z = 0x07, //3
42 IBUS_MEAS_TYPE_ACC_Y = 0x08, //3
43 IBUS_MEAS_TYPE_ACC_X = 0x09, //3
44 IBUS_MEAS_TYPE_VSPEED = 0x0a, //3
45 IBUS_MEAS_TYPE_SPEED = 0x0b, //3
46 IBUS_MEAS_TYPE_DIST = 0x0c, //3
47 IBUS_MEAS_TYPE_ARMED = 0x0d, //3
48 IBUS_MEAS_TYPE_MODE = 0x0e, //3
49 //IBUS_MEAS_TYPE_RESERVED = 0x0f, //3
50 IBUS_MEAS_TYPE_PRES = 0x41, // Pressure, not work
51 //IBUS_MEAS_TYPE_ODO1 = 0x7c, // Odometer1, 0.0km, 0.0 only
52 //IBUS_MEAS_TYPE_ODO2 = 0x7d, // Odometer2, 0.0km, 0.0 only
53 IBUS_MEAS_TYPE_SPE = 0x7e, //1 Speed km/h, ###0km/h, 0=0Km/h, 1000=100Km/h
54 IBUS_MEAS_TYPE_COG = 0x80, //3 2byte course deg * 100, 0.0..359.99
55 IBUS_MEAS_TYPE_GPS_STATUS = 0x81, //3 2byte special parse byte by byte
56 IBUS_MEAS_TYPE_GPS_LON = 0x82, //3 4byte signed WGS84 in deg * 1E7, format into %u?%02u'%02u
57 IBUS_MEAS_TYPE_GPS_LAT = 0x83, //3 4byte signed WGS84 in deg * 1E7
58 IBUS_MEAS_TYPE_ALT = 0x84, //3 2byte signed barometer alt
59 IBUS_MEAS_TYPE_S85 = 0x85, //3
60 IBUS_MEAS_TYPE_S86 = 0x86, //3
61 IBUS_MEAS_TYPE_S87 = 0x87, //3
62 IBUS_MEAS_TYPE_S88 = 0x88, //3
63 IBUS_MEAS_TYPE_S89 = 0x89, //3
64 IBUS_MEAS_TYPE_S8A = 0x8A, //3
65 IBUS_MEAS_TYPE_GALT = 0xf9, //2 Altitude m, not work
66 //IBUS_MEAS_TYPE_SNR = 0xfa, // SNR, not work
67 //IBUS_MEAS_TYPE_NOISE = 0xfb, // Noise, not work
68 //IBUS_MEAS_TYPE_RSSI = 0xfc, // RSSI, not work
69 IBUS_MEAS_TYPE_GPS = 0xfd // 1byte fix 1byte satellites 4byte LAT 4byte LON 4byte alt, return UNKNOWN sensor and no formating
70 //IBUS_MEAS_TYPE_ERR = 0xfe //0 Error rate, #0%
71 } ibusSensorType_e;
73 typedef enum {
74 IBUS_MEAS_TYPE1_INTV = 0x00,
75 IBUS_MEAS_TYPE1_TEM = 0x01,
76 IBUS_MEAS_TYPE1_MOT = 0x02,
77 IBUS_MEAS_TYPE1_EXTV = 0x03,
78 IBUS_MEAS_TYPE1_CELL = 0x04,
79 IBUS_MEAS_TYPE1_BAT_CURR = 0x05,
80 IBUS_MEAS_TYPE1_FUEL = 0x06,
81 IBUS_MEAS_TYPE1_RPM = 0x07,
82 IBUS_MEAS_TYPE1_CMP_HEAD = 0x08,
83 IBUS_MEAS_TYPE1_CLIMB_RATE = 0x09,
84 IBUS_MEAS_TYPE1_COG = 0x0a,
85 IBUS_MEAS_TYPE1_GPS_STATUS = 0x0b,
86 IBUS_MEAS_TYPE1_ACC_X = 0x0c,
87 IBUS_MEAS_TYPE1_ACC_Y = 0x0d,
88 IBUS_MEAS_TYPE1_ACC_Z = 0x0e,
89 IBUS_MEAS_TYPE1_ROLL = 0x0f,
90 IBUS_MEAS_TYPE1_PITCH = 0x10,
91 IBUS_MEAS_TYPE1_YAW = 0x11,
92 IBUS_MEAS_TYPE1_VERTICAL_SPEED = 0x12,
93 IBUS_MEAS_TYPE1_GROUND_SPEED = 0x13,
94 IBUS_MEAS_TYPE1_GPS_DIST = 0x14,
95 IBUS_MEAS_TYPE1_ARMED = 0x15,
96 IBUS_MEAS_TYPE1_FLIGHT_MODE = 0x16,
97 IBUS_MEAS_TYPE1_PRES = 0x41,
98 //IBUS_MEAS_TYPE1_ODO1 = 0x7c,
99 //IBUS_MEAS_TYPE1_ODO2 = 0x7d,
100 IBUS_MEAS_TYPE1_SPE = 0x7e,
101 //IBUS_MEAS_TYPE1_TX_V = 0x7f,
102 IBUS_MEAS_TYPE1_GPS_LAT = 0x80,
103 IBUS_MEAS_TYPE1_GPS_LON = 0x81,
104 IBUS_MEAS_TYPE1_GPS_ALT = 0x82,
105 IBUS_MEAS_TYPE1_ALT = 0x83,
106 IBUS_MEAS_TYPE1_S84 = 0x84,
107 IBUS_MEAS_TYPE1_S85 = 0x85,
108 IBUS_MEAS_TYPE1_S86 = 0x86,
109 IBUS_MEAS_TYPE1_S87 = 0x87,
110 IBUS_MEAS_TYPE1_S88 = 0x88,
111 IBUS_MEAS_TYPE1_S89 = 0x89,
112 IBUS_MEAS_TYPE1_S8a = 0x8a
113 //IBUS_MEAS_TYPE1_SNR = 0xfa,
114 //IBUS_MEAS_TYPE1_NOISE = 0xfb,
115 //IBUS_MEAS_TYPE1_RSSI = 0xfc,
116 //IBUS_MEAS_TYPE1_ERR = 0xfe
117 } ibusSensorType1_e;
119 typedef enum {
120 IBUS_MEAS_VALUE_NONE = 0x00, //2
121 IBUS_MEAS_VALUE_TEMPERATURE = 0x01, //2
122 IBUS_MEAS_VALUE_MOT = 0x02, //2
123 IBUS_MEAS_VALUE_EXTERNAL_VOLTAGE = 0x03, //2
124 IBUS_MEAS_VALUE_CELL = 0x04, //2
125 IBUS_MEAS_VALUE_CURRENT = 0x05, //2
126 IBUS_MEAS_VALUE_FUEL = 0x06, //2
127 IBUS_MEAS_VALUE_RPM = 0x07, //2
128 IBUS_MEAS_VALUE_HEADING = 0x08, //2
129 IBUS_MEAS_VALUE_CLIMB = 0x09, //2
130 IBUS_MEAS_VALUE_COG = 0x0a, //2
131 IBUS_MEAS_VALUE_GPS_STATUS = 0x0b, //2
132 IBUS_MEAS_VALUE_ACC_X = 0x0c, //2
133 IBUS_MEAS_VALUE_ACC_Y = 0x0d, //2
134 IBUS_MEAS_VALUE_ACC_Z = 0x0e, //2
135 IBUS_MEAS_VALUE_ROLL = 0x0f, //2
136 IBUS_MEAS_VALUE_PITCH = 0x10, //2
137 IBUS_MEAS_VALUE_YAW = 0x11, //2
138 IBUS_MEAS_VALUE_VSPEED = 0x12, //2
139 IBUS_MEAS_VALUE_SPEED = 0x13, //2
140 IBUS_MEAS_VALUE_DIST = 0x14, //2
141 IBUS_MEAS_VALUE_ARMED = 0x15, //2
142 IBUS_MEAS_VALUE_MODE = 0x16, //2
143 IBUS_MEAS_VALUE_PRES = 0x41, //2
144 IBUS_MEAS_VALUE_SPE = 0x7e, //2
145 IBUS_MEAS_VALUE_GPS_LAT = 0x80, //4
146 IBUS_MEAS_VALUE_GPS_LON = 0x81, //4
147 IBUS_MEAS_VALUE_GALT4 = 0x82, //4
148 IBUS_MEAS_VALUE_ALT4 = 0x83, //4
149 IBUS_MEAS_VALUE_GALT = 0x84, //2
150 IBUS_MEAS_VALUE_ALT = 0x85, //2
151 IBUS_MEAS_VALUE_STATUS = 0x87, //2
152 IBUS_MEAS_VALUE_GPS_LAT1 = 0x88, //2
153 IBUS_MEAS_VALUE_GPS_LON1 = 0x89, //2
154 IBUS_MEAS_VALUE_GPS_LAT2 = 0x90, //2
155 IBUS_MEAS_VALUE_GPS_LON2 = 0x91, //2
156 IBUS_MEAS_VALUE_GPS = 0xfd //14 1byte fix 1byte satellites 4byte LAT 4byte LON 4byte alt
157 } ibusSensorValue_e;
159 uint8_t respondToIbusRequest(uint8_t ibusPacket[static IBUS_RX_BUF_LEN]);
160 void initSharedIbusTelemetry(serialPort_t *port);
161 void changeTypeIbusTelemetry(uint8_t id, uint8_t type, uint8_t value);
163 #endif //defined(USE_TELEMETRY) && defined(USE_TELEMETRY_IBUS)
165 bool ibusIsChecksumOkIa6b(const uint8_t *ibusPacket, const uint8_t length);
166 uint16_t ibusCalculateChecksum(const uint8_t *ibusPacket, size_t packetLength);