// The arrays that are used globally
unsigned long ch1[15], ch[7];
int nextPos = 0;
int lastPos = 0;
// A boolean to signalize that a number of 15 data is available
boolean dataAvailable = false;
constexpr byte outPin = 8;
constexpr byte buttonPin = 13;
void setup() {
Serial.begin(9600);
pinMode(outPin, OUTPUT);
digitalWrite(outPin, HIGH);
pinMode(buttonPin, INPUT_PULLUP);
pinMode(2, INPUT_PULLUP);
attachInterrupt(digitalPinToInterrupt(2), read_me, FALLING);
// enabling interrupt at pin 2
}
void loop() {
read_rc();
if (buttonReleased()) {
SendRC();
}
}
// All the printing in a separate function
void printData() {
Serial.print("\t");
Serial.print(ch[1]); Serial.print("\t");
Serial.print(ch[2]); Serial.print("\t");
Serial.print(ch[3]); Serial.print("\t");
Serial.print(ch[4]); Serial.print("\t");
Serial.print(ch[5]); Serial.print("\t");
Serial.print(ch[6]);
Serial.println();
}
void read_me() {
//this code reads value from RC reciever from PPM pin (Pin 2 or 3)
//this code gives channel values from 0-1000 values
// -: ABHILASH :- //
// Variables for data only used in this function but must be static
// so they keep their content for the next call
static unsigned long int lastInterruptTime = 0;
static unsigned long x[15];
static int counter = 0;
// Variables which are calculated or set new with every call of the function
unsigned long int interruptTime;
unsigned long int timeDifference;
// While the global variable dataAvailable is true
// we "ignore" interrupts ...
// so we do not interfere with data which have been stored
// until they were handled by read_rc();
if (dataAvailable) {
return;
};
interruptTime = micros(); //store time value a when pin value falling
timeDifference = interruptTime - lastInterruptTime; //calculating time inbetween two peaks
lastInterruptTime = interruptTime; //
x[counter] = timeDifference; //storing 15 value in array
counter++;
if (counter == 15) {
for (int j = 0; j < 15; j++) {
ch1[j] = x[j];
}
counter = 0;
// if we got enough data we tell this to "read_rc()" via dataAvailable
dataAvailable = true;
}
}
//copy store all values from temporary array another array after 15 reading
void read_rc() {
int i, k;
int j = 0; // initialize j with zero
if (dataAvailable) {
showRawData();
for (k = 8; k >= 0; k--) { //we start with k = 8 to avoid an overflow in ch1[i + j] later
if (ch1[k] > 10000) {
j = k; //detecting always the separation space > 10000us in array ch1[] with the lowest(!) index
}
}
for (i = 1; i <= 6; i++) {
ch[i] = (ch1[i + j]-1000); //assign 6 channel values after separation space
}
printData();
dataAvailable = false;
}
}
void SendRC() {
bool toggle = true;
for (int i = 0; i < 15; i++) {
digitalWrite(outPin, LOW);
delayMicroseconds(2);
digitalWrite(outPin, HIGH);
if (toggle) {
delayMicroseconds(2000 + i * 10);
}
else {
delayMicroseconds(1500 + i * 10);
}
if (i==7) delay(10);
toggle = !toggle;
}
}
boolean buttonReleased() {
static unsigned long lastPressed = 0;
static int lastState = HIGH;
static int actState = HIGH;
int state;
state = digitalRead(buttonPin);
if (state != lastState) {
lastPressed = millis();
lastState = state;
}
if (millis() - lastPressed > 30 && state != actState) {
actState = state;
if (actState) {
return true;
}
} else {
return false;
}
}
void showRawData() {
int i;
Serial.println("\n-------------------------------Raw Data -------------------------------------------------");
for (i = 0; i < 15; i++) {
Serial.print("\t");
Serial.print(ch1[i]);
if (i == 7) {
Serial.println();
}
}
Serial.println("\n--------------------------------Prepared Data---------------------------------------------");
}