2 * This file is part of Cleanflight and Betaflight.
4 * Cleanflight and Betaflight are free software. You can redistribute
5 * this software and/or modify this software under the terms of the
6 * GNU General Public License as published by the Free Software
7 * Foundation, either version 3 of the License, or (at your option)
10 * Cleanflight and Betaflight are distributed in the hope that they
11 * will be useful, but WITHOUT ANY WARRANTY; without even the implied
12 * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
13 * See the GNU General Public License for more details.
15 * You should have received a copy of the GNU General Public License
16 * along with this software.
18 * If not, see <http://www.gnu.org/licenses/>.
22 * The ibus_shared module implements the ibus telemetry packet handling
23 * which is shared between the ibus serial rx and the ibus telemetry.
25 * There is only one 'user' active at any time, serial rx will open the
26 * serial port if both functions are enabled at the same time
32 #include "drivers/serial.h"
34 #define IBUS_CHECKSUM_SIZE (2)
35 #define IBUS_SENSOR_COUNT 15
38 IBUS_SENSOR_TYPE_NONE
= 0x00,
39 IBUS_SENSOR_TYPE_TEMPERATURE
= 0x01,
40 IBUS_SENSOR_TYPE_RPM_FLYSKY
= 0x02,
41 IBUS_SENSOR_TYPE_EXTERNAL_VOLTAGE
= 0x03,
42 IBUS_SENSOR_TYPE_CELL
= 0x04, // Avg Cell voltage
43 IBUS_SENSOR_TYPE_BAT_CURR
= 0x05, // battery current A * 100
44 IBUS_SENSOR_TYPE_FUEL
= 0x06, // remaining battery percentage / mah drawn otherwise or fuel level no unit!
45 IBUS_SENSOR_TYPE_RPM
= 0x07, // throttle value / battery capacity
46 IBUS_SENSOR_TYPE_CMP_HEAD
= 0x08, //Heading 0..360 deg, 0=north 2bytes
47 IBUS_SENSOR_TYPE_CLIMB_RATE
= 0x09, //2 bytes m/s *100
48 IBUS_SENSOR_TYPE_COG
= 0x0a, //2 bytes Course over ground(NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. unknown max uint
49 IBUS_SENSOR_TYPE_GPS_STATUS
= 0x0b, //2 bytes
50 IBUS_SENSOR_TYPE_ACC_X
= 0x0c, //2 bytes m/s *100 signed
51 IBUS_SENSOR_TYPE_ACC_Y
= 0x0d, //2 bytes m/s *100 signed
52 IBUS_SENSOR_TYPE_ACC_Z
= 0x0e, //2 bytes m/s *100 signed
53 IBUS_SENSOR_TYPE_ROLL
= 0x0f, //2 bytes deg *100 signed
54 IBUS_SENSOR_TYPE_PITCH
= 0x10, //2 bytes deg *100 signed
55 IBUS_SENSOR_TYPE_YAW
= 0x11, //2 bytes deg *100 signed
56 IBUS_SENSOR_TYPE_VERTICAL_SPEED
= 0x12, //2 bytes m/s *100
57 IBUS_SENSOR_TYPE_GROUND_SPEED
= 0x13, //2 bytes m/s *100 different unit than build-in sensor
58 IBUS_SENSOR_TYPE_GPS_DIST
= 0x14, //2 bytes dist from home m unsigned
59 IBUS_SENSOR_TYPE_ARMED
= 0x15, //2 bytes
60 IBUS_SENSOR_TYPE_FLIGHT_MODE
= 0x16, //2 bytes
61 IBUS_SENSOR_TYPE_PRES
= 0x41, // Pressure
62 IBUS_SENSOR_TYPE_ODO1
= 0x7c, // Odometer1
63 IBUS_SENSOR_TYPE_ODO2
= 0x7d, // Odometer2
64 IBUS_SENSOR_TYPE_SPE
= 0x7e, // Speed 2bytes km/h
66 IBUS_SENSOR_TYPE_GPS_LAT
= 0x80, //4bytes signed WGS84 in degrees * 1E7
67 IBUS_SENSOR_TYPE_GPS_LON
= 0x81, //4bytes signed WGS84 in degrees * 1E7
68 IBUS_SENSOR_TYPE_GPS_ALT
= 0x82, //4bytes signed!!! GPS alt m*100
69 IBUS_SENSOR_TYPE_ALT
= 0x83, //4bytes signed!!! Alt m*100
70 IBUS_SENSOR_TYPE_ALT_MAX
= 0x84, //4bytes signed MaxAlt m*100
72 IBUS_SENSOR_TYPE_ALT_FLYSKY
= 0xf9, // Altitude 2 bytes signed in m
73 #if defined(USE_TELEMETRY_IBUS_EXTENDED)
74 IBUS_SENSOR_TYPE_GPS_FULL
= 0xfd,
75 IBUS_SENSOR_TYPE_VOLT_FULL
= 0xf0,
76 IBUS_SENSOR_TYPE_ACC_FULL
= 0xef,
77 #endif //defined(TELEMETRY_IBUS_EXTENDED)
78 IBUS_SENSOR_TYPE_UNKNOWN
= 0xff
81 #if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_IBUS)
83 uint8_t respondToIbusRequest(uint8_t const * const ibusPacket
);
84 void initSharedIbusTelemetry(serialPort_t
* port
);
86 #endif //defined(TELEMETRY) && defined(TELEMETRY_IBUS)
88 bool isChecksumOkIa6b(const uint8_t *ibusPacket
, const uint8_t length
);