|
@@ -1,26 +1,9 @@
|
1
|
1
|
/*
|
2
|
2
|
* Combined-PPM signal generator
|
3
|
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
|
|
4
|
+ * Based on the code from:
|
|
5
|
+ * https://quadmeup.com/generate-ppm-signal-with-arduino/
|
|
6
|
+ * https://github.com/DzikuVx/ppm_encoder/blob/master/ppm_encoder_source.ino
|
24
|
7
|
*
|
25
|
8
|
* Copyright 2016 by Thomas Buck <xythobuz@xythobuz.de>
|
26
|
9
|
*
|
|
@@ -28,41 +11,42 @@
|
28
|
11
|
* modify it under the terms of the GNU General Public License as
|
29
|
12
|
* published by the Free Software Foundation, version 2.
|
30
|
13
|
*/
|
31
|
|
-#include <TimerOne.h>
|
|
14
|
+#include <Arduino.h>
|
32
|
15
|
#include "cppm.h"
|
33
|
16
|
|
34
|
17
|
//#define DEBUG_OUTPUT
|
35
|
|
-//#define DEBUG_OUTPUT_ALL
|
36
|
|
-
|
37
|
|
-#define CHANNELS 8
|
38
|
|
-#define MAX_STATES ((2 * CHANNELS) + 1)
|
39
|
|
-#define WHOLE_PULSE_WIDTH 20000
|
40
|
|
-#define PULSE_WIDTH 2000
|
41
|
|
-#define MAX_PULSE_WIDTH (CHANNELS * PULSE_WIDTH) // 16.000
|
42
|
|
-#define PULSE_LOW 100
|
43
|
|
-#define PULSE_LOW_SUM ((CHANNELS + 1) * PULSE_LOW) // 900
|
44
|
|
-#define MIN_WAIT (WHOLE_PULSE_WIDTH - MAX_PULSE_WIDTH - PULSE_LOW_SUM) // 3100
|
45
|
|
-#define TIME_AFTER_OVERFLOW 128
|
46
|
|
-#define TIME_MULTIPLIER 2
|
47
|
18
|
|
48
|
|
-volatile uint16_t cppmData[CHANNELS] = { 1500, 1500, 1500, 1500, 1500, 1500, 1500, 1500 };
|
49
|
|
-volatile uint16_t delaySum = 0;
|
50
|
|
-volatile uint8_t state = 0;
|
|
19
|
+#define CHANNELS 8 // set the number of chanels
|
|
20
|
+#define CHANNEL_DEFAULT_VALUE 1500 // set the default servo value
|
|
21
|
+#define FRAME_LENGTH 20000 // set the PPM frame length in microseconds (1ms = 1000µs)
|
|
22
|
+#define PULSE_LENGTH 100 // set the pulse length
|
|
23
|
+#define ON_STATE 1 // set polarity of the pulses: 1 is positive, 0 is negative
|
51
|
24
|
|
52
|
|
-static void triggerIn(uint16_t us);
|
53
|
|
-static void nextState(void);
|
|
25
|
+static volatile uint16_t cppmData[CHANNELS];
|
|
26
|
+static volatile uint8_t state = 1;
|
|
27
|
+static volatile uint8_t currentChannel = CHANNELS;
|
|
28
|
+static volatile uint16_t calcRest = 0;
|
54
|
29
|
|
55
|
30
|
void cppmInit(void) {
|
56
|
31
|
#ifdef DEBUG_OUTPUT
|
57
|
32
|
Serial.println("Initializing Timer...");
|
58
|
33
|
#endif
|
59
|
34
|
|
|
35
|
+ for (uint8_t i = 0; i < CHANNELS; i++) {
|
|
36
|
+ cppmData[i] = CHANNEL_DEFAULT_VALUE;
|
|
37
|
+ }
|
|
38
|
+
|
60
|
39
|
pinMode(CPPM_OUTPUT_PIN, OUTPUT);
|
61
|
|
- digitalWrite(CPPM_OUTPUT_PIN, LOW);
|
62
|
|
- Timer1.initialize(PULSE_LOW);
|
63
|
|
- Timer1.attachInterrupt(&nextState);
|
64
|
|
- state = 0;
|
65
|
|
- delaySum = MIN_WAIT;
|
|
40
|
+ digitalWrite(CPPM_OUTPUT_PIN, ON_STATE ? LOW : HIGH);
|
|
41
|
+
|
|
42
|
+ cli();
|
|
43
|
+ TCCR1A = 0; // set entire TCCR1 register to 0
|
|
44
|
+ TCCR1B = 0;
|
|
45
|
+ OCR1A = 100; // compare match register
|
|
46
|
+ TCCR1B |= (1 << WGM12); // turn on CTC mode
|
|
47
|
+ TCCR1B |= (1 << CS11); // 8 prescaler: 0,5 microseconds at 16mhz
|
|
48
|
+ TIMSK1 |= (1 << OCIE1A); // enable timer compare interrupt
|
|
49
|
+ sei();
|
66
|
50
|
}
|
67
|
51
|
|
68
|
52
|
void cppmCopy(uint16_t *data) {
|
|
@@ -77,38 +61,26 @@ void cppmCopy(uint16_t *data) {
|
77
|
61
|
sei();
|
78
|
62
|
}
|
79
|
63
|
|
80
|
|
-static void triggerIn(uint16_t us) {
|
81
|
|
- Timer1.setPeriod(us);
|
82
|
|
- //Timer1.start();
|
83
|
|
-}
|
84
|
|
-
|
85
|
|
-static void nextState(void) {
|
86
|
|
- //Timer1.stop();
|
87
|
|
-
|
88
|
|
-#ifdef DEBUG_OUTPUT_ALL
|
89
|
|
- Serial.print("CPPM state ");
|
90
|
|
- Serial.println(state, DEC);
|
91
|
|
-#endif
|
92
|
|
-
|
93
|
|
- state++;
|
94
|
|
- if (state > MAX_STATES) {
|
|
64
|
+ISR(TIMER1_COMPA_vect){
|
|
65
|
+ TCNT1 = 0;
|
|
66
|
+ if (state) {
|
|
67
|
+ // start pulse
|
|
68
|
+ digitalWrite(CPPM_OUTPUT_PIN, ON_STATE ? HIGH : LOW);
|
|
69
|
+ OCR1A = PULSE_LENGTH << 1;
|
95
|
70
|
state = 0;
|
96
|
|
- delaySum = MIN_WAIT;
|
97
|
|
- }
|
98
|
|
- if (!(state & 0x01)) {
|
99
|
|
- // pulse pause
|
100
|
|
- digitalWrite(CPPM_OUTPUT_PIN, LOW);
|
101
|
|
- triggerIn(PULSE_LOW);
|
102
|
71
|
} else {
|
103
|
|
- digitalWrite(CPPM_OUTPUT_PIN, HIGH);
|
104
|
|
- if (state <= 15) {
|
105
|
|
- // normal ppm pulse
|
106
|
|
- uint8_t index = state >> 1;
|
107
|
|
- triggerIn(cppmData[index]);
|
108
|
|
- delaySum += PULSE_WIDTH - cppmData[index];
|
|
72
|
+ // end pulse and calculate when to start the next pulse
|
|
73
|
+ digitalWrite(CPPM_OUTPUT_PIN, ON_STATE ? LOW : HIGH);
|
|
74
|
+ state = 1;
|
|
75
|
+ if (currentChannel >= CHANNELS) {
|
|
76
|
+ currentChannel = 0;
|
|
77
|
+ calcRest += PULSE_LENGTH;
|
|
78
|
+ OCR1A = (FRAME_LENGTH - calcRest) << 1;
|
|
79
|
+ calcRest = 0;
|
109
|
80
|
} else {
|
110
|
|
- // sync pulse
|
111
|
|
- triggerIn(delaySum);
|
|
81
|
+ OCR1A = (cppmData[currentChannel] - PULSE_LENGTH) << 1;
|
|
82
|
+ calcRest += cppmData[currentChannel];
|
|
83
|
+ currentChannel++;
|
112
|
84
|
}
|
113
|
85
|
}
|
114
|
86
|
}
|