S-Bus input

Post Reply
Teo
Posts: 6
Joined: Mon Apr 18, 2011 4:41 pm

S-Bus input

Post by Teo »

Hello,

Is't possible to some how integrate S-Bus encoding to MWC code? Because now there is small 3/18 channel full-range S-Bus receiver. Here is one encoder board but only 8 channel http://forum.mikrokopter.de/topic-16535.html

Teo

Captain Ixi
Posts: 3
Joined: Sun Sep 04, 2011 10:32 pm

Re: S-Bus input

Post by Captain Ixi »

It is possible!!!
I did it (with a little help from Zaggo).
The following code it works with 8 channels (It should be easy to extend it to the maximum like 16/2). At the moment it only works with Arduino/Flyduino/Seeduino Mega but not with the Pro Mini/Duemilanove/Uno ... , because of the missing second UART (I'll try to fix this, but I got no time at the moment).
I tested it with Futaba FF8 (T8 FG) + R6208SB and the Flyduino Mega (ATMega 2048) at the Multiwii 1.8 code. Only one Problem: You have to invert the S-Bus-Serial Signal e.g. with a Hex-Inverter like IC SN74 LS 04.

Change the code of RX.pde to

Code: Select all

static uint8_t pinRcChannel[8]  = {ROLLPIN, PITCHPIN, YAWPIN, THROTTLEPIN, AUX1PIN,AUX2PIN,CAM1PIN,CAM2PIN};
volatile uint16_t rcPinValue[8] = {1500,1500,1500,1500,1500,1500,1500,1500}; // interval [1000;2000]
static int16_t rcData4Values[8][4];
static int16_t rcDataMean[8];

// ***PPM SUM SIGNAL***
#ifdef SERIAL_SUM_PPM
static uint8_t rcChannel[8] = {SERIAL_SUM_PPM};
#endif
// ***S-BUS Signal***
#ifdef SBUS
static uint8_t rcChannel[8] = {SBUS}; //8 channels yet, no problem getting 16 channels! you hav to change some other stuff!
static uint16_t sbus[25]={0};
static boolean sbusSynched = false;
static unsigned int sbusIndex=0;
static int rc0 = 0;// ROLL-YAW-MIXER - experimental!!!
static int rc7 = 0;// ROLL-YAW-MIXER - experimental!!!
static unsigned int rc7a = 0;// ROLL-YAW-MIXER - experimental!!!
static long corr= 0;// ROLL-YAW-MIXER - experimental!!!
#define SBUS_SYNCBYTE 0x0F // Not 100% shure: at the beginning of coding it was 0xF0 !!!
#endif
volatile uint16_t rcValue[8] = {1500,1500,1500,1500,1500,1500,1500,1500}; // interval [1000;2000]

// Configure each rc pin for PCINT
void configureReceiver() {
  #if !defined(SERIAL_SUM_PPM) && !defined(SPEKTRUM) && !defined(SBUS)
    for (uint8_t chan = 0; chan < 8; chan++)
      for (uint8_t a = 0; a < 4; a++)
        rcData4Values[chan][a] = 1500; //we initiate the default value of each channel. If there is no RC receiver connected, we will see those values
    #if defined(PROMINI)
      // PCINT activated only for specific pin inside [D0-D7]  , [D2 D4 D5 D6 D7] for this multicopter
      PORTD   = (1<<2) | (1<<4) | (1<<5) | (1<<6) | (1<<7); //enable internal pull ups on the PINs of PORTD (no high impedence PINs)
      PCMSK2 |= (1<<2) | (1<<4) | (1<<5) | (1<<6) | (1<<7);
      PCICR   = 1<<2; // PCINT activated only for the port dealing with [D0-D7] PINs
    #endif
    #if defined(MEGA)
      // PCINT activated only for specific pin inside [A8-A15]
      DDRK = 0;  // defined PORTK as a digital port ([A8-A15] are consired as digital PINs and not analogical)
      PORTK   = (1<<0) | (1<<1) | (1<<2) | (1<<3) | (1<<4) | (1<<5) | (1<<6) | (1<<7); //enable internal pull ups on the PINs of PORTK
      PCMSK2 |= (1<<0) | (1<<1) | (1<<2) | (1<<3) | (1<<4) | (1<<5) | (1<<6) | (1<<7);
      PCICR   = 1<<2; // PCINT activated only for PORTK dealing with [A8-A15] PINs
    #endif
  #endif
  #if defined(SERIAL_SUM_PPM)
    PPM_PIN_INTERRUPT
  #endif
  #if defined (SPEKTRUM)
 
  #endif
  #if defined(SBUS)
    Serial1.begin(100000);
  #endif
}

#if !defined(SERIAL_SUM_PPM) && !defined(SPEKTRUM) && !defined(SBUS)
ISR(PCINT2_vect) { //this ISR is common to every receiver channel, it is call everytime a change state occurs on a digital pin [D2-D7]
  uint8_t mask;
  uint8_t pin;
  uint16_t cTime,dTime;
  static uint16_t edgeTime[8];
  static uint8_t PCintLast;

  #if defined(PROMINI)
    pin = PIND;             // PIND indicates the state of each PIN for the arduino port dealing with [D0-D7] digital pins (8 bits variable)
  #endif
  #if defined(MEGA)
    pin = PINK;             // PINK indicates the state of each PIN for the arduino port dealing with [A8-A15] digital pins (8 bits variable)
  #endif
  mask = pin ^ PCintLast;   // doing a ^ between the current interruption and the last one indicates wich pin changed
  sei();                    // re enable other interrupts at this point, the rest of this interrupt is not so time critical and can be interrupted safely
  PCintLast = pin;          // we memorize the current state of all PINs [D0-D7]

  cTime = micros();         // micros() return a uint32_t, but it is not usefull to keep the whole bits => we keep only 16 bits
 
  // mask is pins [D0-D7] that have changed // the principle is the same on the MEGA for PORTK and [A8-A15] PINs
  // chan = pin sequence of the port. chan begins at D2 and ends at D7
  if (mask & 1<<2)           //indicates the bit 2 of the arduino port [D0-D7], that is to say digital pin 2, if 1 => this pin has just changed
    if (!(pin & 1<<2)) {     //indicates if the bit 2 of the arduino port [D0-D7] is not at a high state (so that we match here only descending PPM pulse)
      dTime = cTime-edgeTime[2]; if (900<dTime && dTime<2200) rcPinValue[2] = dTime; // just a verification: the value must be in the range [1000;2000] + some margin
    } else edgeTime[2] = cTime;    // if the bit 2 of the arduino port [D0-D7] is at a high state (ascending PPM pulse), we memorize the time
  if (mask & 1<<4)   //same principle for other channels   // avoiding a for() is more than twice faster, and it's important to minimize execution time in ISR
    if (!(pin & 1<<4)) {
      dTime = cTime-edgeTime[4]; if (900<dTime && dTime<2200) rcPinValue[4] = dTime;
    } else edgeTime[4] = cTime;
  if (mask & 1<<5)
    if (!(pin & 1<<5)) {
      dTime = cTime-edgeTime[5]; if (900<dTime && dTime<2200) rcPinValue[5] = dTime;
    } else edgeTime[5] = cTime;
  if (mask & 1<<6)
    if (!(pin & 1<<6)) {
      dTime = cTime-edgeTime[6]; if (900<dTime && dTime<2200) rcPinValue[6] = dTime;
    } else edgeTime[6] = cTime;
  if (mask & 1<<7)
    if (!(pin & 1<<7)) {
      dTime = cTime-edgeTime[7]; if (900<dTime && dTime<2200) rcPinValue[7] = dTime;
    } else edgeTime[7] = cTime;
  #if defined(MEGA)
    if (mask & 1<<0)   
      if (!(pin & 1<<0)) {
        dTime = cTime-edgeTime[0]; if (900<dTime && dTime<2200) rcPinValue[0] = dTime;
      } else edgeTime[0] = cTime;
    if (mask & 1<<1)     
      if (!(pin & 1<<1)) {
        dTime = cTime-edgeTime[1]; if (900<dTime && dTime<2200) rcPinValue[1] = dTime;
      } else edgeTime[1] = cTime;
    if (mask & 1<<3)
      if (!(pin & 1<<3)) {
        dTime = cTime-edgeTime[3]; if (900<dTime && dTime<2200) rcPinValue[3] = dTime;
      } else edgeTime[3] = cTime;
  #endif
  #if defined(FAILSAFE)
    if (mask & 1<<THROTTLEPIN) {    // If pulse present on THROTTLE pin (independent from ardu version), clear FailSafe counter  - added by MIS
      if(failsafeCnt > 20) failsafeCnt -= 20; else failsafeCnt = 0; }
  #endif
}
#endif

#if defined(SERIAL_SUM_PPM)
void rxInt() {
  uint16_t now,diff;
  static uint16_t last = 0;
  static uint8_t chan = 0;

  now = micros();
  diff = now - last;
  last = now;
  if(diff>3000) chan = 0;
  else {
    if(900<diff && diff<2200 && chan<8 ) {   //Only if the signal is between these values it is valid, otherwise the failsafe counter should move up
      rcValue[chan] = diff;
      #if defined(FAILSAFE)
        if(failsafeCnt > 20) failsafeCnt -= 20; else failsafeCnt = 0;   // clear FailSafe counter - added by MIS  //incompatible to quadroppm
      #endif
    }
    chan++;
  }
}
#endif

#if defined(SPEKTRUM)


#endif

#if defined(SBUS)
void  readSBus(){
  while(Serial1.available()){
    int val = Serial1.read();
    if(sbusIndex==0 && val != SBUS_SYNCBYTE)
      continue;
    sbus[sbusIndex++] = val;
    if(sbusIndex==25){
      sbusIndex=0;
      rcValue[0] = ((sbus[1]|sbus[2]<< 8) & 0x07FF)/2+976; // Perhaps you may change the term "/2+976" -> center will be 1486
      rcValue[1] = ((sbus[2]>>3|sbus[3]<<5) & 0x07FF)/2+976;
      rcValue[2] = ((sbus[3]>>6|sbus[4]<<2|sbus[5]<<10) & 0x07FF)/2+976;
      rcValue[3] = ((sbus[5]>>1|sbus[6]<<7) & 0x07FF)/2+976;
      rcValue[4] = ((sbus[6]>>4|sbus[7]<<4) & 0x07FF)/2+976;
      rcValue[5] = ((sbus[7]>>7|sbus[8]<<1|sbus[9]<<9) & 0x07FF)/2+976;
      rcValue[6] = ((sbus[9]>>2|sbus[10]<<6) & 0x07FF)/2+976;
      rcValue[7] = ((sbus[10]>>5|sbus[11]<<3) & 0x07FF)/2+976; // & the other 8 + 2 channels if you need them
     
      #if defined(FAILSAFE)
        if(failsafeCnt > 20) failsafeCnt -= 20; else failsafeCnt = 0;   // clear FailSafe counter
      #endif
    }
  }        
}
#endif

uint16_t readRawRC(uint8_t chan) {
  uint16_t data;
  #ifndef SBUS
    uint8_t oldSREG;
    oldSREG = SREG;
    cli(); // Let's disable interrupts
    #ifndef SERIAL_SUM_PPM
      data = rcPinValue[pinRcChannel[chan]]; // Let's copy the data Atomically
    #else
      data = rcValue[rcChannel[chan]];
    #endif
    SREG = oldSREG;
    sei();// Let's enable the interrupts
    #if defined(PROMINI) && !defined(SERIAL_SUM_PPM)
    if (chan>4) return 1500;
    #endif
  #else
    data = rcValue[rcChannel[chan]];
  #endif
  return data; // We return the value correctly copied when the IRQ's where disabled
}
 
void computeRC() {
  static uint8_t rc4ValuesIndex = 0;
  uint8_t chan,a;
  #if defined(SBUS)
    readSBus();
  #endif
  rc4ValuesIndex++;
  for (chan = 0; chan < 8; chan++) {
    rcData4Values[chan][rc4ValuesIndex%4] = readRawRC(chan);
    rcDataMean[chan] = 0;
    for (a=0;a<4;a++) rcDataMean[chan] += rcData4Values[chan][a];
    rcDataMean[chan]= (rcDataMean[chan]+2)/4;
    if ( rcDataMean[chan] < rcData[chan] -3)  rcData[chan] = rcDataMean[chan]+2;
    if ( rcDataMean[chan] > rcData[chan] +3)  rcData[chan] = rcDataMean[chan]-2;
  }
}


and add the following code in config.h after //#define SPEKTRUM

Code: Select all

/* The following line apply only for Futaba S-Bus Receiver on MEGA boards at RX1 only. You have to invert the signal*/
#define SBUS   PITCH,YAW,THROTTLE,ROLL,AUX1,AUX2,CAMPITCH,CAMROLL // Order of channels in the SBUS


And of course: You do it by your own risk. I do not guaratee that it will work 100%.
I hope that you and a lot of other pilots have fun with it and tell me about bugs you find.
Perhaps someone can tell me more about the Start-Byte, because at the beginning of the development some other (nice) guys documented the xF0 and my Receiver worked with this too. But some day my simulations did "funny things" an i was very unhappy until i read somewhere, that the Start-Byte should be x0F. So i fixed it and now it is running very well.

I hope to get some feedback soon.

Captain Ixi

Alexinparis
Posts: 1630
Joined: Wed Jan 19, 2011 9:07 pm

Re: S-Bus input

Post by Alexinparis »

Thank you man for this contribution.
I will integrate it :)

So now, we have:
- standard receiver code
- ppm sum receiver code
- spektrum satellite receiver code (from Danal, not yet integrated)
- S-Bus receiver code from you
- I saw also a contribution from the o24rcp guys with a direct rc communication via an xbee module.

User avatar
aBUGSworstnightmare
Posts: 115
Joined: Mon Jun 27, 2011 8:31 pm
Location: Munich, Germany

Re: S-Bus input

Post by aBUGSworstnightmare »

Hi Alex,

when will you realse a version with Spektrum support? Can it be used on the Pro-Mini too or will we need a mega?

Rgds
aBUGSworstnightmare

Alexinparis
Posts: 1630
Joined: Wed Jan 19, 2011 9:07 pm

Re: S-Bus input

Post by Alexinparis »

Hi,

Spektrum and S-bus option are now merged in the dev version.

It would be possible to use it on a pro mini, but you will have to choose between GUI or receiver.
Not very simple to tune as you won't be able to see the RC inputs in the gui, but it's possible.

User avatar
aBUGSworstnightmare
Posts: 115
Joined: Mon Jun 27, 2011 8:31 pm
Location: Munich, Germany

Re: S-Bus input

Post by aBUGSworstnightmare »

Hi Alex,

realy great news! Well, you're right! Using the satellite and the GUI together is not possible on the Pro-Mini. But, one can use a PPMSUM receiver (I'm using this one http://www.1hoch4.net/downloads/docu/Sp ... M_V0_3.pdf) when connected to the GUI and then only use the satellite when flying.

Rgds
aBUGSworstnightmare

Teo
Posts: 6
Joined: Mon Apr 18, 2011 4:41 pm

Re: S-Bus input

Post by Teo »

Nice :)

Captain Ixi
Posts: 3
Joined: Sun Sep 04, 2011 10:32 pm

Re: S-Bus input

Post by Captain Ixi »

Hi
Today i improved the S-Bus RX to Multiwii.
I included channel 9 to 16 (analog) and 17 and 18 (digital switch) for whatever you need them. I suggest to comment the channels you wont need. I tested it with my upgraded T8FG (now 12 + 2 channels). I also included the failsafe function. It was very easy, because in the S-Bus protocol there is a failsafe-bit (in Byte 25 Bit 4). I didn't test the software in real, because none of my 2 copters actually work, but with the MultiWiiConf1_8 App it worked fine, also the failsafe.
Perhaps Alex improve the software for the cool guys, who have more than 8 channels for some funny things. Perhaps some looping functions.
@ Alex: I recognized, that you included my code in the dev-code and also the code to use the spectrum satellite stuff. Now the code gets more and more confusing, in German we say "Hasenstall". Perhaps you can put the stuff to a separate file.

The RX-file:

Code: Select all

static uint8_t pinRcChannel[8]  = {ROLLPIN, PITCHPIN, YAWPIN, THROTTLEPIN, AUX1PIN,AUX2PIN,CAM1PIN,CAM2PIN};
volatile uint16_t rcPinValue[8] = {1500,1500,1500,1500,1500,1500,1500,1500}; // interval [1000;2000]
static int16_t rcData4Values[8][4];
static int16_t rcDataMean[8];

// ***PPM SUM SIGNAL***
#ifdef SERIAL_SUM_PPM
static uint8_t rcChannel[8] = {SERIAL_SUM_PPM};
#endif
#ifndef SBUS
volatile uint16_t rcValue[8] = {1500,1500,1500,1500,1500,1500,1500,1500}; // interval [1000;2000]
#endif
#ifdef SBUS
/*********** RC alias *****************/
#define AUX3       8
#define AUX4       9
#define AUX5       10
#define AUX6       11
#define AUX7       12
#define AUX8       13
#define AUX9       14
#define AUX10      15
#define DIG1       16
#define DIG2       17

static uint8_t rcChannel[18] = {SBUS};
static uint16_t sbus[25]={0};
static boolean sbusSynched = false;
static unsigned int sbusIndex=0;
#define SBUS_SYNCBYTE 0x0F // Not 100% shure: sometimes it also could be 0xF0 !!!
volatile uint16_t rcValue[18] = {1500,1500,1500,1500,1500,1500,1500,1500,1500,1500,1500,1500,1500,1500,1500,1500,1000,1000}; // for 16 + 2 Channels SBUS

#endif



// Configure each rc pin for PCINT
void configureReceiver() {
  #if !defined(SERIAL_SUM_PPM) && !defined(SPEKTRUM) && !defined(SBUS)
    for (uint8_t chan = 0; chan < 8; chan++)
      for (uint8_t a = 0; a < 4; a++)
        rcData4Values[chan][a] = 1500; //we initiate the default value of each channel. If there is no RC receiver connected, we will see those values
    #if defined(PROMINI)
      // PCINT activated only for specific pin inside [D0-D7]  , [D2 D4 D5 D6 D7] for this multicopter
      PORTD   = (1<<2) | (1<<4) | (1<<5) | (1<<6) | (1<<7); //enable internal pull ups on the PINs of PORTD (no high impedence PINs)
      PCMSK2 |= (1<<2) | (1<<4) | (1<<5) | (1<<6) | (1<<7);
      PCICR   = 1<<2; // PCINT activated only for the port dealing with [D0-D7] PINs
    #endif
    #if defined(MEGA)
      // PCINT activated only for specific pin inside [A8-A15]
      DDRK = 0;  // defined PORTK as a digital port ([A8-A15] are consired as digital PINs and not analogical)
      PORTK   = (1<<0) | (1<<1) | (1<<2) | (1<<3) | (1<<4) | (1<<5) | (1<<6) | (1<<7); //enable internal pull ups on the PINs of PORTK
      PCMSK2 |= (1<<0) | (1<<1) | (1<<2) | (1<<3) | (1<<4) | (1<<5) | (1<<6) | (1<<7);
      PCICR   = 1<<2; // PCINT activated only for PORTK dealing with [A8-A15] PINs
    #endif
  #endif
  #if defined(SERIAL_SUM_PPM)
    PPM_PIN_INTERRUPT
  #endif
  #if defined (SPEKTRUM)
 
  #endif
  #if defined(SBUS)
    Serial1.begin(100000);
  #endif
}

#if !defined(SERIAL_SUM_PPM) && !defined(SPEKTRUM) && !defined(SBUS)
ISR(PCINT2_vect) { //this ISR is common to every receiver channel, it is call everytime a change state occurs on a digital pin [D2-D7]
  uint8_t mask;
  uint8_t pin;
  uint16_t cTime,dTime;
  static uint16_t edgeTime[8];
  static uint8_t PCintLast;

  #if defined(PROMINI)
    pin = PIND;             // PIND indicates the state of each PIN for the arduino port dealing with [D0-D7] digital pins (8 bits variable)
  #endif
  #if defined(MEGA)
    pin = PINK;             // PINK indicates the state of each PIN for the arduino port dealing with [A8-A15] digital pins (8 bits variable)
  #endif
  mask = pin ^ PCintLast;   // doing a ^ between the current interruption and the last one indicates wich pin changed
  sei();                    // re enable other interrupts at this point, the rest of this interrupt is not so time critical and can be interrupted safely
  PCintLast = pin;          // we memorize the current state of all PINs [D0-D7]

  cTime = micros();         // micros() return a uint32_t, but it is not usefull to keep the whole bits => we keep only 16 bits
 
  // mask is pins [D0-D7] that have changed // the principle is the same on the MEGA for PORTK and [A8-A15] PINs
  // chan = pin sequence of the port. chan begins at D2 and ends at D7
  if (mask & 1<<2)           //indicates the bit 2 of the arduino port [D0-D7], that is to say digital pin 2, if 1 => this pin has just changed
    if (!(pin & 1<<2)) {     //indicates if the bit 2 of the arduino port [D0-D7] is not at a high state (so that we match here only descending PPM pulse)
      dTime = cTime-edgeTime[2]; if (900<dTime && dTime<2200) rcPinValue[2] = dTime; // just a verification: the value must be in the range [1000;2000] + some margin
    } else edgeTime[2] = cTime;    // if the bit 2 of the arduino port [D0-D7] is at a high state (ascending PPM pulse), we memorize the time
  if (mask & 1<<4)   //same principle for other channels   // avoiding a for() is more than twice faster, and it's important to minimize execution time in ISR
    if (!(pin & 1<<4)) {
      dTime = cTime-edgeTime[4]; if (900<dTime && dTime<2200) rcPinValue[4] = dTime;
    } else edgeTime[4] = cTime;
  if (mask & 1<<5)
    if (!(pin & 1<<5)) {
      dTime = cTime-edgeTime[5]; if (900<dTime && dTime<2200) rcPinValue[5] = dTime;
    } else edgeTime[5] = cTime;
  if (mask & 1<<6)
    if (!(pin & 1<<6)) {
      dTime = cTime-edgeTime[6]; if (900<dTime && dTime<2200) rcPinValue[6] = dTime;
    } else edgeTime[6] = cTime;
  if (mask & 1<<7)
    if (!(pin & 1<<7)) {
      dTime = cTime-edgeTime[7]; if (900<dTime && dTime<2200) rcPinValue[7] = dTime;
    } else edgeTime[7] = cTime;
  #if defined(MEGA)
    if (mask & 1<<0)   
      if (!(pin & 1<<0)) {
        dTime = cTime-edgeTime[0]; if (900<dTime && dTime<2200) rcPinValue[0] = dTime;
      } else edgeTime[0] = cTime;
    if (mask & 1<<1)     
      if (!(pin & 1<<1)) {
        dTime = cTime-edgeTime[1]; if (900<dTime && dTime<2200) rcPinValue[1] = dTime;
      } else edgeTime[1] = cTime;
    if (mask & 1<<3)
      if (!(pin & 1<<3)) {
        dTime = cTime-edgeTime[3]; if (900<dTime && dTime<2200) rcPinValue[3] = dTime;
      } else edgeTime[3] = cTime;
  #endif
  #if defined(FAILSAFE)
    if (mask & 1<<THROTTLEPIN) {    // If pulse present on THROTTLE pin (independent from ardu version), clear FailSafe counter  - added by MIS
      if(failsafeCnt > 20) failsafeCnt -= 20; else failsafeCnt = 0; }
  #endif
}
#endif

#if defined(SERIAL_SUM_PPM)
void rxInt() {
  uint16_t now,diff;
  static uint16_t last = 0;
  static uint8_t chan = 0;

  now = micros();
  diff = now - last;
  last = now;
  if(diff>3000) chan = 0;
  else {
    if(900<diff && diff<2200 && chan<8 ) {   //Only if the signal is between these values it is valid, otherwise the failsafe counter should move up
      rcValue[chan] = diff;
      #if defined(FAILSAFE)
        if(failsafeCnt > 20) failsafeCnt -= 20; else failsafeCnt = 0;   // clear FailSafe counter - added by MIS  //incompatible to quadroppm
      #endif
    }
    chan++;
  }
}
#endif

#if defined(SPEKTRUM)


#endif

#if defined(SBUS)
void  readSBus(){
  while(Serial1.available()){
    int val = Serial1.read();
    if(sbusIndex==0 && val != SBUS_SYNCBYTE)
      continue;
    sbus[sbusIndex++] = val;
    if(sbusIndex==25){
      sbusIndex=0;
      rcValue[0] = ((sbus[1]|sbus[2]<< 8) & 0x07FF)/2+976; // Perhaps you may change the term "/2+976" -> center will be 1486
      rcValue[1] = ((sbus[2]>>3|sbus[3]<<5) & 0x07FF)/2+976;
      rcValue[2] = ((sbus[3]>>6|sbus[4]<<2|sbus[5]<<10) & 0x07FF)/2+976;
      rcValue[3] = ((sbus[5]>>1|sbus[6]<<7) & 0x07FF)/2+976;
      rcValue[4] = ((sbus[6]>>4|sbus[7]<<4) & 0x07FF)/2+976;
      rcValue[5] = ((sbus[7]>>7|sbus[8]<<1|sbus[9]<<9) & 0x07FF)/2+976;
      rcValue[6] = ((sbus[9]>>2|sbus[10]<<6) & 0x07FF)/2+976;
      rcValue[7] = ((sbus[10]>>5|sbus[11]<<3) & 0x07FF)/2+976;
      //The following lines: If you need more than 8 channels, max 16 analog + 2 digital. Yust comment the not needed channels!
      rcValue[8] = ((sbus[12]|sbus[13]<< 8) & 0x07FF)/2+976;
      rcValue[9] = ((sbus[13]>>3|sbus[14]<<5) & 0x07FF)/2+976;
      rcValue[10] = ((sbus[14]>>6|sbus[15]<<2|sbus[16]<<10) & 0x07FF)/2+976;
      rcValue[11] = ((sbus[16]>>1|sbus[17]<<7) & 0x07FF)/2+976;
      rcValue[12] = ((sbus[17]>>4|sbus[18]<<4) & 0x07FF)/2+976;
      rcValue[13] = ((sbus[18]>>7|sbus[19]<<1|sbus[20]<<9) & 0x07FF)/2+976;
      rcValue[14] = ((sbus[20]>>2|sbus[21]<<6) & 0x07FF)/2+976;
      rcValue[15] = ((sbus[21]>>5|sbus[22]<<3) & 0x07FF)/2+976;
      // now the two Digital-Channels
      if ((sbus[23]) & 0x0001)       rcValue[16] = 2000; else rcValue[16] = 1000;
      if ((sbus[23] >> 1) & 0x0001)  rcValue[17] = 2000; else rcValue[17] = 1000;

      // Failsafe: there is one Bit in the SBUS-protocol (Byte 25, Bit 4) whitch is the failsafe-indicator-bit
      #if defined(FAILSAFE)
      if (!((sbus[23] >> 3) & 0x0001))
        {if(failsafeCnt > 20) failsafeCnt -= 20; else failsafeCnt = 0;}   // clear FailSafe counter
      #endif
    }
  }        
}
#endif

uint16_t readRawRC(uint8_t chan) {
  uint16_t data;
  #ifndef SBUS
    uint8_t oldSREG;
    oldSREG = SREG;
    cli(); // Let's disable interrupts
    #ifndef SERIAL_SUM_PPM
      data = rcPinValue[pinRcChannel[chan]]; // Let's copy the data Atomically
    #else
      data = rcValue[rcChannel[chan]];
    #endif
    SREG = oldSREG;
    sei();// Let's enable the interrupts
    #if defined(PROMINI) && !defined(SERIAL_SUM_PPM)
    if (chan>4) return 1500;
    #endif
  #else
    data = rcValue[rcChannel[chan]];
  #endif
  return data; // We return the value correctly copied when the IRQ's where disabled
}
 
void computeRC() {
  static uint8_t rc4ValuesIndex = 0;
  uint8_t chan,a;
  #if defined(SBUS)
    readSBus();
  #endif
  rc4ValuesIndex++;
  for (chan = 0; chan < 8; chan++) {
    rcData4Values[chan][rc4ValuesIndex%4] = readRawRC(chan);
    rcDataMean[chan] = 0;
    for (a=0;a<4;a++) rcDataMean[chan] += rcData4Values[chan][a];
    rcDataMean[chan]= (rcDataMean[chan]+2)/4;
    if ( rcDataMean[chan] < rcData[chan] -3)  rcData[chan] = rcDataMean[chan]+2;
    if ( rcDataMean[chan] > rcData[chan] +3)  rcData[chan] = rcDataMean[chan]-2;
  }
}


the new lines for the Config.h

Code: Select all

/* The following line apply only for Futaba S-Bus Receiver on MEGA boards at RX1 only. You have to invert the signal*/
#define SBUS   PITCH,YAW,THROTTLE,ROLL,AUX1,AUX2,CAMPITCH,CAMROLL,AUX3,AUX4,AUX5,AUX6,AUX7,AUX8,AUX9,AUX10,DIG1,DIG2 // Order of channels in the SBUS


Have fun with it!
The same words i always say: I do not guarantee for anything - own risk!

Captain Ixi

Alexinparis
Posts: 1630
Joined: Wed Jan 19, 2011 9:07 pm

Re: S-Bus input

Post by Alexinparis »

Hi,

Thanks for this update.
I didn't know a TX could have up to 18 RC channels !
It will be merged in some way in the dev, but I will still keep the principle of the single RX file.
I think It's much easier to maintain due to the number of common functions.

Captain Ixi
Posts: 3
Joined: Sun Sep 04, 2011 10:32 pm

Re: S-Bus input

Post by Captain Ixi »

Hi
Yesterday i tested the Code i posted (with 16 + 2 channels, actually i just dont know what to do with all of these) in following configuration:
TX: Futaba T8FG (upgraded to Firmware V4 -> 12 + 2 channels)
RX: Futaba R6208SB with Hex-Inverter
Controller: Flyduino Mega (ATMega 2048) at the Multiwii 1.8 code (except the RX-File is the same i just posted)
the rest: Quadrocopter, nothing special!
=> It worked very well! No differences to the old code!
@Alex: You can integrate it into the next version.
To all: Test it!!!!

Captain Ixi

zaggo
Posts: 10
Joined: Sun Aug 21, 2011 5:33 pm

Re: S-Bus input

Post by zaggo »

Alex,
unfortunately there were some bugs introduced into the SBUS code during merging Captain Ixi's code into v1.9.

Here's a diff of the changes needed to fix the SBUS code in v1.9

Code: Select all

diff --git a/MultiWii/RX.pde b/MultiWii/RX.pde
index 4b480ceb668b8bf08d44f1ce38fe0633e74595b2..b186296d21f3c3ffff9722310939faea19344672 100644
--- a/MultiWii/RX.pde
+++ b/MultiWii/RX.pde
@@ -1,4 +1,4 @@
-volatile uint16_t rcValue[8] = {1502,1502,1502,1502,1502,1502,1502,1502}; // interval [1000;2000]
+volatile uint16_t rcValue[18] = {1502, 1502, 1502, 1502, 1502, 1502, 1502, 1502, 1502, 1502, 1502, 1502, 1502, 1502, 1502, 1502, 1502, 1502}; // interval [1000;2000]
 
 #if defined(SERIAL_SUM_PPM)
   static uint8_t rcChannel[8] = {SERIAL_SUM_PPM};
@@ -237,6 +237,9 @@ void  readSBus(){
 
 uint16_t readRawRC(uint8_t chan) {
   uint16_t data;
+#if defined(SBUS)
+  data = rcValue[rcChannel[chan]]; // Let's copy the data Atomically
+#else
   uint8_t oldSREG;
   oldSREG = SREG; cli(); // Let's disable interrupts
   data = rcValue[rcChannel[chan]]; // Let's copy the data Atomically
@@ -264,6 +267,7 @@ uint16_t readRawRC(uint8_t chan) {
       #endif
     }
   #endif
+#endif
   return data; // We return the value correctly copied when the IRQ's where disabled
 }


See also https://github.com/zaggo/MultiWii-Zaggo ... e685ae9f8c

Cheers
Eberhard

Alexinparis
Posts: 1630
Joined: Wed Jan 19, 2011 9:07 pm

Re: S-Bus input

Post by Alexinparis »

ok thanks, I will include it for the next rev.

Alexinparis
Posts: 1630
Joined: Wed Jan 19, 2011 9:07 pm

Re: S-Bus input

Post by Alexinparis »

Hi,

I don't catch the interest of the mod in function readRawRC as data = rcValue[rcChannel[chan]];
is already fine and interrupt protected
could you explain ?

another remark:
#if defined(SBUS)
Serial1.begin(100000);
#endif

100000 is very strange here. shouldn't be something like 115200 of 57600 ?

timecop
Posts: 1880
Joined: Fri Sep 02, 2011 4:48 pm

Re: S-Bus input

Post by timecop »

100000 is the weird baudrate for sbus.

Post Reply