AUX2 for PROMINI - solution!

This forum is dedicated to software development related to MultiWii.
It is not the right place to submit a setup problem.
Software download
Post Reply
marbalon
Posts: 107
Joined: Thu Aug 18, 2011 10:59 am

AUX2 for PROMINI - solution!

Post by marbalon »

Hi,
I have a solution for every PROMINI user who want to use AUX2 but on the port B. This example will work on pin B0 but if redefine to other pin from PORTB should works with other pin to. Here is what you need to change:

file def.h

Code: Select all

...
  #define AUX1PIN                    7
  #define AUX2PIN                    0   //<-- pin 0 from port B
  #define CAM1PIN                    7   //unused just for compatibility with MEGA
...


RX.pde

function configureReceiver():

Code: Select all

...
    #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 oraz port B
           
      PORTB |= (1<<AUX2PIN);  //<--added
      PCMSK0 |= (1<<AUX2PIN);//<--added
      PCICR  |= 0x01;               //<--added
     
    #endif
...



New function in the same file:

Code: Select all

...
#if defined(PROMINI)
ISR(PCINT0_vect) {
  uint8_t mask;
  uint8_t pin;
  uint16_t cTime,dTime;
  static uint16_t edgeTime;
  static uint8_t PCintLast;

  pin = PINB;
  mask = pin ^ PCintLast;
  sei();                 
  PCintLast = pin;       

  cTime = micros();     
 
  if (mask & (1<<AUX2PIN))
    if (!(pin & (1<<AUX2PIN))) {
      dTime = cTime-edgeTime; if (900<dTime && dTime<2200) rcPinValue[0] = dTime;
    } else edgeTime = cTime;
}
#endif
...


in function readRawRC()

Code: Select all

...
  #if defined(PROMINI) && !defined(SERIAL_SUM_PPM)
  if (chan>5) return 1500; //changed from 4-5
  #endif


And that is all. aux2 work in the same way as other pins from port D but use different interrupt.

Maybe this can be committed to new version?

Cheers,
Marcin.

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

Re: AUX2 for PROMINI - solution!

Post by Alexinparis »

Hi Marcin,

We got it nearly at the same time :)
I was working on this last week with a global simplification of RX.pde between PPM SUM and conventional PPM receiver.
Spektrum UART code is also on the way.

The second ISR can be hugely simplified because there is only one PIN to handle, and we know which one it is.
I think to reuse PIN12 because resetting sensors is not useful for setups with no WMP clones.

here is my current implementation:

Code: Select all

volatile uint16_t rcValue[8] = {1502,1502,1502,1502,1502,1502,1502,1502}; // interval [1000;2000]

// ***PPM SUM SIGNAL***
#ifdef SERIAL_SUM_PPM
static uint8_t rcChannel[8] = {SERIAL_SUM_PPM};
#else
static uint8_t rcChannel[8]  = {ROLLPIN, PITCHPIN, YAWPIN, THROTTLEPIN, AUX1PIN,AUX2PIN,CAM1PIN,CAM2PIN};
#endif

// Configure each rc pin for PCINT
void configureReceiver() {
  #if !defined(SERIAL_SUM_PPM) && !defined(SPEKTRUM)
    #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);

      PORTB   = (1<<0) ; //enable internal pull ups on the PINs of PORTD (no high impedence PINs)
      PCMSK0 |= (1<<0) ; //first PIN of the port (arduino PIN 8)

      PCICR   = (1<<0) | (1<<2); // PCINT activated only for the port dealing with [D0-D7] PINs and [B0-B7] 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(SERIAL_SUM_PPM) && !defined(SPEKTRUM)
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) rcValue[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) rcValue[4] = dTime;
    } else edgeTime[4] = cTime;
  if (mask & 1<<5)
    if (!(pin & 1<<5)) {
      dTime = cTime-edgeTime[5]; if (900<dTime && dTime<2200) rcValue[5] = dTime;
    } else edgeTime[5] = cTime;
  if (mask & 1<<6)
    if (!(pin & 1<<6)) {
      dTime = cTime-edgeTime[6]; if (900<dTime && dTime<2200) rcValue[6] = dTime;
    } else edgeTime[6] = cTime;
  if (mask & 1<<7)
    if (!(pin & 1<<7)) {
      dTime = cTime-edgeTime[7]; if (900<dTime && dTime<2200) rcValue[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) rcValue[0] = dTime;
      } else edgeTime[0] = cTime;
    if (mask & 1<<1)     
      if (!(pin & 1<<1)) {
        dTime = cTime-edgeTime[1]; if (900<dTime && dTime<2200) rcValue[1] = dTime;
      } else edgeTime[1] = cTime;
    if (mask & 1<<3)
      if (!(pin & 1<<3)) {
        dTime = cTime-edgeTime[3]; if (900<dTime && dTime<2200) rcValue[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

// this ISR is a simplication of the previous one for PROMINI on port D
// it's simplier because we know the interruption deals only with on PIN: bit 0 of PORT B, ie Arduino PIN 8
// => no need to check which PIN has changed
ISR(PCINT0_vect) {
  uint8_t pin;
  uint16_t cTime,dTime;
  static uint16_t edgeTime;

  pin = PINB;
  sei();
  cTime = micros();
  if (!(pin & 1<<0)) {     //indicates if the bit 0 of the arduino port [B0-B7] is not at a high state (so that we match here only descending PPM pulse)
    dTime = cTime-edgeTime; if (900<dTime && dTime<2200) rcValue[0] = dTime; // just a verification: the value must be in the range [1000;2000] + some margin
  } else edgeTime = cTime;    // if the bit 2 is at a high state (ascending PPM pulse), we memorize the time

}

#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

uint16_t readRawRC(uint8_t chan) {
  uint16_t data;
  uint8_t oldSREG;
  oldSREG = SREG; cli(); // Let's disable interrupts
  data = rcValue[rcChannel[chan]]; // Let's copy the data Atomically
  SREG = oldSREG; sei();// Let's enable the interrupts
  return data; // We return the value correctly copied when the IRQ's where disabled
}
 
void computeRC() {
  static int16_t rcData4Values[8][4], rcDataMean[8];
  static uint8_t rc4ValuesIndex = 0;
  uint8_t chan,a;

  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;
  }
}

User avatar
UndCon
Posts: 293
Joined: Mon Feb 21, 2011 2:10 pm

Re: AUX2 for PROMINI - solution!

Post by UndCon »

Cool - good work/coding.

If AUX2 will be available for promini it also means all my shields will be outdated as they does not have headers for AUX2.

No big deal but the extra feature could be nice to have. (and I will on my MEGA1280 instead)

//UndCon

actionplus
Posts: 2
Joined: Wed Sep 21, 2011 4:43 pm
Location: Fontana, Ca

Re: AUX2 for PROMINI - solution!

Post by actionplus »

I am trying to use this method so that I can enable/disable my BMP085 using this as AUX2.
I was able to change all code as above except for one.
I could not find:
readRawRC() function in the rx. file from version 1.8p2.

Has this been removed?

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

Re: AUX2 for PROMINI - solution!

Post by aBUGSworstnightmare »

Hi Alex,

is AUX2 availabe in the latest relase (on Pro Mini)? If not, when will it be there?

Rgds
aBUGSworstnightmare

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

Re: AUX2 for PROMINI - solution!

Post by Alexinparis »

I will include it in the next release,
It would be either on PIN 8 or PIN 12 via 2 optional #define

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

Re: AUX2 for PROMINI - solution!

Post by aBUGSworstnightmare »

Hi Alex,

perfect! I've designed the DIVIDE (viewtopic.php?f=6&t=751) with AUX2 connected to D12. So now this I/O can be put to good use for enableing/disabeling sensors.

aBUGSworstnightmare

muggel117
Posts: 1
Joined: Mon Oct 24, 2011 3:02 pm

Re: AUX2 for PROMINI - solution!

Post by muggel117 »

Is it possible to get AUX2 in 1.8p2?

The solution from first post isn't possible in 1.8p2.

bob4432
Posts: 51
Joined: Sat Jan 29, 2011 2:51 am
Location: USA

Re: AUX2 for PROMINI - solution!

Post by bob4432 »

UndCon wrote:Cool - good work/coding.

If AUX2 will be available for promini it also means all my shields will be outdated as they does not have headers for AUX2.

No big deal but the extra feature could be nice to have. (and I will on my MEGA1280 instead)

//UndCon


UndCon, check out Bob's Super Simple Shield w/ Aux2 brought out from Pin8 along with A0, A1 in the ESC lineup :)

Post Reply