Wednesday, April 23, 2014

Adding the full code for demonstration purposes


#include 
#include 

/*
*Version 1.10b
** DISCLAIMER!!!!  This is a work in progress.  If you decide that adding this
** to you own quad copter, please do so at your own risk.  I am not in any way shape
** or form responsible for your silliness.
** While this is listed as a beta, its really between alpha and beta realities, meaning
** If you look hard at it its alpha, if you look away its beta.  Also remember:
** ---Alpha. Software undergoes alpha testing as a first step in getting user feedback. Alpha is Latin for "doesn't work."
** ---Beta. Software undergoes beta testing shortly before it's released. Beta is Latin for "still doesn't work.
** Copyrights???  This is open source man.  Don't make money off of it at my expense
** enjoy.
** This code is intended to be used in conjunction with an Arduino Mega2560 to interpret
** ultrasonic readings and limit or override user RC control on a quadcopter.
** It is flexible in that it doesnt matter what kind of flight controller you are
** using.  Tested with APM 2.5, APM 2.6, MultiWii 328p and Multiwii MegaPirate.
** If it uses a standard RF controller it will use the same type of control signal
** and this only mimics user control when seen from the flight controllers point of view.
** As stated on my blog, Understand that this is heavily influenced by
** Duane's 8 channel RCArduino work at
** http://rcarduino.blogspot.co.uk/2012/04/how-to-read-multiple-rc-channels-draft.html
*/

#define PITCH_CHANNEL_IN 2  // attach from receiver elevator channel for pitch control (Mega2560 interrupt 0)
#define ROLL_CHANNEL_IN 3   // attach from receiver ailerons channel for roll control (Mega interrupt 1)

#define PITCH_CHANNEL_OUT 12  // attach to flight controller elevator pin
#define ROLL_CHANNEL_OUT 13  // attach to flight controller aileron pin

Servo servoChannel1;  // setup servo channel for pwm output
Servo servoChannel2;  // setup servo channel for pwm output

#define PITCH_FLAG 1  // flag to determine if new input is detected on pitch channel
#define ROLL_FLAG 2   // flag to determine if new input is detected on roll channel

volatile uint32_t SharedNewFlag;  // global shared flag for determining if any flag has been triggered

volatile uint32_t PITCH_IN_SHARED;  // global shared flag for pitch input trigger
volatile uint32_t ROLL_IN_SHARED;   // global shared flag for roll input trigger

#define SONAR_NUM       4 // Number of sonar sensors
#define MAX_DISTANCE  179 // Max distance in cm
#define PING_INTERVAL 33 // Milliseconds between sensor pings (29ms is about the min to avoid cross-sensor echo).

unsigned long pingTimer[SONAR_NUM];
unsigned int cm[SONAR_NUM];
uint8_t currentSensor = 0;

NewPing sonar[SONAR_NUM] = { // NewPing v1.5 library and examples used here.
 // Visit https://code.google.com/p/arduino-new-ping/ for more info
 NewPing(4, 5, MAX_DISTANCE),
 NewPing(6, 7, MAX_DISTANCE),
 NewPing(8, 9, MAX_DISTANCE),
 NewPing(10, 11, MAX_DISTANCE)
};

void setup()
{ Serial.begin(115200);
  servoChannel1.attach(PITCH_CHANNEL_OUT);// attach the servo channel 1 to pitch out pin
 servoChannel2.attach(ROLL_CHANNEL_OUT); // attach the servo channel 2 to roll out pin

 pingTimer[0] = millis() + 75;           // First ping starts at 75ms
 for (uint8_t i = 1; i < SONAR_NUM; i++) // Set the starting time for each sensor.
 pingTimer[i] = pingTimer[i - 1] + PING_INTERVAL;

 attachInterrupt(0, calcPitch, CHANGE); // attach interrupt to the in pins for pass through
 attachInterrupt(1, calcRoll, CHANGE);  // attach interrupt to the in pins for pass through
void loop()
 {
  // static local copies to be used as output and calculation
  static uint32_t PITCH_IN_LOCAL;
  static uint32_t ROLL_IN_LOCAL;
  // local update flag
  static uint32_t LocalNewFlag;
  // check if global flag has been triggered then turn off interrupts until output has been completed
  if (SharedNewFlag)
  {
   noInterrupts(); // turn off hardware interrupts
   LocalNewFlag = SharedNewFlag; // copy the shared flag status into the local flag to allow the shared one to be reset for the next input
   if (LocalNewFlag & PITCH_FLAG)
   // if the local flag is true (greater than 0) and the pitch flag is true update the local copy of the user input
   {
    PITCH_IN_LOCAL = PITCH_IN_SHARED; // set local copy of input to the global shared value
   }

   if (LocalNewFlag & ROLL_FLAG) // same as before local flag and roll flag must be true
   {
    ROLL_IN_LOCAL = ROLL_IN_SHARED;  // set local copy of input to the global shared value
   }

   SharedNewFlag = 0;  // reset global update flag to zero for next loop
   interrupts();
  }

  for (uint8_t i = 0; i < SONAR_NUM; i++)
  { // Loop through all the sensors.
   if (millis() >= pingTimer[i])
   {       // Is it this sensor's time to ping?
    pingTimer[i] += PING_INTERVAL * SONAR_NUM;  // Set next time this sensor will be pinged.
    sonar[currentSensor].timer_stop();          // Make sure previous timer is cancelled.
    currentSensor = i;                          // Sensor being accessed.
    cm[currentSensor] = MAX_DISTANCE;           // Make distance MAX_DISTANCE if there's no echo.
    sonar[currentSensor].ping_timer(echoCheck); // Do the ping (interrupt will call echoCheck).
   }
  }
  int distancef = map(cm[0], 0, 180, 1, 4);
  int distanceb = map(cm[1], 0, 180, 1, 4);
  int distancer = map(cm[2], 0, 180, 1, 4);
  int distancel = map(cm[3], 0, 180, 1, 4);
  
  if (distancef <= distanceb) // checks to see which distance is closer that involves this channel
  {
   switch (distancef)
   {
   case 1:
    if (LocalNewFlag & PITCH_FLAG)
    {
     if (PITCH_IN_LOCAL > 1700)
     {
      servoChannel1.writeMicroseconds(PITCH_IN_LOCAL);
     }
    }
    else
    {
     servoChannel1.writeMicroseconds(1700);
    }
    break;
   case 2:
    if (LocalNewFlag & PITCH_FLAG)
    {
     if (PITCH_IN_LOCAL > 1500)
     {
      servoChannel1.writeMicroseconds(PITCH_IN_LOCAL); //  no user input over 1500
     }
    }
    else
    {
     servoChannel1.writeMicroseconds(1500); 
    }    
    break;
   default:
    if (LocalNewFlag & PITCH_FLAG)
    {
     servoChannel1.writeMicroseconds(PITCH_IN_LOCAL);
    }
   }
  }
  else
  {
   switch (distanceb)
   {
   case 1:
    if (LocalNewFlag & PITCH_FLAG)
    {
     if(PITCH_IN_LOCAL < 1300)
     {
      servoChannel1.writeMicroseconds(PITCH_IN_LOCAL); // back away from the wall
     }
    }
    else
    {
     servoChannel1.writeMicroseconds(1300);
    }
    break;
   case 2:
    if (LocalNewFlag & PITCH_FLAG)
    {
     if(PITCH_IN_LOCAL < 1500)
     {
      servoChannel1.writeMicroseconds(PITCH_IN_LOCAL); //  no user input over 1500
     }
    }
    else
    {
     servoChannel1.writeMicroseconds(1500);
    }
    break;
   default: 
    if (LocalNewFlag & PITCH_FLAG)
    {
     servoChannel1.writeMicroseconds(PITCH_IN_LOCAL);
    }
   }
  }
  if(distancer <= distancel)
  {
   switch (distancer)
   {
   case 1:
    if(LocalNewFlag & ROLL_FLAG)
    {
     if(ROLL_IN_LOCAL < 1300)
     {
      servoChannel2.writeMicroseconds(ROLL_IN_LOCAL); // back away from the wall
     }
    }
    else
    {
     servoChannel2.writeMicroseconds(1300);
    }
    break;
   case 2:
    if(LocalNewFlag & ROLL_FLAG)
    {
     if(ROLL_IN_LOCAL < 1500)
     {
      servoChannel2.writeMicroseconds(ROLL_IN_LOCAL);
     }
    }
    else
    {
     servoChannel2.writeMicroseconds(1500);
    }
    break;
   default:
    if(LocalNewFlag & ROLL_FLAG)
    {
     servoChannel2.writeMicroseconds(ROLL_IN_LOCAL);
    }
   }
  }
  else
  {
   switch (distancel)
   {
   case 1:
    if(LocalNewFlag & ROLL_FLAG)
    {
     if(ROLL_IN_LOCAL > 1700)
     {
      servoChannel2.writeMicroseconds(ROLL_IN_LOCAL); // back away from the wall
     }
    }
    else
    {
     servoChannel2.writeMicroseconds(1700);
    }
    break;
   case 2:
    if(LocalNewFlag & ROLL_FLAG)
    {
     if(ROLL_IN_LOCAL > 1500)
     {
      servoChannel2.writeMicroseconds(ROLL_IN_LOCAL);
     }
    }
    else
    {
     servoChannel2.writeMicroseconds(1500);
    }
    break;
   default:
    if(LocalNewFlag & ROLL_FLAG)
    {
     servoChannel2.writeMicroseconds(ROLL_IN_LOCAL);
    }
   }
  }

  LocalNewFlag = 0; // reset local flag to zero for next update
 }
 // calculate the PWM pulse lengths and flip flags
void calcPitch()
 {
  static uint32_t ulStart;

  if(digitalRead(PITCH_CHANNEL_IN))
  {
   ulStart = micros();
  }
  else
  {
   PITCH_IN_SHARED = (uint32_t)(micros() - ulStart);
   SharedNewFlag |= PITCH_FLAG;
  }
 }
void calcRoll()
 {
  static uint32_t ulStart;

  if(digitalRead(ROLL_CHANNEL_IN))
  {
   ulStart = micros();
  }
  else
  {
   ROLL_IN_SHARED = (uint32_t)(micros() - ulStart);
   SharedNewFlag |= ROLL_FLAG;
  }
 }
void echoCheck() { // If ping received, set the sensor distance to array.
  if (sonar[currentSensor].check_timer())
  cm[currentSensor] = sonar[currentSensor].ping_result / US_ROUNDTRIP_CM;
 }

No comments:

Post a Comment