|
| 1 | + |
| 2 | + |
| 3 | +/* ROBOTmaker 28.12.2016 |
| 4 | + * This example decodes a Futaba SBUS or compatible stream and convert it to soft switches or PPM. |
| 5 | + * |
| 6 | + * Thanks goes to https://www.ordinoscope.net/index.php/Electronique/Protocoles/SBUS for the arduino code which was converted to for our use |
| 7 | + * It is based on a verion found : |
| 8 | + * - https://github.com/zendes/SBUS |
| 9 | + * - http://forum.arduino.cc/index.php?topic=99708.0 |
| 10 | + * - https://mbed.org/users/Digixx/notebook/futaba-s-bus-controlled-by-mbed/ |
| 11 | + * |
| 12 | + * There are some inexpensibe SBUS to PPM decoders, such as |
| 13 | + * http://www.hobbyking.com/hobbyking/store/__37953__frsky_4_channel_s_bus_to_pwm_decoder.html |
| 14 | + * This code is more a proof of concept than a real alternative. |
| 15 | + * |
| 16 | + *Further details on our website: |
| 17 | + *http://www.robotmaker.eu/ROBOTmaker/quadcopter-3d-proximity-sensing/sbus-graphical-representation |
| 18 | + * |
| 19 | + * This code uses the RX0 as input. It's not possible to use a software serial port, because |
| 20 | + * there are too many conflicting interrupts between serial input and PWM generation. |
| 21 | + * |
| 22 | + * Since RX0 is also used to communicate with the FTDI, the SBUS must be disconnected while |
| 23 | + * flashing the Arduino. |
| 24 | + * |
| 25 | + * Furthermore, the SBUS uses an inverted serial communication. Why should the Futaba designers of the SBUS make life simple when |
| 26 | + * it's so much fun to make it more difficult? Inverting the signal is easy and can be done with a simple transistor / resistor (see our website) or an inverter: |
| 27 | + * http://www.hobbyking.com/hobbyking/store/__24523__ZYX_S_S_BUS_Connection_Cable.html |
| 28 | + * (the shortest end goes to the receiver, the longest to the Arduino) |
| 29 | + * Alternatively, if you use an X4R you can tap directly into the inverted signal provided on the PCB for a side connector. Details of how to do this are on our website. |
| 30 | + * See http://www.robotmaker.eu/ROBOTmaker/quadcopter-3d-proximity-sensing/sbus-graphical-representation |
| 31 | + * |
| 32 | + * The code works on an Arduino Pro Mini. It will probably work on others too, but I haven't tried on other versions yet |
| 33 | + * Ensure to Download the library -> <SoftwareSerial.h> and <Servo.h> via the Arduino IDE otherwise the code won't compile |
| 34 | + * |
| 35 | + * |
| 36 | + * |
| 37 | + * |
| 38 | + */ |
| 39 | +#include <SoftwareSerial.h> |
| 40 | +//#include <SoftwareServo.h> |
| 41 | +#include <Servo.h> |
| 42 | +#define rxPin 7 |
| 43 | +#define txPin 8 |
| 44 | +Servo myservo8; // create servo object to control a servo |
| 45 | +int pos = 0; // variable to store the servo position |
| 46 | + |
| 47 | +//Not used in the Demo |
| 48 | +//Servo myservo9; // create servo object to control a servo |
| 49 | +//Servo myservo10; // create servo object to control a servo |
| 50 | +//Servo myservo11; // create servo object to control a servo |
| 51 | +//SoftwareSerial InvertedSerialPort = SoftwareSerial(rxPin, txPin, true); //(Tx,TX, Inverted mode ping this device uses inverted signaling |
| 52 | +//For Piezo Buzzer |
| 53 | + |
| 54 | +//*********************************************************************** |
| 55 | +// Setup |
| 56 | +//*********************************************************************** |
| 57 | +void setup () |
| 58 | +{ |
| 59 | + |
| 60 | + //The pins on the Arduino need to be defined. In this demo pin 9-13 are used. Pin 13 is the LED on the Arduino which is |
| 61 | + //a simple mehod for debugging. The demo turns this on when the Channel 1 (often used for throttle) exceeds a predefined SBUS level. |
| 62 | + pinMode(13, OUTPUT); //Debug with LED |
| 63 | + pinMode(12, OUTPUT); //Debug with LED |
| 64 | + pinMode(11, OUTPUT); //Debug with LED |
| 65 | + pinMode(10, OUTPUT); //Debug with LED |
| 66 | + pinMode(9, OUTPUT); //Debug with LED |
| 67 | + pinMode(rxPin, INPUT); |
| 68 | + pinMode(txPin, OUTPUT); |
| 69 | + myservo8.attach(8); // attaches the servo on pin 8 to the servo object |
| 70 | + //myservo11.attach(11); // attaches the servo on pin 11 to the servo object |
| 71 | + Serial.begin(100000,SERIAL_8E2); //The SBUS is a non standard baud rate which can be confirmed using an oscilloscope |
| 72 | + } |
| 73 | + |
| 74 | +//*********************************************************************** |
| 75 | +// Loop |
| 76 | +//*********************************************************************** |
| 77 | +void loop () |
| 78 | +{ |
| 79 | + |
| 80 | + //Declare the variabes |
| 81 | + static byte buffer[25]; |
| 82 | + static int channels[18]; |
| 83 | + static int errors = 0; |
| 84 | + static bool failsafe = 0; |
| 85 | + static int idx; |
| 86 | + static unsigned long last_refresh = 0; |
| 87 | + static int lost = 0; |
| 88 | + byte b; |
| 89 | + int i; |
| 90 | + int redPin = 3; |
| 91 | + int greenPin = 5; |
| 92 | + int bluePin = 6; |
| 93 | + word results; |
| 94 | + |
| 95 | + |
| 96 | + |
| 97 | + //Check the serial port for incoming data |
| 98 | + //This could also be done via the serialEvent() |
| 99 | + if (Serial.available ()) { |
| 100 | + b = Serial.read (); |
| 101 | + |
| 102 | + //this is a new package and it' not zero byte then it's probably the start byte B11110000 (sent MSB) |
| 103 | + //so start reading the 25 byte package |
| 104 | + if (idx == 0 && b != 0x0F) { // start byte 15? |
| 105 | + // error - wait for the start byte |
| 106 | + |
| 107 | + } else { |
| 108 | + buffer[idx++] = b; // fill the buffer with the bytes until the end byte B0000000 is recived |
| 109 | + } |
| 110 | + |
| 111 | + if (idx == 25) { // If we've got 25 bytes then this is a good package so start to decode |
| 112 | + idx = 0; |
| 113 | + if (buffer[24] != 0x00) { |
| 114 | + errors++; |
| 115 | + } else |
| 116 | + { |
| 117 | + // Serial.println("Found Packet"); |
| 118 | + // 25 byte packet received is little endian. Details of how the package is explained on our website: |
| 119 | + //http://www.robotmaker.eu/ROBOTmaker/quadcopter-3d-proximity-sensing/sbus-graphical-representation |
| 120 | + channels[1] = ((buffer[1] |buffer[2]<<8) & 0x07FF); |
| 121 | + channels[2] = ((buffer[2]>>3 |buffer[3]<<5) & 0x07FF); |
| 122 | + channels[3] = ((buffer[3]>>6 |buffer[4]<<2 |buffer[5]<<10) & 0x07FF); |
| 123 | + channels[4] = ((buffer[5]>>1 |buffer[6]<<7) & 0x07FF); |
| 124 | + channels[5] = ((buffer[6]>>4 |buffer[7]<<4) & 0x07FF); |
| 125 | + channels[6] = ((buffer[7]>>7 |buffer[8]<<1 |buffer[9]<<9) & 0x07FF); |
| 126 | + channels[7] = ((buffer[9]>>2 |buffer[10]<<6) & 0x07FF); |
| 127 | + channels[8] = ((buffer[10]>>5|buffer[11]<<3) & 0x07FF); |
| 128 | + channels[9] = ((buffer[12] |buffer[13]<<8) & 0x07FF); |
| 129 | + channels[10] = ((buffer[13]>>3|buffer[14]<<5) & 0x07FF); |
| 130 | + channels[11] = ((buffer[14]>>6|buffer[15]<<2|buffer[16]<<10) & 0x07FF); |
| 131 | + channels[12] = ((buffer[16]>>1|buffer[17]<<7) & 0x07FF); |
| 132 | + channels[13] = ((buffer[17]>>4|buffer[18]<<4) & 0x07FF); |
| 133 | + channels[14] = ((buffer[18]>>7|buffer[19]<<1|buffer[20]<<9) & 0x07FF); |
| 134 | + channels[15] = ((buffer[20]>>2|buffer[21]<<6) & 0x07FF); |
| 135 | + channels[16] = ((buffer[21]>>5|buffer[22]<<3) & 0x07FF); |
| 136 | + channels[17] = ((buffer[23]) & 0x0001) ? 2047 : 0; |
| 137 | + channels[18] = ((buffer[23] >> 1) & 0x0001) ? 2047 : 0; |
| 138 | + |
| 139 | + failsafe = ((buffer[23] >> 3) & 0x0001) ? 1 : 0; |
| 140 | + if ((buffer[23] >> 2) & 0x0001) lost++; |
| 141 | + //serialPrint (lost); debg the signals lost |
| 142 | + |
| 143 | + |
| 144 | + //For this demo, the corresponding channels mapped below need to be also configured on the FrSky Taranis tranmitter accordingly. |
| 145 | + //Any of the Channels can of course be used trigger any of the pins on the Arduino |
| 146 | + //Channels used in the demo are 5,6,7. Mapped these to the sliders on the transmitter to change RGB LED values |
| 147 | + //Channel 1 set to trigger the Internal Arduino LED on pin 13 once the threshold exceeds 1500 |
| 148 | + //Channel 10 needs to be mapped to one of the switches on the Taranis which triggers a buzzer on pin 10 of the Arduino |
| 149 | + //Channel 1 also triggers a servo connected to pin 8 on the Arduino. So moving the throttle will also move the servo accordingly |
| 150 | + |
| 151 | + |
| 152 | + //*********************************************************************** |
| 153 | + //Create RGB 3 colour LED display using PWM on pins mapped to Ch5=S1, Ch6=S2 Ch7=LS |
| 154 | + //The channels used in the demo are 5,6,7. Mapped these to the sliders on the transmitter to change |
| 155 | + //The amount of RGB values |
| 156 | + //*********************************************************************** |
| 157 | + int RedLed = map(channels[5],0,2000,0,255); |
| 158 | + int GreenLed = map(channels[6],0,2000,0,255); |
| 159 | + int BlueLed = map(channels[7],0,2000,0,255); |
| 160 | + analogWrite(redPin, RedLed); |
| 161 | + analogWrite(greenPin, GreenLed); |
| 162 | + analogWrite(bluePin, BlueLed); |
| 163 | + |
| 164 | + |
| 165 | + //*********************************************************************** |
| 166 | + //Turn on internal Arduino LED 13 if channel 1 (thrust) exceeds 1500. |
| 167 | + //*********************************************************************** |
| 168 | + results=channels[1]; |
| 169 | + Serial.write (results); |
| 170 | + if (channels[1] > 1500){ |
| 171 | + |
| 172 | + digitalWrite(13, HIGH); |
| 173 | + } |
| 174 | + else |
| 175 | + { |
| 176 | + digitalWrite(13, LOW); |
| 177 | + } |
| 178 | + |
| 179 | + //*********************************************************************** |
| 180 | + //Turn on LED. Channel 16 mapped to switch SF to trigger Buzzer on pin 12 |
| 181 | + //*********************************************************************** |
| 182 | + serialPrint (channels[1]); |
| 183 | + if (channels[16] > 500){ |
| 184 | + digitalWrite(12, HIGH); |
| 185 | + } |
| 186 | + else |
| 187 | + { |
| 188 | + digitalWrite(12, LOW); |
| 189 | + } |
| 190 | + |
| 191 | + |
| 192 | + |
| 193 | + //*********************************************************************** |
| 194 | + //Drive a Servo connected to channel 1 (which is mapped to thrust if you are using Mode 2) |
| 195 | + //Servo connected to pin 8 on the Arduino |
| 196 | + //*********************************************************************** |
| 197 | + // Proportionaly Map the position of the S.BUS channel to the server position |
| 198 | + int servoPosition = map(channels[1],0,2000,0,180); |
| 199 | + myservo8.write(servoPosition ); // tell servo to go to position in variable servoPosition |
| 200 | + |
| 201 | + //*********************************************************************** |
| 202 | + //Turn on or off a buzzer. Channel 10 is mapped to switch SH. |
| 203 | + // Buzzer connected to pin 10 on Arduino |
| 204 | + //*********************************************************************** |
| 205 | + if (channels[10] > 1500){ |
| 206 | + digitalWrite(10, HIGH); |
| 207 | + } |
| 208 | + else |
| 209 | + { |
| 210 | + digitalWrite(10, LOW); |
| 211 | + } |
| 212 | + } //closing - else |
| 213 | + } //closing - if (idx == 25) |
| 214 | + } //closing - if (Serial.available ()) |
| 215 | +} //closing void loop |
0 commit comments