-
Notifications
You must be signed in to change notification settings - Fork 3
/
pwm_to_ppm.ino
162 lines (129 loc) · 4.2 KB
/
pwm_to_ppm.ino
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
//#include <ESP8266WiFi.h>
//#include <ESP8266WebServer.h>
//#include <ArduinoOTA.h>
//#include <WiFiUdp.h>
//#include <WebSocketsServer.h>
//#include <DNSServer.h>
//#include <Hash.h>
//#include "MSP.h"
/* Set these to your desired credentials. */
#define CPU_MHZ 80
#define CHANNEL_NUMBER 8 //set the number of chanels
#define CHANNEL_DEFAULT_VALUE 1100 //set the default servo value
#define FRAME_LENGTH 22500 //set the PPM frame length in microseconds (1ms = 1000µs)
#define PULSE_LENGTH 300 //set the pulse length
#define onState 0 //set polarity of the pulses: 1 is positive, 0 is negative
#define sigPin 5 //set PPM signal output pin on the arduino
//#define DEBUGPIN 4
#define PWM_NUMBER 5 // the number of pwm input chanals
//working 14, 12, 13, 4
//pin name d5, d6, d7, d2
//gpio 2 = d4 ##README## this pin must be disconected during bootup
const unsigned int PWM_PINS[] = {14, 12, 13, 4 ,2};
volatile unsigned long next;
volatile unsigned int ppm_running = 1;
int ppm[CHANNEL_NUMBER];
//ppm
volatile int pwm_value = 0;
volatile int prev_time = 0;
//uint8_t latest_interrupted_pin;
volatile int pwm_time[PWM_NUMBER];//array for tracking the timeings of each pwm pin
volatile int pwm[PWM_NUMBER]; // an array for storing the current pwm values
volatile int current_pwm_pin = 0;
ICACHE_RAM_ATTR void risingPWM() {
// pwm_time[current_pwm_pin] = micros();
prev_time = micros();
// Serial.print("PIN");
// Serial.print(current_pwm_pin);
// Serial.print(": Rise");
// Serial.print("\n");
attachInterrupt(PWM_PINS[current_pwm_pin], fallingPWM, FALLING);
}
ICACHE_RAM_ATTR void fallingPWM() {
ppm[current_pwm_pin] = micros() - prev_time;
// Serial.print("PIN");
// Serial.print(current_pwm_pin);
// Serial.print(": Fall");
// Serial.print("\n");
// ppm[current_pwm_pin] = micros() - pwm_time[current_pwm_pin];
Serial.print("PIN");
Serial.print(current_pwm_pin);
Serial.print(":");
Serial.print(ppm[current_pwm_pin]);
Serial.print(",");
if (current_pwm_pin == PWM_NUMBER - 1) {
Serial.print("\n");
}
detachInterrupt(PWM_PINS[current_pwm_pin]);
current_pwm_pin = (current_pwm_pin + 1) % PWM_NUMBER;
attachInterrupt(PWM_PINS[current_pwm_pin], risingPWM, RISING);
}
void inline ppmISR(void) {
static boolean state = true;
if (state) { //start pulse
digitalWrite(sigPin, onState);
next = next + (PULSE_LENGTH * CPU_MHZ);
state = false;
// alivecount++;
} else { //end pulse and calculate when to start the next pulse
static byte cur_chan_numb;
static unsigned int calc_rest;
digitalWrite(sigPin, !onState);
state = true;
if (cur_chan_numb >= CHANNEL_NUMBER) {
cur_chan_numb = 0;
calc_rest = calc_rest + PULSE_LENGTH;//
next = next + ((FRAME_LENGTH - calc_rest) * CPU_MHZ);
calc_rest = 0;
// digitalWrite(DEBUGPIN, !digitalRead(DEBUGPIN));
} else {
next = next + ((ppm[cur_chan_numb] - PULSE_LENGTH) * CPU_MHZ);
calc_rest = calc_rest + ppm[cur_chan_numb];
cur_chan_numb++;
}
}
timer0_write(next);
}
void setup() {
pinMode(sigPin, OUTPUT);
digitalWrite(sigPin, !onState); //set the PPM signal pin to the default state (off)
//Setup each pwm input pin
for (int i = 0; i < PWM_NUMBER; i++) {
pinMode(PWM_PINS[i], INPUT);
}
noInterrupts();
//initiate
attachInterrupt(digitalPinToInterrupt(PWM_PINS[0]), risingPWM, FALLING);
timer0_isr_init();
timer0_attachInterrupt(ppmISR);
next = ESP.getCycleCount() + 1000;
timer0_write(next);
for (int i = 0; i < CHANNEL_NUMBER; i++) {
ppm[i] = CHANNEL_DEFAULT_VALUE;
}
interrupts();
Serial.begin(115200);
// msp.begin(Serial);
}
unsigned long time_now = 0;
void loop() {
//
// int time = millis();
// ppm[0] = pwm[0];
//// ppm[0] = 1000 + (time % 10000) / 10;
// ppm[1] = 1000 + ((time + 500) % 10000) / 10;
//
////
//// for (int i = 0; i < numInputs; i++) {
//// pinMode(inputPins[i], INPUT);
//// }
//
//
//
// for (int i = 2; i < CHANNEL_NUMBER; i++) {
//
// ppm[i] = 1500;
//// }
// }
// yield();
}