|
@@ -0,0 +1,123 @@
|
|
1
|
+/*
|
|
2
|
+ * Combined-PPM signal generator
|
|
3
|
+ *
|
|
4
|
+ * The whole CPPM pulse should be 20ms long.
|
|
5
|
+ * It contains 8 channels with 2ms each, followed
|
|
6
|
+ * by 4ms of silence. One channel pulse varies between
|
|
7
|
+ * 1 and 2 ms. They are seperated with a very short low
|
|
8
|
+ * pulse of about 0.1ms.
|
|
9
|
+ *
|
|
10
|
+ * 20.000us
|
|
11
|
+ * - 8 * 2.000us = 16.000us
|
|
12
|
+ * - 9 * 100us = 900us
|
|
13
|
+ * = 3.100us
|
|
14
|
+ *
|
|
15
|
+ * 1 2 3 4 5 6 7 8
|
|
16
|
+ * ___ ___ ___ ___ ___ ___ ___ ___ __________
|
|
17
|
+ * | | | | | | | | | | | | | | | | | | |
|
|
18
|
+ * | | | | | | | | | | | | | | | | | | |
|
|
19
|
+ * | | | | | | | | | | | | | | | | | | |
|
|
20
|
+ * |_| |_| |_| |_| |_| |_| |_| |_| |_| |
|
|
21
|
+ *
|
|
22
|
+ * States:
|
|
23
|
+ * 0 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17
|
|
24
|
+ */
|
|
25
|
+
|
|
26
|
+#include <avr/io.h>
|
|
27
|
+#include <avr/interrupt.h>
|
|
28
|
+
|
|
29
|
+#include "cppm.h"
|
|
30
|
+
|
|
31
|
+#define MAX_STATES 17
|
|
32
|
+#define CHANNELS 8
|
|
33
|
+#define WHOLE_PULSE_WIDTH 20000
|
|
34
|
+#define PULSE_WIDTH 2000
|
|
35
|
+#define MAX_PULSE_WIDTH (CHANNELS * PULSE_WIDTH) // 16.000
|
|
36
|
+#define PULSE_LOW 100
|
|
37
|
+#define PULSE_LOW_SUM ((CHANNELS + 1) * PULSE_LOW) // 900
|
|
38
|
+#define MIN_WAIT (WHOLE_PULSE_WIDTH - MAX_PULSE_WIDTH - PULSE_LOW_SUM) // 3100
|
|
39
|
+#define TIME_AFTER_OVERFLOW 128
|
|
40
|
+#define TIME_MULTIPLIER 2
|
|
41
|
+
|
|
42
|
+volatile uint16_t cppmData[CHANNELS] = { 1500, 1500, 1500, 1500, 1500, 1500, 1500, 1500 };
|
|
43
|
+volatile uint16_t delaySum = 0;
|
|
44
|
+volatile uint8_t state = 0;
|
|
45
|
+volatile uint16_t triggerTimeRemaining = 0;
|
|
46
|
+
|
|
47
|
+#define NONE 0
|
|
48
|
+#define COMPARE_MATCH 1
|
|
49
|
+#define OVERFLOW 2
|
|
50
|
+volatile uint8_t triggerState = NONE;
|
|
51
|
+
|
|
52
|
+static void triggerIn(uint16_t us);
|
|
53
|
+static void nextState(void);
|
|
54
|
+
|
|
55
|
+void cppmInit(void) {
|
|
56
|
+ // Set pin to output mode
|
|
57
|
+ CPPM_DDR |= (1 << CPPM_PIN);
|
|
58
|
+
|
|
59
|
+ // Start with a low pulse
|
|
60
|
+ CPPM_PORT &= ~(1 << CPPM_PIN);
|
|
61
|
+
|
|
62
|
+ TCCR0B |= (1 << CS01); // Prescaler: 8
|
|
63
|
+ TIMSK |= (1 << TOIE0) | (1 << OCIE0A); // Enable Overflow and Compare Match Interrupt
|
|
64
|
+ OCR0A = 0;
|
|
65
|
+
|
|
66
|
+ state = 0;
|
|
67
|
+ delaySum = MIN_WAIT;
|
|
68
|
+ triggerIn(PULSE_LOW);
|
|
69
|
+}
|
|
70
|
+
|
|
71
|
+static void triggerIn(uint16_t us) {
|
|
72
|
+ TCNT0 = 0; // Reset Timer
|
|
73
|
+ if (us <= (TIME_AFTER_OVERFLOW - 1)) {
|
|
74
|
+ triggerState = COMPARE_MATCH;
|
|
75
|
+ OCR0A = us * TIME_MULTIPLIER;
|
|
76
|
+ } else {
|
|
77
|
+ triggerState = OVERFLOW;
|
|
78
|
+ triggerTimeRemaining = us - TIME_AFTER_OVERFLOW;
|
|
79
|
+ }
|
|
80
|
+}
|
|
81
|
+
|
|
82
|
+static void nextState(void) {
|
|
83
|
+ state++;
|
|
84
|
+ if (state > MAX_STATES) {
|
|
85
|
+ state = 0;
|
|
86
|
+ delaySum = MIN_WAIT;
|
|
87
|
+ }
|
|
88
|
+ if ((state % 2) == 0) {
|
|
89
|
+ // pulse pause
|
|
90
|
+ CPPM_PORT &= ~(1 << CPPM_PIN);
|
|
91
|
+ triggerIn(PULSE_LOW);
|
|
92
|
+ } else {
|
|
93
|
+ CPPM_PORT |= (1 << CPPM_PIN);
|
|
94
|
+ if (state <= 15) {
|
|
95
|
+ // normal ppm pulse
|
|
96
|
+ uint8_t index = state / 2;
|
|
97
|
+ triggerIn(cppmData[index]);
|
|
98
|
+ delaySum += PULSE_WIDTH - cppmData[index];
|
|
99
|
+ } else {
|
|
100
|
+ // sync pulse
|
|
101
|
+ triggerIn(delaySum);
|
|
102
|
+ }
|
|
103
|
+ }
|
|
104
|
+}
|
|
105
|
+
|
|
106
|
+ISR(TIM0_OVF_vect) {
|
|
107
|
+ if (triggerState == OVERFLOW) {
|
|
108
|
+ if (triggerTimeRemaining == 0) {
|
|
109
|
+ triggerState = NONE;
|
|
110
|
+ nextState();
|
|
111
|
+ } else {
|
|
112
|
+ triggerIn(triggerTimeRemaining);
|
|
113
|
+ }
|
|
114
|
+ }
|
|
115
|
+}
|
|
116
|
+
|
|
117
|
+ISR(TIM0_COMPA_vect) {
|
|
118
|
+ if (triggerState == COMPARE_MATCH) {
|
|
119
|
+ triggerState = NONE;
|
|
120
|
+ nextState();
|
|
121
|
+ }
|
|
122
|
+}
|
|
123
|
+
|