Futaba SBUS reverse engineered to work with Arduino

Hi guys,

http://www.futaba-rc.com/sbus/index.html

I needed to use both regular servos and SBUS servos for a project I have going on right now. SBUS is an interesting thing. It uses a 100000 baud inverted UART with a 25 byte transmission. Each channel is transmitted using 11 bits of data. There is also a start an end byte. They also use 2 stop bits and even parity. Now is where the fun comes in. The signal is transmitted big endian, but each of the individual bytes are little endian. I had figured all this stuff out when I stumbled upon this gem:

http://mbed.org/users/Digixx/notebook/futaba-s-bus-controlled-by-mbed/

Not only did what they have to say confirm my reverse engineering suspicions, but they had already made a great algorithm to bit bang the transmission into the correct format. A thanks is also due to user fat16lib for his excellent serial library which allows things like changing the parity and stop bits. I modified the code the guys over at MBED had done and used a hex inverter and the results are perfect. I wrote basically none of this code and those that did allow free redistribution so go nuts. IMO the ability to use SBUS is pretty big for arduino. If I feel motivated I'll turn this into a proper library. But for now it is what it is. If you can read code, the way this thing works is pretty self explanatory:

#include <SerialPort.h>

#define SBUS_SIGNAL_OK          0x00
#define SBUS_SIGNAL_LOST        0x01
#define SBUS_SIGNAL_FAILSAFE    0x03

SerialPort<0,25,25> port0;

uint8_t sbus_data[25] = {
  0x0f,0x01,0x04,0x20,0x00,0xff,0x07,0x40,0x00,0x02,0x10,0x80,0x2c,0x64,0x21,0x0b,0x59,0x08,0x40,0x00,0x02,0x10,0x80,0x00,0x00};
int16_t channels[18]  = {
  1023,1023,1023,1023,1023,1023,1023,1023,1023,1023,1023,1023,1023,1023,1023,1023,0,0};
int16_t servos[18]    = {
  1023,1023,1023,1023,1023,1023,1023,1023,1023,1023,1023,1023,1023,1023,1023,1023,0,0};
uint8_t  failsafe_status = SBUS_SIGNAL_FAILSAFE;
int sbus_passthrough = 1;
uint8_t byte_in_sbus;
uint8_t bit_in_sbus;
uint8_t ch;
uint8_t bit_in_channel;
uint8_t bit_in_servo;
uint8_t inBuffer[25];
int bufferIndex=0;
uint8_t inData;
int toChannels = 0;
uint32_t baud = 100000;
void setup(){
  //Serial.begin(100000);
  port0.begin(baud,  SP_2_STOP_BIT | SP_EVEN_PARITY | SP_8_BIT_CHAR);

}

void loop(){
  feedLine();
  if(toChannels==1){
    update_channels();
    update_servos();
    toChannels=0;
  }  
  //update_servos();
}





int16_t channel(uint8_t ch) {
  // Read channel data
  if ((ch>0)&&(ch<=16)){
    return channels[ch-1];
  }
  else{
    return 1023;
  }
}
uint8_t digichannel(uint8_t ch) {
  // Read digital channel data
  if ((ch>0) && (ch<=2)) {
    return channels[15+ch];
  }
  else{
    return 0;
  }
}
void servo(uint8_t ch, int16_t position) {
  // Set servo position
  if ((ch>0)&&(ch<=16)) {
    if (position>2048) {
      position=2048;
    }
    servos[ch-1] = position;
  }
}
void digiservo(uint8_t ch, uint8_t position) {
  // Set digital servo position
  if ((ch>0) && (ch<=2)) {
    if (position>1) {
      position=1;
    }
    servos[15+ch] = position;
  }
}
uint8_t failsafe(void) {
  return failsafe_status;
}

void passthroughSet(int mode) {
  // Set passtrough mode, if true, received channel data is send to servos
  sbus_passthrough = mode;
}

int passthroughRet(void) {
  // Return current passthrough mode
  return sbus_passthrough;
}
void update_servos(void) {
  // Send data to servos
  // Passtrough mode = false >> send own servo data
  // Passtrough mode = true >> send received channel data
  uint8_t i;
  if (sbus_passthrough==0) {
    // clear received channel data
    for (i=1; i<24; i++) {
      sbus_data[i] = 0;
    }

    // reset counters
    ch = 0;
    bit_in_servo = 0;
    byte_in_sbus = 1;
    bit_in_sbus = 0;

    // store servo data
    for (i=0; i<176; i++) {
      if (servos[ch] & (1<<bit_in_servo)) {
        sbus_data[byte_in_sbus] |= (1<<bit_in_sbus);
      }
      bit_in_sbus++;
      bit_in_servo++;

      if (bit_in_sbus == 8) {
        bit_in_sbus =0;
        byte_in_sbus++;
      }
      if (bit_in_servo == 11) {
        bit_in_servo =0;
        ch++;
      }
    }

    // DigiChannel 1
    if (channels[16] == 1) {
      sbus_data[23] |= (1<<0);
    }
    // DigiChannel 2
    if (channels[17] == 1) {
      sbus_data[23] |= (1<<1);
    }

    // Failsafe
    if (failsafe_status == SBUS_SIGNAL_LOST) {
      sbus_data[23] |= (1<<2);
    }

    if (failsafe_status == SBUS_SIGNAL_FAILSAFE) {
      sbus_data[23] |= (1<<2);
      sbus_data[23] |= (1<<3);
    }
  }
  // send data out
  //serialPort.write(sbus_data,25);
 for (i=0;i<25;i++) {
    port0.write(sbus_data[i]);
  }
}
void update_channels(void) {
  uint8_t i;
  uint8_t sbus_pointer = 0;
  // clear channels[]
  for (i=0; i<16; i++) {
    channels[i] = 0;
  }

  // reset counters
  byte_in_sbus = 1;
  bit_in_sbus = 0;
  ch = 0;
  bit_in_channel = 0;

  // process actual sbus data
  for (i=0; i<176; i++) {
    if (sbus_data[byte_in_sbus] & (1<<bit_in_sbus)) {
      channels[ch] |= (1<<bit_in_channel);
    }
    bit_in_sbus++;
    bit_in_channel++;

    if (bit_in_sbus == 8) {
      bit_in_sbus =0;
      byte_in_sbus++;
    }
    if (bit_in_channel == 11) {
      bit_in_channel =0;
      ch++;
    }
  }
  // DigiChannel 1
  if (sbus_data[23] & (1<<0)) {
    channels[16] = 1;
  }
  else{
    channels[16] = 0;
  }
  // DigiChannel 2
  if (sbus_data[23] & (1<<1)) {
    channels[17] = 1;
  }
  else{
    channels[17] = 0;
  }
  // Failsafe
  failsafe_status = SBUS_SIGNAL_OK;
  if (sbus_data[23] & (1<<2)) {
    failsafe_status = SBUS_SIGNAL_LOST;
  }
  if (sbus_data[23] & (1<<3)) {
    failsafe_status = SBUS_SIGNAL_FAILSAFE;
  }

}
void feedLine(){
  while(port0.available()){
    inData = port0.read();
    if (inData == 0x0f){
      bufferIndex = 0;
      inBuffer[bufferIndex] = inData;
      inBuffer[24] = 0xff;
    }
    else{
      bufferIndex ++;
      inBuffer[bufferIndex] = inData;
    }
    if(inBuffer[0]==0x0f & inBuffer[24] == 0x00){

      memcpy(sbus_data,inBuffer,25);
      toChannels = 1;
      return;
    }
  }
}

It took me a while to find the fat16lib SerialPort library you've used (probably because I'm new at this), so here's the link:

http://arduino.cc/forum/index.php/topic,85207.0.html

Have you seen the price of these things?
I won't be using them anytime soon

http://www3.towerhobbies.com/cgi-bin/WTI0095P?FVSEARCH=sbus&search=Go

Have you seen the price of these things?

Yes but they have EASY PAY :slight_smile:


Rob

I found a major bug in the code. The problem come from one of the channels transmitting a byte of 0x0F. I changed the code so that is not longer a problem. It also runs slightly faster:

#include <SerialPort.h>

#define SBUS_SIGNAL_OK          0x00
#define SBUS_SIGNAL_LOST        0x01
#define SBUS_SIGNAL_FAILSAFE    0x03



SerialPort<0,64,64> port0;


uint8_t sbus_data[25] = {
  0x0f,0x01,0x04,0x20,0x00,0xff,0x07,0x40,0x00,0x02,0x10,0x80,0x2c,0x64,0x21,0x0b,0x59,0x08,0x40,0x00,0x02,0x10,0x80,0x00,0x00};
int16_t channels[18]  = {
  1023,1023,1023,1023,1023,1023,1023,1023,1023,1023,1023,1023,1023,1023,1023,1023,0,0};
int16_t servos[18]    = {
  1023,1023,1023,1023,1023,1023,1023,1023,1023,1023,1023,1023,1023,1023,1023,1023,0,0};
uint8_t  failsafe_status = SBUS_SIGNAL_FAILSAFE;
int sbus_passthrough = 1;
uint8_t byte_in_sbus;
uint8_t bit_in_sbus;
uint8_t ch;
uint8_t bit_in_channel;
uint8_t bit_in_servo;
uint8_t inBuffer[25];
int bufferIndex=0;
uint8_t inData;
int toChannels = 0;
uint32_t baud = 99000;
int feedState = 0;


void setup(){
  port0.begin(baud,  SP_2_STOP_BIT | SP_EVEN_PARITY | SP_8_BIT_CHAR);

}

void loop(){

  feedLine();
  
  if(toChannels==1){
    update_channels();
    update_servos();
    toChannels=0;
  }  

}





int16_t channel(uint8_t ch) {
  // Read channel data
  if ((ch>0)&&(ch<=16)){
    return channels[ch-1];
  }
  else{
    return 1023;
  }
}
uint8_t digichannel(uint8_t ch) {
  // Read digital channel data
  if ((ch>0) && (ch<=2)) {
    return channels[15+ch];
  }
  else{
    return 0;
  }
}
void servo(uint8_t ch, int16_t position) {
  // Set servo position
  if ((ch>0)&&(ch<=16)) {
    if (position>2048) {
      position=2048;
    }
    servos[ch-1] = position;
  }
}
void digiservo(uint8_t ch, uint8_t position) {
  // Set digital servo position
  if ((ch>0) && (ch<=2)) {
    if (position>1) {
      position=1;
    }
    servos[15+ch] = position;
  }
}
uint8_t failsafe(void) {
  return failsafe_status;
}

void passthroughSet(int mode) {
  // Set passtrough mode, if true, received channel data is send to servos
  sbus_passthrough = mode;
}

int passthroughRet(void) {
  // Return current passthrough mode
  return sbus_passthrough;
}
void update_servos(void) {
  // Send data to servos
  // Passtrough mode = false >> send own servo data
  // Passtrough mode = true >> send received channel data
  uint8_t i;
  if (sbus_passthrough==0) {
    // clear received channel data
    for (i=1; i<24; i++) {
      sbus_data[i] = 0;
    }

    // reset counters
    ch = 0;
    bit_in_servo = 0;
    byte_in_sbus = 1;
    bit_in_sbus = 0;

    // store servo data
    for (i=0; i<176; i++) {
      if (servos[ch] & (1<<bit_in_servo)) {
        sbus_data[byte_in_sbus] |= (1<<bit_in_sbus);
      }
      bit_in_sbus++;
      bit_in_servo++;

      if (bit_in_sbus == 8) {
        bit_in_sbus =0;
        byte_in_sbus++;
      }
      if (bit_in_servo == 11) {
        bit_in_servo =0;
        ch++;
      }
    }

    // DigiChannel 1
    if (channels[16] == 1) {
      sbus_data[23] |= (1<<0);
    }
    // DigiChannel 2
    if (channels[17] == 1) {
      sbus_data[23] |= (1<<1);
    }

    // Failsafe
    if (failsafe_status == SBUS_SIGNAL_LOST) {
      sbus_data[23] |= (1<<2);
    }

    if (failsafe_status == SBUS_SIGNAL_FAILSAFE) {
      sbus_data[23] |= (1<<2);
      sbus_data[23] |= (1<<3);
    }
  }
  // send data out
  //serialPort.write(sbus_data,25);
  for (i=0;i<25;i++) {
    port0.write(sbus_data[i]);
  }
}
void update_channels(void) {
  uint8_t i;
  uint8_t sbus_pointer = 0;
  // clear channels[]
  for (i=0; i<16; i++) {
    channels[i] = 0;
  }

  // reset counters
  byte_in_sbus = 1;
  bit_in_sbus = 0;
  ch = 0;
  bit_in_channel = 0;

  // process actual sbus data
  for (i=0; i<176; i++) {
    if (sbus_data[byte_in_sbus] & (1<<bit_in_sbus)) {
      channels[ch] |= (1<<bit_in_channel);
    }
    bit_in_sbus++;
    bit_in_channel++;

    if (bit_in_sbus == 8) {
      bit_in_sbus =0;
      byte_in_sbus++;
    }
    if (bit_in_channel == 11) {
      bit_in_channel =0;
      ch++;
    }
  }
  // DigiChannel 1
  if (sbus_data[23] & (1<<0)) {
    channels[16] = 1;
  }
  else{
    channels[16] = 0;
  }
  // DigiChannel 2
  if (sbus_data[23] & (1<<1)) {
    channels[17] = 1;
  }
  else{
    channels[17] = 0;
  }
  // Failsafe
  failsafe_status = SBUS_SIGNAL_OK;
  if (sbus_data[23] & (1<<2)) {
    failsafe_status = SBUS_SIGNAL_LOST;
  }
  if (sbus_data[23] & (1<<3)) {
    failsafe_status = SBUS_SIGNAL_FAILSAFE;
  }

}
void feedLine(){
  if (port0.available() > 24){
    while(port0.available() > 0){
      inData = port0.read();
      switch (feedState){
      case 0:
        if (inData != 0x0f){
          while(port0.available() > 0){//read the contents of in buffer this should resync the transmission
            inData = port0.read();
          }
          return;
        }
        else{
          bufferIndex = 0;
          inBuffer[bufferIndex] = inData;
          inBuffer[24] = 0xff;
          feedState = 1;
        }
        break;
      case 1:
        bufferIndex ++;
        inBuffer[bufferIndex] = inData;
        if (bufferIndex < 24 && port0.available() == 0){
          feedState = 0;
        }
        if (bufferIndex == 24){
          feedState = 0;
          if (inBuffer[0]==0x0f && inBuffer[24] == 0x00){
            memcpy(sbus_data,inBuffer,25);
            toChannels = 1;
          }
        }
        break;
      }
    }
  }
}

I have turned this into a library finally.

FUTABA_SBUS.zip (3.18 KB)

Hi.
It would be very nice if you could include a small description of the hardware-side of this :slight_smile:

alekoy:
Hi.
It would be very nice if you could include a small description of the hardware-side of this :slight_smile:

The output of the SBUS receiver goes into one of the inputs on an inverter (74HC14). The output from that input goes into the serial port. The output of the serial port you are using goes into the inverter and the output will drive SBUS servos. You must have a common ground to all the devices. It is best to run the servos from a different power supply than the arduino.

The library has been updated to no longer rely on the SerialPort.h library

Nice project. FYI, you can get cheap sbus receivers from Hobby King now. I have been looking for a similar solution. I want to convert the sbus protocol into a ppm signal. Does your project have that ability? If so, any idea of how much lag there would be?

Thanks

Sir
I am very interested by this project.
I use the Arduino 1.0 version.
I'm not an Arduino specialist and so, I doesn't compile This like the reply 4.
I have an error like "expected constructor,destructor,or type conversion before '<' token and the line "SerialPort<0,64,64> port0;" is in Yellow.
I have had file "SerialPort.h" from "SerialPortBeta20120106.zip"
In fact, I have a lot of error :
sketch_jan07b.cpp:1:24: error: SerialPort.h: No such file or directory
sketch_jan07b:4: error: expected constructor, destructor, or type conversion before '<' token
sketch_jan07b.cpp: In function 'void setup()':
sketch_jan07b:22: error: 'port0' was not declared in this scope
sketch_jan07b:22: error: 'SP_2_STOP_BIT' was not declared in this scope
sketch_jan07b:22: error: 'SP_EVEN_PARITY' was not declared in this scope
sketch_jan07b:22: error: 'SP_8_BIT_CHAR' was not declared in this scope
sketch_jan07b.cpp: In function 'void update_servos()':
sketch_jan07b:86: error: 'sbus_data' was not declared in this scope
sketch_jan07b:96: error: 'sbus_data' was not declared in this scope
sketch_jan07b:111: error: 'sbus_data' was not declared in this scope
sketch_jan07b:115: error: 'sbus_data' was not declared in this scope
sketch_jan07b:119: error: 'sbus_data' was not declared in this scope
sketch_jan07b:121: error: 'sbus_data' was not declared in this scope
sketch_jan07b:128: error: 'port0' was not declared in this scope
sketch_jan07b:128: error: 'sbus_data' was not declared in this scope
sketch_jan07b.cpp: In function 'void update_channels()':
sketch_jan07b:145: error: 'sbus_data' was not declared in this scope
sketch_jan07b:160: error: 'sbus_data' was not declared in this scope
sketch_jan07b:167: error: 'sbus_data' was not declared in this scope
sketch_jan07b:175: error: 'sbus_data' was not declared in this scope
sketch_jan07b:178: error: 'sbus_data' was not declared in this scope
sketch_jan07b.cpp: In function 'void feedLine()':
sketch_jan07b:183: error: 'port0' was not declared in this scope
sketch_jan07b:210: error: 'sbus_data' was not declared in this scope
Could you hepl me ?
Best regards
Marc

Fantastic work on this Mike 8)

I have a Futaba 14 channel transmitter (T8FG) with the R6208SB S-BUS receiver.

I would like to use the S-BUS channel to control 4 PPM outputs via the Arduino. Just probably simple switched outputs not servos at all.

One appplication is two create a different output depending on the PMM input range from the transmitter.

Is it possible to use your code for this 4 channel application, or is it designed for just one channel.

Many thanks and great work again.

Steve

Sorry for the slow response guys, I thought I was subscribed to this thread. In the future if someone needs some help with this library PM me if I don't respond fairly quickly.

m_marc0 - I have updated the library to no longer require SerialPort.h. It now uses the standard arduino conventions. The library is currently configured to run off of Serial1 on a mega. To change the edit the FUTABA_SBUS.h line 12

#define SBUS_SIGNAL_OK          0x00
#define SBUS_SIGNAL_LOST        0x01
#define SBUS_SIGNAL_FAILSAFE    0x03
#define BAUDRATE 100000
#define port Serial1  <---- this is the line to change

Tissy -I'm not quite clear on what you are trying to accomplish. You can create a PPM signal based off the different channels, but to what end? If you could describe your project in a little more detial hopefully I can give you a better answer. Also, are you sure you aren't confusing PPM with PWM?

Thanks Mike.

Sorry, you're right, I wasn't very clear.

Basically I have a Futaba R6208SB S-BUS receiver which I am using on a multi-rotor.

I have one of the outputs from this receiver going to an Arduino MiniPro which is programmed to detect the PWM signal and use an IR LED to control a Sony NEX5 camera. This works very will and I can switch the camera modes between video and stills and take manual or automatic interval pictures.

As this is connected to one of the main outputs of the Rx and I have a Futaba 14 channel Tx (T8FG), I would like to move auxiliary functions such as this to the S-Bus.

So the code on the MiniPro will read the S-BUS and perform a function (either servo based or logic based) on say 4 channels.

I know this device (FUTM4191 SBD-1 S.Bus Decoder) is available to decode the S-Bus signal to PWM, however I would still need the MiniPro to perform certain functions, so I was looking at cutting out the middle man if possible.

http://www.futaba-rc.com/sbus/

I would need to define the channel on the MiniPro which corresponds to the channel on the Tx, for example channels 9 - 12.

Does that make sense or have I made it worse :smiley:

Steve

Got it. What you need to do is have a way to turn SBUS into PWM.

Let's talk at little bit more about SBUS and DSM2/DSMx serial. They are simply transmitting unsigned integers in raw binary over a UART. This means once you have these values you can do whatever you want with them. DSMx and SBUS have a 2048 resolution (2^11) whereas DSM2 has a 1024 (2^10) resolution. OK so the question now is how do we do something with this information.

First you map those values to a range you want to use:

void MapVar (float *x, float *y, float in_min, float in_max, float out_min, float out_max){
  *y = (*x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min;
}
void MapVar (int16_t *x, float *y, float in_min, float in_max, float out_min, float out_max){
  *y = (*x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min;
}

void MapVar (uint16_t *x, float *y, float in_min, float in_max, float out_min, float out_max){
  *y = (*x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min;
}

In the above code I am using pointers. In addition to using pointers you could simple pass the variables or make the variables global. For the servo control you want to generate a PWM signal. Here is a great article about the difference between the two:

http://www.endurance-rc.com/ppmtut.php

Both PPM and PWM use square waves of varying width to convey information. Let's look at servos and ESC (electronic speed controllers). They are controlled by PWM signal with a frequency between 50 - 500Hz and a pulse width of around 1000 - 2000us. For this signal we are concerned with the pulse width and not the PWM's duty cycle. The center is 1500us, but many servos center at 1520. If you run a servo at too high a frequency it will break the servo. This is also for ESCs.

There are a number of ways that you can generate these signals with the arduino. The easiest is to use servo.h. It will allow you to make a lot of these signals on any pin you want. It also doesn't run all that fast. The maximum refresh rate is ~125Hz. A good flight controller runs the control loops very fast and updates the ESCs at ~400Hz. You want to use AVR C. I know that can be a big turn off for a lot of people here since it is considered difficult. And it is, but it is not too bad. If you do it right you only have to figure it out once. Here is another code sample to illustrate how to generate higher frequency ESC PWM signals. This code was written for the mega, but if you look at the datasheet for the 128 it will become clear to you as to how to do it. If it not don't be afraid to ask for assistance with a concept you are struggling with.

//motor defines
#define FREQ 400
#define PRESCALE 8
#define PERIOD ((F_CPU/PRESCALE/FREQ) - 1)

#define Motor1WriteMicros(x) OCR3B = x * 2//motor 1 is attached to pin2
#define Motor2WriteMicros(x) OCR3C = x * 2//motor 2 is attached to pin3
#define Motor3WriteMicros(x) OCR3A = x * 2//motor 3 is attached to pin5
#define Motor4WriteMicros(x) OCR4A = x * 2//motor 4 is attached to pin6

void setup(){
  MotorInit();
  //do other stuff
}

void loop(){
  Motor1WriteMicros(1250);
  Motor2WriteMicros(someVar);
  //do other stuff
}

void MotorInit(){
  DDRE |= B00111000;//set the ports as outputs
  DDRH |= B00001000;

  
  // Init PWM Timer 3                                       
  // WGMn1 WGMn2 WGMn3  = Mode 14 Fast PWM, TOP = ICRn ,Update of OCRnx at BOTOM
  TCCR3A = (1<<WGM31)|(1<<COM3A1)|(1<<COM3B1)|(1<<COM3C1);  // Clear OCnA/OCnB/OCnC on compare match, set OCnA/OCnB/OCnC at BOTTOM (non-inverting mode)
  TCCR3B = (1<<WGM33)|(1<<WGM32)|(1<<CS31);                 // Prescaler set to 8, that gives us a resolution of 0.5us
  ICR3 = PERIOD;                                // Clock_speed / ( Prescaler * desired_PWM_Frequency) #defined above.  

  TCCR4A = (1<<WGM41)|(1<<COM4A1);
  TCCR4B = (1<<WGM43)|(1<<WGM42)|(1<<CS41);
  ICR4 = PERIOD;
  
  Motor1WriteMicros(1000);//set the output compare value
  Motor2WriteMicros(1000);
  Motor3WriteMicros(1000);
  Motor4WriteMicros(1000);
  
}

This code will not run on the miniPro. This is meant to be an example as to how to set this all up. Furthermore, the 128 only has 1 16bit timer. The above code gives a 0.5us resolution. To use this method with the 128 it will give you two channels with 16bit resolution and two channels with 8 bit of resolution.

Hope that helps. Let me know if there is anything further I can clear up for you.

Michael,

Thank you so much for your detailed response, its really appreciated.

I always seem to jump straight into the deep end.

Is there a reason the code will not run on a ATMega328 Pro Mini?

I have posted my code below to hopefully give you an idea of what I am trying to achieve. Instead of using the normal output from my RC receiver, I would like to adapt the code to use the S-BUS instead and thereby freeing up at least one of the normal Rx channels.

You will see from the code below that if the PWM input is detected between certain frequencies, then it outputs accordingly, in this case utilising an IR Led.

In addition, I would like to use another S-Bus channel for the Arduino to switch on landing lights for example if again a switch on the Tx is 'on'. Chances are I won't need it to control servos, just some auxiliary devices.

So my need is not to generate a PWM signal from the Arduino, but to interpret the S-BUS signal and have set routines depending on the channel input.

Hope that makes sense and thank you again for your assistance.

Steve

#include <multiCameraIrControl.h>

int x=50, y=300, z=100; 
int ledPin = 13;
int IRPin = 2;
int RxInput = A0;
int pic_pause = 5000;
Sony Nex5(IRPin);

void setup()
{
Serial.begin(9600);      // 
  pinMode (IRPin, OUTPUT);  // Output pin for IR LED
  pinMode (RxInput, INPUT);    // Input pin for PWM from Rx
}

void loop () {
z = pulseIn(RxInput, HIGH, 20000);
if (z<1400) {
  digitalWrite(IRPin, 0);
  Serial.println(z);
  delay(y);  
  }
//if (z>1401 && z<1599) {

  if (z>1155 && z<1170) {
    digitalWrite(IRPin, 1);
    Nex5.shutterNow();
  //  Nex5.shutterDelayed();
  //  delay(500);
    digitalWrite(IRPin, 0);
    Serial.println(z);
  //  delay(y);
    }
  
  if (z>1780 && z<1820) {
    digitalWrite(IRPin, 1);
    Nex5.shutterNow();
  //  delay(500);
    digitalWrite(IRPin, 0);
    Serial.println(z);
    delay(pic_pause);
    }

  if (z>1430 && z<1500) {
    digitalWrite(IRPin, 1);
    Nex5.toggleVideo();
    delay(500);
    digitalWrite(IRPin, 0);
    Serial.println(z);
  //  delay(y);
    }
  
  if (z>1600)   {  
    digitalWrite(IRPin, 1); delay (x); digitalWrite(IRPin, 0); delay (x);
    digitalWrite(IRPin, 1); delay (x); digitalWrite(IRPin, 0); delay (x);
    delay(y);
    Serial.println(z);
    }
  }

You should be able to do that no problem. Just assign the variable Z to one of the channels off the SBUS. Use that map function to map max and min of the SBUS channel to whatever you want or modify the code to work with different ranges.

Thanks Mike.

So should the code you have posted above still use the FUTABA_SBUS.h library?

I haven't used the map function before, so should the variables in_min & in_max be the expected PWM frequencies such as 1023 for example from the Rx?

I think I can work my code, I'm just trying to understand how the S_Bus channels are defined etc.

Could you expand a little more please :slight_smile:

Thanks again Mike,

Steve

Hi Mike,

Great stuff you have done, have you had a chance to look at the SBUS2 protocol? It seems to be frames appended after the channel data is sent. I just received an FX32 so should be able to do some tests shortly. Would be interested in building a "base" sensor PCB around Arduino which people could extend to build their own sensors.

One thing I did read is that increasing the telemetry data rate has a direct impact on servo smoothness, which I guess makes perfect sense. Price to pay for sharing bandwidth I guess however not clear if there is any difference depending on amount of telemetry slots being used.

Best,
Serge