{"id":3865,"date":"2021-12-14T14:00:52","date_gmt":"2021-12-14T22:00:52","guid":{"rendered":"https:\/\/www.cloudacm.com\/?p=3865"},"modified":"2021-11-12T06:40:20","modified_gmt":"2021-11-12T14:40:20","slug":"flysky-ibus-interface","status":"publish","type":"post","link":"https:\/\/www.cloudacm.com\/?p=3865","title":{"rendered":"FlySky iBus Interface"},"content":{"rendered":"<p>The FlySky TX has some interesting features that allow it to display sensor readings from a RX. Having a ground based data logger made looking into this worthwhile. This post will cover the process used by the FlySky for sensor readings as well as interfacing micro controllers as a sensor source. There is a community of developers that have done a bulk of the work presented here and an effort will be made to give credit to them.<\/p>\n<p><a href=\"https:\/\/www.cloudacm.com\/wp-content\/uploads\/2021\/12\/main-screen-flyplus.jpg\"><img loading=\"lazy\" decoding=\"async\" class=\"aligncenter size-large wp-image-3877\" src=\"https:\/\/www.cloudacm.com\/wp-content\/uploads\/2021\/12\/main-screen-flyplus-1024x512.jpg\" alt=\"\" width=\"640\" height=\"320\" srcset=\"https:\/\/www.cloudacm.com\/wp-content\/uploads\/2021\/12\/main-screen-flyplus-1024x512.jpg 1024w, https:\/\/www.cloudacm.com\/wp-content\/uploads\/2021\/12\/main-screen-flyplus-300x150.jpg 300w, https:\/\/www.cloudacm.com\/wp-content\/uploads\/2021\/12\/main-screen-flyplus-768x384.jpg 768w, https:\/\/www.cloudacm.com\/wp-content\/uploads\/2021\/12\/main-screen-flyplus-1536x768.jpg 1536w, https:\/\/www.cloudacm.com\/wp-content\/uploads\/2021\/12\/main-screen-flyplus-540x270.jpg 540w, https:\/\/www.cloudacm.com\/wp-content\/uploads\/2021\/12\/main-screen-flyplus.jpg 1600w\" sizes=\"auto, (max-width: 640px) 100vw, 640px\" \/><\/a><\/p>\n<p>The FlySky RX is the receiving radio device that has 2 way radio communication with the TX. It also has its own set of protocols to interface with peripherals that connect to it, such as servos. Traditionally, servos are controlled with PWM signals from the RX. The FlySky RX also has a proprietary protocol called iBus which is a serial protocol that physically connects to peripherals in a daisy chain.<\/p>\n<p>Contributors to Betaflight have provided details about iBus which is available here, <a href=\"https:\/\/github.com\/betaflight\/betaflight\/wiki\/Single-wire-FlySky-(IBus)-telemetry\">https:\/\/github.com\/betaflight\/betaflight\/wiki\/Single-wire-FlySky-(IBus)-telemetry<\/a>. For those of you new to Betaflight, that is a flight controller software platform that was forked from Cleanflight, <a href=\"http:\/\/cleanflight.com\/\">http:\/\/cleanflight.com\/<\/a> and <a href=\"https:\/\/github.com\/cleanflight\/cleanflight\">https:\/\/github.com\/cleanflight\/cleanflight<\/a>. The main take away is the identification process iBus uses to determine the sensor type. FlySky iBus supports numerous sensor types which identify themselves with 0x00 to 0xFF hex values.<\/p>\n<p>This project contains more details about iBus support with microcontrollers, <a href=\"https:\/\/github.com\/bmellink\/IBusBM\">https:\/\/github.com\/bmellink\/IBusBM<\/a>. The IBusBM.h in the source has a narrow selection of sensor types, but makes reference to another source:<br \/>\n<a href=\"https:\/\/github.com\/cleanflight\/cleanflight\/blob\/7cd417959b3cb605aa574fc8c0f16759943527ef\/src\/main\/telemetry\/ibus_shared.h\">https:\/\/github.com\/cleanflight\/cleanflight\/blob\/7cd417959b3cb605aa574fc8c0f16759943527ef\/src\/main\/telemetry\/ibus_shared.h<\/a>. This list is included in some of my code examples as a reference. As pointed out, the sensor list is extensive and has the potential to provide operators with much detail. This page provides a glimpse at that, <a href=\"https:\/\/github.com\/qba667\/FlySkyI6\/wiki\/Telemetry\">https:\/\/github.com\/qba667\/FlySkyI6\/wiki\/Telemetry<\/a>.<\/p>\n<p>FlySky provides a range of prebuilt iBus sensors, some of which are demonstrated here.<\/p>\n<p><iframe loading=\"lazy\" title=\"FlySky FTr4 receiver and iBUS sensors\" width=\"640\" height=\"360\" src=\"https:\/\/www.youtube.com\/embed\/l3FmPq308ck?feature=oembed\" frameborder=\"0\" allow=\"accelerometer; autoplay; clipboard-write; encrypted-media; gyroscope; picture-in-picture; web-share\" referrerpolicy=\"strict-origin-when-cross-origin\" allowfullscreen><\/iframe><\/p>\n<p>The cost of these sensors are reasonable for those not comfortable with lower level electronics. For the sake of knowing, a voltage sensor was purchased with its photos below. This sensor design looks like it&#8217;s dated from 2014 and it has a mystery chip with no labeling. The photos were taken on a 1\/2 inch grid drafting mat to give a sense of scale, these are small devices.<\/p>\n<p><a href=\"https:\/\/www.cloudacm.com\/wp-content\/uploads\/2021\/12\/IMG_1696.png\"><img loading=\"lazy\" decoding=\"async\" class=\"aligncenter size-full wp-image-3879\" src=\"https:\/\/www.cloudacm.com\/wp-content\/uploads\/2021\/12\/IMG_1696.png\" alt=\"\" width=\"640\" height=\"359\" srcset=\"https:\/\/www.cloudacm.com\/wp-content\/uploads\/2021\/12\/IMG_1696.png 640w, https:\/\/www.cloudacm.com\/wp-content\/uploads\/2021\/12\/IMG_1696-300x168.png 300w, https:\/\/www.cloudacm.com\/wp-content\/uploads\/2021\/12\/IMG_1696-481x270.png 481w\" sizes=\"auto, (max-width: 640px) 100vw, 640px\" \/><\/a><\/p>\n<p><a href=\"https:\/\/www.cloudacm.com\/wp-content\/uploads\/2021\/11\/IMG_1718.png\"><img loading=\"lazy\" decoding=\"async\" class=\"aligncenter size-full wp-image-3866\" src=\"https:\/\/www.cloudacm.com\/wp-content\/uploads\/2021\/11\/IMG_1718.png\" alt=\"\" width=\"667\" height=\"375\" srcset=\"https:\/\/www.cloudacm.com\/wp-content\/uploads\/2021\/11\/IMG_1718.png 667w, https:\/\/www.cloudacm.com\/wp-content\/uploads\/2021\/11\/IMG_1718-300x169.png 300w, https:\/\/www.cloudacm.com\/wp-content\/uploads\/2021\/11\/IMG_1718-480x270.png 480w\" sizes=\"auto, (max-width: 667px) 100vw, 667px\" \/><\/a><br \/>\n<a href=\"https:\/\/www.cloudacm.com\/wp-content\/uploads\/2021\/11\/IMG_1717.png\"><img loading=\"lazy\" decoding=\"async\" class=\"aligncenter size-full wp-image-3867\" src=\"https:\/\/www.cloudacm.com\/wp-content\/uploads\/2021\/11\/IMG_1717.png\" alt=\"\" width=\"667\" height=\"375\" srcset=\"https:\/\/www.cloudacm.com\/wp-content\/uploads\/2021\/11\/IMG_1717.png 667w, https:\/\/www.cloudacm.com\/wp-content\/uploads\/2021\/11\/IMG_1717-300x169.png 300w, https:\/\/www.cloudacm.com\/wp-content\/uploads\/2021\/11\/IMG_1717-480x270.png 480w\" sizes=\"auto, (max-width: 667px) 100vw, 667px\" \/> <\/a><\/p>\n<p><a href=\"https:\/\/www.cloudacm.com\/wp-content\/uploads\/2021\/11\/IMG_1716.png\"><img loading=\"lazy\" decoding=\"async\" class=\"aligncenter size-full wp-image-3868\" src=\"https:\/\/www.cloudacm.com\/wp-content\/uploads\/2021\/11\/IMG_1716.png\" alt=\"\" width=\"667\" height=\"375\" srcset=\"https:\/\/www.cloudacm.com\/wp-content\/uploads\/2021\/11\/IMG_1716.png 667w, https:\/\/www.cloudacm.com\/wp-content\/uploads\/2021\/11\/IMG_1716-300x169.png 300w, https:\/\/www.cloudacm.com\/wp-content\/uploads\/2021\/11\/IMG_1716-480x270.png 480w\" sizes=\"auto, (max-width: 667px) 100vw, 667px\" \/><\/a><br \/>\n<a href=\"https:\/\/www.cloudacm.com\/wp-content\/uploads\/2021\/11\/IMG_1715.png\"><img loading=\"lazy\" decoding=\"async\" class=\"aligncenter size-full wp-image-3869\" src=\"https:\/\/www.cloudacm.com\/wp-content\/uploads\/2021\/11\/IMG_1715.png\" alt=\"\" width=\"667\" height=\"375\" srcset=\"https:\/\/www.cloudacm.com\/wp-content\/uploads\/2021\/11\/IMG_1715.png 667w, https:\/\/www.cloudacm.com\/wp-content\/uploads\/2021\/11\/IMG_1715-300x169.png 300w, https:\/\/www.cloudacm.com\/wp-content\/uploads\/2021\/11\/IMG_1715-480x270.png 480w\" sizes=\"auto, (max-width: 667px) 100vw, 667px\" \/><\/a><\/p>\n<p>Mimicking one of these sensors with an Arduino Uno is demonstrated by this developer, <a href=\"https:\/\/github.com\/adis1313\/iBUSTelemetry-Arduino\/\">https:\/\/github.com\/adis1313\/iBUSTelemetry-Arduino\/<\/a>. It was simpler than other methods that required multiple serial ports, resistors, and diodes. All that was needed were 3 connections, 5 volts, ground, and the signal wire. In addition, the signal wire connection can be defined to pins D8 to D13, which gives more flexibility. These changes were made to the code base to mimic temperature and rmp sensors.<\/p>\n<pre class=\"EnlighterJSRAW\" data-enlighter-language=\"cpp\">\/** \r\n\r\niBus_Sensor_SerialDebug_ver1.ino\r\nFlySky RX iBus Sensor Emulator on Arduino Uno\r\nDebug on Serial Port\r\nNov 4th, 2021 - 0534\r\n\r\n**\/\r\n\r\n\/*\r\n\r\nhttps:\/\/github.com\/adis1313\/iBUSTelemetry-Arduino\/blob\/master\/examples\/iBUSTelemetry_example\/iBUSTelemetry_example.ino\r\nhttps:\/\/github.com\/adis1313\/iBUSTelemetry-Arduino\/archive\/refs\/heads\/master.zip\r\n\r\n*\/\r\n\r\n\r\n\r\n\r\n\/\/ Libraries\r\n\r\n#include &lt;iBUSTelemetry.h&gt;\r\n\r\n\r\n\r\n\r\n\/\/ Variables and Constants\r\n\r\n#define UPDATE_INTERVAL 500\r\n#define TEMPBASE 400    \/\/ base value for 0'C\r\n\r\niBUSTelemetry IBus(11); \/\/ Pin 11 of Arduino Uno connects to FlySky RX iBus\r\n\r\nuint32_t prevMillis = 0; \/\/ Necessary to updateValues() method. Look below.\r\n\r\n\r\n\r\n\r\n\/\/ sensor values\r\nuint16_t rpm=1000;\r\nuint16_t temp=TEMPBASE+100; \/\/ start at 10'C\r\n\r\n\r\n\r\n\r\n\/\/ Hardware Initialization Routine\r\nvoid HardwareInit()\r\n{\r\n\r\n  IBus.begin(); \/\/ Let's start having fun!\r\n  \r\n  \/\/ adding 2 sensors\r\n  \/\/ Reference https:\/\/github.com\/adis1313\/iBUSTelemetry-Arduino\/blob\/master\/iBUSSensors.h\r\n  \/\/ Commented list below for reference\r\n  IBus.addSensor(0x07); \/\/ RPM\r\n  IBus.addSensor(0x01); \/\/ Temp\r\n  \r\n  \r\n  \/*\r\n  \r\n  \r\n    NONE             = 0x00,\r\n    TEMPERATURE      = 0x01,\r\n    RPM_FLYSKY       = 0x02,\r\n    EXTERNAL_VOLTAGE = 0x03,\r\n    CELL             = 0x04, \/\/ Avg Cell voltage\r\n    BAT_CURR         = 0x05, \/\/ battery current A * 100\r\n    FUEL             = 0x06, \/\/ remaining battery percentage \/ mah drawn otherwise or fuel level no unit!\r\n    RPM              = 0x07, \/\/ throttle value \/ battery capacity\r\n    CMP_HEAD         = 0x08, \/\/Heading  0..360 deg, 0=north 2bytes\r\n    CLIMB_RATE       = 0x09, \/\/2 bytes m\/s *100\r\n    COG              = 0x0a, \/\/2 bytes  Course over ground(NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. unknown max uint\r\n    GPS_STATUS       = 0x0b, \/\/2 bytes\r\n    ACC_X            = 0x0c, \/\/2 bytes m\/s *100 signed\r\n    ACC_Y            = 0x0d, \/\/2 bytes m\/s *100 signed\r\n    ACC_Z            = 0x0e, \/\/2 bytes m\/s *100 signed\r\n    ROLL             = 0x0f, \/\/2 bytes deg *100 signed\r\n    PITCH            = 0x10, \/\/2 bytes deg *100 signed\r\n    YAW              = 0x11, \/\/2 bytes deg *100 signed\r\n    VERTICAL_SPEED   = 0x12, \/\/2 bytes m\/s *100\r\n    GROUND_SPEED     = 0x13, \/\/2 bytes m\/s *100 different unit than build-in sensor\r\n    GPS_DIST         = 0x14, \/\/2 bytes dist from home m unsigned\r\n    ARMED            = 0x15, \/\/2 bytes\r\n    FLIGHT_MODE      = 0x16, \/\/2 bytes\r\n    PRES             = 0x41, \/\/ Pressure\r\n    ODO1             = 0x7c, \/\/ Odometer1\r\n    ODO2             = 0x7d, \/\/ Odometer2\r\n    SPE              = 0x7e, \/\/ Speed 2bytes km\/h\r\n    GPS_LAT          = 0x80, \/\/4bytes signed WGS84 in degrees * 1E7\r\n    GPS_LON          = 0x81, \/\/4bytes signed WGS84 in degrees * 1E7\r\n    GPS_ALT          = 0x82, \/\/4bytes signed!!! GPS alt m*100\r\n    ALT              = 0x83, \/\/4bytes signed!!! Alt m*100\r\n    ALT_MAX          = 0x84, \/\/4bytes signed MaxAlt m*100\r\n    ALT_FLYSKY       = 0xf9, \/\/ Altitude 2 bytes signed in m\r\n    GPS_FULL         = 0xfd,\r\n    VOLT_FULL        = 0xf0,\r\n    ACC_FULL         = 0xef,\r\n    UNKNOWN          = 0xff,\r\n  \r\n  \r\n  *\/\r\n  \r\n  Serial.begin(115200);\r\n  Serial.println(\"Start iBUS sensor\");\r\n  \r\n} \r\n\r\n\r\n\r\n\r\nvoid setup()\r\n{\r\n  HardwareInit();   \r\n}\r\n\r\n\r\n\r\nvoid loop()\r\n{\r\n    InboundData(); \/\/ Very important! iBUS protocol is very sensitive to timings.\r\n                    \/\/ DO NOT USE ANY delay()! Look at updateValues() method.\r\n                    \/\/ It's an example of how to use intervals without delays.\r\n\r\n    IBus.run(); \/\/It must be here. Period.\r\n}\r\n\r\n\r\n\r\n\r\nvoid InboundData()\r\n{\r\n    uint32_t currMillis = millis();\r\n\r\n    if (currMillis - prevMillis &gt;= UPDATE_INTERVAL) { \/\/ Code in the middle of these brackets will be performed every 500ms.\r\n        prevMillis = currMillis;\r\n\r\n        IBus.setSensorValue(1,rpm); \/\/ Now, you have two ways to set sensors values. Using floating point variables\r\n                                    \/\/ or directly in 32bit integer, but then you have to format variable by yourself.\r\n                                    \/\/ Ex.: telemetry.setSensorValueFP(1, 24.45); is equivalent to telemetry.setSensorValue(1, 2445);\r\n                                    \/\/ The values differ for different sensors.\r\n        rpm += 10;                  \/\/ increase motor speed by 10 RPM\r\n        \r\n        IBus.setSensorValue(2,temp++); \/\/ increase temperature by 0.1 'C every loop\r\n        \r\n        Serial.print(\"RPM=\");\r\n        Serial.print(rpm);\r\n        Serial.print(\" Temp=\");\r\n        Serial.println((temp-TEMPBASE)\/10.);\r\n\r\n\r\n    }\r\n}<\/pre>\n<p>It&#8217;s basically a counter that increases the values to the 2 sensor variables. Those variables are passed to the RX which in turn become available on the TX once it is bound. Having actual sensor readings was based off of this project that can be found here, <a href=\"https:\/\/electropeak.com\/learn\/arduino-determining-pressure-altitude-using-bosch-bmp180\/\">https:\/\/electropeak.com\/learn\/arduino-determining-pressure-altitude-using-bosch-bmp180\/<\/a>. This leveraged the GY-68 sensors that had been sourced for an earlier project. You can also reference this code base, however it is not native to the Arduino IDE, <a href=\"https:\/\/github.com\/Yenya\/ibus-altitude-sensor\">https:\/\/github.com\/Yenya\/ibus-altitude-sensor<\/a><\/p>\n<pre class=\"EnlighterJSRAW\" data-enlighter-language=\"cpp\">\/** \r\n\r\niBus_Sensor_BarometricSensor_ver4.3.ino\r\nFlySky RX iBus Sensor Emulator on Arduino Uno with GY-68 BMP085 Module\r\nDebug on Serial Port\r\nNov 5th, 2021 - 0529\r\n\r\n**\/\r\n\r\n\r\n\r\n\/\/ Libraries\r\n\r\n#include &lt;iBUSTelemetry.h&gt;\r\n#include &lt;Wire.h&gt;\r\n#include &lt;SFE_BMP180.h&gt;\r\n\r\n\r\n\/\/ Variables and Constants\r\n\r\niBUSTelemetry IBus(11); \/\/ Pin 11 of Arduino Uno connects to FlySky RX iBus\r\nSFE_BMP180 dps;\r\n\r\n#define UPDATE_INTERVAL 500\r\n\r\ndouble baseline; \r\ndouble T,P,p0,a;\r\n\r\nuint32_t prevMillis = 0; \/\/ Necessary to updateValues() method. Look below.\r\n\r\nconst int analogInPin = A3; \r\nint ExtVoltage = 0;        \r\nfloat ReadVolts = 0;\r\n\/\/ sensor values\r\nlong GY68Temp=0; \r\nlong GY68Alt=0; \r\n\r\n\r\n\r\n\r\n\/\/ Hardware Initialization Routine\r\nvoid HardwareInit()\r\n{\r\n\r\n  dps.begin();\r\n  baseline = getPressure();\r\n  \r\n  IBus.begin(); \/\/ Let's start having fun!\r\n  \r\n  \/\/ Reference https:\/\/github.com\/adis1313\/iBUSTelemetry-Arduino\/blob\/master\/iBUSSensors.h\r\n  \r\n  IBus.addSensor(0x01); \/\/ Temperature\r\n  IBus.addSensor(0x03); \/\/ External Voltage\r\n  IBus.addSensor(0x07); \/\/ Had to use RPM sensor for Altitude readings\r\n\r\n  Serial.begin(115200);\r\n  Serial.println(\"Start iBUS sensor\");\r\n\r\n} \r\n\r\n\r\n\r\n\r\nvoid setup()\r\n{\r\n  HardwareInit();   \r\n}\r\n\r\n\r\n\r\nvoid loop()\r\n{    \r\n\r\n    InboundData(); \/\/ Very important! iBUS protocol is very sensitive to timings.\r\n                    \/\/ DO NOT USE ANY delay()! Look at updateValues() method.\r\n                    \/\/ It's an example of how to use intervals without delays.\r\n\r\n    IBus.run(); \/\/It must be here. Period.\r\n}\r\n\r\n\r\n\r\nvoid InboundData()\r\n{\r\n    uint32_t currMillis = millis();\r\n\r\n    if (currMillis - prevMillis &gt;= UPDATE_INTERVAL) { \/\/ Code in the middle of these brackets will be performed every 500ms.\r\n        prevMillis = currMillis;\r\n        \r\n        SensorData();\r\n     \r\n        IBus.setSensorValue(1,GY68Temp);  \r\n        IBus.setSensorValue(2,ExtVoltage);      \r\n        IBus.setSensorValue(3,GY68Alt); \r\n        \r\n        Serial.print(\"Temp=\");\r\n        Serial.print((9.0\/5.0)*(GY68Temp\/10)+32.0,2);\r\n        Serial.print(\" F\");\r\n        Serial.print(\" Volt=\");\r\n        ReadVolts = ExtVoltage;\r\n        Serial.print(ReadVolts\/100, 2); \r\n        Serial.print(\" Altitude: \");\r\n        if (a &gt;= 0.0) Serial.print(\" \"); \/\/ add a space for positive numbers\r\n        Serial.print(a,1);\r\n        Serial.println(\" M\");\r\n\r\n\r\n\r\n    }\r\n} \r\n\r\n\r\n\r\n\r\nvoid SensorData()\r\n{\r\n  \r\n  P = getPressure();\r\n\r\n  a = dps.altitude(P,baseline);\r\n\r\n  GY68Temp = (T*10); \t\/\/ Temp in C for FlySky\r\n  GY68Alt = a,1; \t\/\/ Altitude in M for FlySky\r\n  \r\n  ExtVoltage = analogRead(analogInPin);\r\n  ExtVoltage = (0.468*ExtVoltage*2); \r\n  \r\n} \r\n\r\n\r\n\r\ndouble getPressure()\r\n{\r\n\r\n  dps.startTemperature();\r\n  delay(20);\r\n  dps.getTemperature(T);\r\n  \r\n  dps.startPressure(3);\r\n  delay(20);\r\n  dps.getPressure(P,T);\r\n  \r\n  return(P);\r\n}\r\n<\/pre>\n<p>The sensor provided debug values as expected, but the TX pressure readings were incorrect. There were various code versions made to try and locate the issue, which ultimately was a 2 byte limit passed by the code to the RX iBus.<\/p>\n<pre class=\"EnlighterJSRAW\" data-enlighter-language=\"cpp\">\/** \r\n\r\niBus_Sensor_SerialDebug_ver1.3.ino\r\nFlySky RX iBus Sensor Emulator on Arduino Uno\r\nDebug on Serial Port\r\nFinding Valid Values for Altimeter\r\nNov 7th, 2021 - 0800\r\n\r\n**\/\r\n\r\n\/*\r\n\r\nhttps:\/\/github.com\/adis1313\/iBUSTelemetry-Arduino\/blob\/master\/examples\/iBUSTelemetry_example\/iBUSTelemetry_example.ino\r\nhttps:\/\/github.com\/adis1313\/iBUSTelemetry-Arduino\/archive\/refs\/heads\/master.zip\r\n\r\n*\/\r\n\r\n\r\n\r\n\r\n\/\/ Libraries\r\n\r\n#include &lt;iBUSTelemetry.h&gt;\r\n\r\n\r\n\r\n\r\n\/\/ Variables and Constants\r\n\r\n#define UPDATE_INTERVAL 500\r\n#define TEMPBASE 400    \/\/ base value for 0'C\r\n\r\niBUSTelemetry IBus(11); \/\/ Pin 11 of Arduino Uno connects to FlySky RX iBus\r\n\r\nuint32_t prevMillis = 0; \/\/ Necessary to updateValues() method. Look below.\r\n\r\n\r\n\r\n\r\n\/\/ sensor values\r\nuint32_t Pressure=1100; \r\n\/\/ Pressure measurement range of 300 to 1100hPa\r\n\r\n\r\n\r\n\r\n\/\/ Hardware Initialization Routine\r\nvoid HardwareInit()\r\n{\r\n\r\n  IBus.begin(); \/\/ Let's start having fun!\r\n  \r\n  \/\/ adding 2 sensors\r\n  \/\/ Reference https:\/\/github.com\/adis1313\/iBUSTelemetry-Arduino\/blob\/master\/iBUSSensors.h\r\n  \/\/ Commented list below for reference\r\n  IBus.addSensor(0x41); \/\/ Pressure\r\n  \t\t\t \/\/ See https:\/\/github.com\/qba667\/FlySkyI6\/wiki\/Telemetry, mentions pressure is a 4 byte sensor try uint32_t\r\n  \r\n  \r\n  \/*\r\n  \r\n  \r\n    NONE             = 0x00,\r\n    TEMPERATURE      = 0x01,\r\n    RPM_FLYSKY       = 0x02,\r\n    EXTERNAL_VOLTAGE = 0x03,\r\n    CELL             = 0x04, \/\/ Avg Cell voltage\r\n    BAT_CURR         = 0x05, \/\/ battery current A * 100\r\n    FUEL             = 0x06, \/\/ remaining battery percentage \/ mah drawn otherwise or fuel level no unit!\r\n    RPM              = 0x07, \/\/ throttle value \/ battery capacity\r\n    CMP_HEAD         = 0x08, \/\/Heading  0..360 deg, 0=north 2bytes\r\n    CLIMB_RATE       = 0x09, \/\/2 bytes m\/s *100\r\n    COG              = 0x0a, \/\/2 bytes  Course over ground(NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. unknown max uint\r\n    GPS_STATUS       = 0x0b, \/\/2 bytes\r\n    ACC_X            = 0x0c, \/\/2 bytes m\/s *100 signed   int16_t\r\n    ACC_Y            = 0x0d, \/\/2 bytes m\/s *100 signed   int16_t\r\n    ACC_Z            = 0x0e, \/\/2 bytes m\/s *100 signed   int16_t\r\n    ROLL             = 0x0f, \/\/2 bytes deg *100 signed   int16_t\r\n    PITCH            = 0x10, \/\/2 bytes deg *100 signed   int16_t\r\n    YAW              = 0x11, \/\/2 bytes deg *100 signed   int16_t\r\n    VERTICAL_SPEED   = 0x12, \/\/2 bytes m\/s *100   uint16_t\r\n    GROUND_SPEED     = 0x13, \/\/2 bytes m\/s *100 different unit than build-in sensor   uint16_t\r\n    GPS_DIST         = 0x14, \/\/2 bytes dist from home m unsigned   uint16_t\r\n    ARMED            = 0x15, \/\/2 bytes   uint16_t\r\n    FLIGHT_MODE      = 0x16, \/\/2 bytes   uint16_t\r\n    PRES             = 0x41, \/\/ Pressure\r\n    ODO1             = 0x7c, \/\/ Odometer1\r\n    ODO2             = 0x7d, \/\/ Odometer2\r\n    SPE              = 0x7e, \/\/ Speed 2bytes km\/h   uint16_t\r\n    GPS_LAT          = 0x80, \/\/4bytes signed WGS84 in degrees * 1E7  int32_t\r\n    GPS_LON          = 0x81, \/\/4bytes signed WGS84 in degrees * 1E7  int32_t\r\n    GPS_ALT          = 0x82, \/\/4bytes signed!!! GPS alt m*100   int32_t\r\n    ALT              = 0x83, \/\/4bytes signed!!! Alt m*100   int32_t\r\n    ALT_MAX          = 0x84, \/\/4bytes signed MaxAlt m*100   int32_t\r\n    ALT_FLYSKY       = 0xf9, \/\/ Altitude 2 bytes signed in m   int16_t\r\n    GPS_FULL         = 0xfd,\r\n    VOLT_FULL        = 0xf0,\r\n    ACC_FULL         = 0xef,\r\n    UNKNOWN          = 0xff,\r\n  \r\n  \r\n  *\/\r\n  \r\n  Serial.begin(115200);\r\n  Serial.println(\"Start iBUS sensor\");\r\n  \r\n} \r\n\r\n\r\n\r\n\r\nvoid setup()\r\n{\r\n  HardwareInit();   \r\n}\r\n\r\n\r\n\r\nvoid loop()\r\n{\r\n    InboundData(); \/\/ Very important! iBUS protocol is very sensitive to timings.\r\n                    \/\/ DO NOT USE ANY delay()! Look at updateValues() method.\r\n                    \/\/ It's an example of how to use intervals without delays.\r\n\r\n    IBus.run(); \/\/It must be here. Period.\r\n}\r\n\r\n\r\n\r\n\r\nvoid InboundData()\r\n{\r\n    uint32_t currMillis = millis();\r\n\r\n    if (currMillis - prevMillis &gt;= UPDATE_INTERVAL) { \/\/ Code in the middle of these brackets will be performed every 500ms.\r\n        prevMillis = currMillis;\r\n\r\n  if (Pressure &lt; 300) { \/\/ Reset pressure once lowest valid value is reached\r\n    Pressure = 1100; \t \/\/ Set pressure value back to highest valid value\r\n    }\r\n\r\n        IBus.setSensorValue(1,Pressure*100); \/\/ sensor value rolls at 65536 because of this, uint16_t.  Fix with Math?\r\n        \r\n        Serial.print(\"Pressure=\");\r\n        Serial.println(Pressure); \/\/ debug of sensor value, if this is correct and the TX is wrong, then FlySky can't do it\r\n        \r\n        Pressure = Pressure-5; \/\/ Decrease Pressure, same as Gain Altitude\r\n\r\n    }\r\n}<\/pre>\n<p>The FlySky TX has a baseline pressure value that can be set manually. That value is used to calculate altitude from pressure readings from a sensor. Although the sensor variable was defined as 4 bytes (uint32_t), the code rolled the values at 2 bytes. Even with the counter code above to force the 4 byte value, the iBUSTelemetry.h inherent 2 byte limit prevents the TX from converting pressure reading to altitude with its internal process. So reading 4 byte sensors is not an option with that library.<\/p>\n<p>The primary goal of this research was to determine if and how ground based data logging could be performed with the TX. The controller does have a serial connection, however its stock firmware is not designed to pass telemetry data through it. It might be possible with third party firmware or device that mimics a tethered controller in a student \/ teacher configuration. But development of that scale is outside the scope of this research.<\/p>\n<p>Eventually the following code was adopted that was a bit of a hack to get altitude readings on the TX. It uses the RPM defined sensor as an altitude reading. When powered on, the microcontroller establishes the base altitude from the sensor. As the sensor changes altitude, that reading is reflected on the TX.<\/p>\n<pre class=\"EnlighterJSRAW\" data-enlighter-language=\"cpp\">\/** \r\n\r\niBus_Sensor_BarometricSensor_ver4.3.ino\r\nFlySky RX iBus Sensor Emulator on Arduino Uno with GY-68 BMP085 Module\r\nDebug on Serial Port\r\nNov 5th, 2021 - 0529\r\n\r\n**\/\r\n\r\n\r\n\r\n\/\/ Libraries\r\n\r\n#include &lt;iBUSTelemetry.h&gt;\r\n#include &lt;Wire.h&gt;\r\n#include &lt;SFE_BMP180.h&gt;\r\n\r\n\r\n\/\/ Variables and Constants\r\n\r\niBUSTelemetry IBus(11); \/\/ Pin 11 of Arduino Uno connects to FlySky RX iBus\r\nSFE_BMP180 dps;\r\n\r\n#define UPDATE_INTERVAL 500\r\n\r\ndouble baseline; \r\ndouble T,P,p0,a;\r\n\r\nuint32_t prevMillis = 0; \/\/ Necessary to updateValues() method. Look below.\r\n\r\nconst int analogInPin = A3; \r\nint ExtVoltage = 0;        \r\nfloat ReadVolts = 0;\r\n\/\/ sensor values\r\nlong GY68Temp=0; \r\nlong GY68Alt=0; \r\n\r\n\r\n\r\n\r\n\/\/ Hardware Initialization Routine\r\nvoid HardwareInit()\r\n{\r\n\r\n  dps.begin();\r\n  baseline = getPressure();\r\n  \r\n  IBus.begin(); \/\/ Let's start having fun!\r\n  \r\n  \/\/ Reference https:\/\/github.com\/adis1313\/iBUSTelemetry-Arduino\/blob\/master\/iBUSSensors.h\r\n  \r\n  IBus.addSensor(0x01); \/\/ Temperature\r\n  IBus.addSensor(0x03); \/\/ External Voltage\r\n  IBus.addSensor(0x07); \/\/ Had to use RPM sensor for Altitude readings\r\n\r\n  Serial.begin(115200);\r\n  Serial.println(\"Start iBUS sensor\");\r\n\r\n} \r\n\r\n\r\n\r\n\r\nvoid setup()\r\n{\r\n  HardwareInit();   \r\n}\r\n\r\n\r\n\r\nvoid loop()\r\n{    \r\n\r\n    InboundData(); \/\/ Very important! iBUS protocol is very sensitive to timings.\r\n                    \/\/ DO NOT USE ANY delay()! Look at updateValues() method.\r\n                    \/\/ It's an example of how to use intervals without delays.\r\n\r\n    IBus.run(); \/\/It must be here. Period.\r\n}\r\n\r\n\r\n\r\nvoid InboundData()\r\n{\r\n    uint32_t currMillis = millis();\r\n\r\n    if (currMillis - prevMillis &gt;= UPDATE_INTERVAL) { \/\/ Code in the middle of these brackets will be performed every 500ms.\r\n        prevMillis = currMillis;\r\n        \r\n        SensorData();\r\n     \r\n        IBus.setSensorValue(1,GY68Temp);  \r\n        IBus.setSensorValue(2,ExtVoltage);      \r\n        IBus.setSensorValue(3,GY68Alt); \r\n        \r\n        Serial.print(\"Temp=\");\r\n        Serial.print((9.0\/5.0)*(GY68Temp\/10)+32.0,2);\r\n        Serial.print(\" F\");\r\n        Serial.print(\" Volt=\");\r\n        ReadVolts = ExtVoltage;\r\n        Serial.print(ReadVolts\/100, 2); \r\n        Serial.print(\" Altitude: \");\r\n        if (a &gt;= 0.0) Serial.print(\" \"); \/\/ add a space for positive numbers\r\n        Serial.print(a,1);\r\n        Serial.println(\" M\");\r\n\r\n\r\n\r\n    }\r\n} \r\n\r\n\r\n\r\n\r\nvoid SensorData()\r\n{\r\n  \r\n  P = getPressure();\r\n\r\n  a = dps.altitude(P,baseline);\r\n\r\n  GY68Temp = (T*10); \t\/\/ Temp in C for FlySky\r\n  GY68Alt = a,1; \t\/\/ Altitude in M for FlySky\r\n  \r\n  ExtVoltage = analogRead(analogInPin);\r\n  ExtVoltage = (0.468*ExtVoltage*2); \r\n  \r\n} \r\n\r\n\r\n\r\ndouble getPressure()\r\n{\r\n\r\n  dps.startTemperature();\r\n  delay(20);\r\n  dps.getTemperature(T);\r\n  \r\n  dps.startPressure(3);\r\n  delay(20);\r\n  dps.getPressure(P,T);\r\n  \r\n  return(P);\r\n}\r\n<\/pre>\n<p>There are several features that the FlySky system has that haven&#8217;t been covered here. In addition, the community of developers are likely to provide more features that aren&#8217;t available at the time of this writing. It would be worthwhile to check back on occasion to see where this goes.<\/p>\n","protected":false},"excerpt":{"rendered":"<p>The FlySky TX has some interesting features that allow it to display sensor readings from a RX. Having a ground based data logger made looking into this worthwhile. This post will cover the process used by the FlySky for sensor readings as well as interfacing micro controllers as a sensor source. There is a community of developers that have done a bulk of the work presented here and an effort will be made to give credit to them. The FlySky&#8230;<\/p>\n<p class=\"read-more\"><a class=\"btn btn-default\" href=\"https:\/\/www.cloudacm.com\/?p=3865\"> Read More<span class=\"screen-reader-text\">  Read More<\/span><\/a><\/p>\n","protected":false},"author":1,"featured_media":0,"comment_status":"closed","ping_status":"closed","sticky":false,"template":"","format":"standard","meta":{"footnotes":""},"categories":[3],"tags":[],"class_list":["post-3865","post","type-post","status-publish","format-standard","hentry","category-rd"],"_links":{"self":[{"href":"https:\/\/www.cloudacm.com\/index.php?rest_route=\/wp\/v2\/posts\/3865","targetHints":{"allow":["GET"]}}],"collection":[{"href":"https:\/\/www.cloudacm.com\/index.php?rest_route=\/wp\/v2\/posts"}],"about":[{"href":"https:\/\/www.cloudacm.com\/index.php?rest_route=\/wp\/v2\/types\/post"}],"author":[{"embeddable":true,"href":"https:\/\/www.cloudacm.com\/index.php?rest_route=\/wp\/v2\/users\/1"}],"replies":[{"embeddable":true,"href":"https:\/\/www.cloudacm.com\/index.php?rest_route=%2Fwp%2Fv2%2Fcomments&post=3865"}],"version-history":[{"count":9,"href":"https:\/\/www.cloudacm.com\/index.php?rest_route=\/wp\/v2\/posts\/3865\/revisions"}],"predecessor-version":[{"id":3871,"href":"https:\/\/www.cloudacm.com\/index.php?rest_route=\/wp\/v2\/posts\/3865\/revisions\/3871"}],"wp:attachment":[{"href":"https:\/\/www.cloudacm.com\/index.php?rest_route=%2Fwp%2Fv2%2Fmedia&parent=3865"}],"wp:term":[{"taxonomy":"category","embeddable":true,"href":"https:\/\/www.cloudacm.com\/index.php?rest_route=%2Fwp%2Fv2%2Fcategories&post=3865"},{"taxonomy":"post_tag","embeddable":true,"href":"https:\/\/www.cloudacm.com\/index.php?rest_route=%2Fwp%2Fv2%2Ftags&post=3865"}],"curies":[{"name":"wp","href":"https:\/\/api.w.org\/{rel}","templated":true}]}}