Quellcode durchsuchen

Added AVR CPPM code from xyFC project

Thomas Buck vor 8 Jahren
Ursprung
Commit
2428d302cc
2 geänderte Dateien mit 186 neuen und 0 gelöschten Zeilen
  1. 150
    0
      cppm.c
  2. 36
    0
      cppm.h

+ 150
- 0
cppm.c Datei anzeigen

@@ -0,0 +1,150 @@
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
+ * Copyright 2016 by Thomas Buck <xythobuz@xythobuz.de>
26
+ *
27
+ * This program is free software; you can redistribute it and/or
28
+ * modify it under the terms of the GNU General Public License as
29
+ * published by the Free Software Foundation, version 2.
30
+ */
31
+
32
+#include <avr/io.h>
33
+#include <avr/interrupt.h>
34
+
35
+#include "cppm.h"
36
+
37
+#define MAX_STATES 17
38
+#define CHANNELS 8
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
+
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;
51
+volatile uint16_t triggerTimeRemaining = 0;
52
+
53
+#define NONE 0
54
+#define COMPARE_MATCH 1
55
+#define OVERFLOW 2
56
+volatile uint8_t triggerState = NONE;
57
+
58
+static void triggerIn(uint16_t us);
59
+static void nextState(void);
60
+
61
+void cppmInit(void) {
62
+    // Set pin to output mode
63
+    CPPM_DDR |= (1 << CPPM_PIN);
64
+
65
+    // Start with a low pulse
66
+    CPPM_PORT &= ~(1 << CPPM_PIN);
67
+
68
+    TCCR0B |= (1 << CS01); // Prescaler: 8
69
+
70
+#ifdef DEBUG
71
+    TIMSK0 |= (1 << TOIE0) | (1 << OCIE0A); // Enable Overflow and Compare Match Interrupt
72
+#else
73
+    TIMSK |= (1 << TOIE0) | (1 << OCIE0A); // Enable Overflow and Compare Match Interrupt
74
+#endif
75
+    OCR0A = 0;
76
+
77
+    state = 0;
78
+    delaySum = MIN_WAIT;
79
+    triggerIn(PULSE_LOW);
80
+}
81
+
82
+void cppmCopy(uint16_t *data) {
83
+    cli();
84
+    for (int i = 0; i < CHANNELS; i++) {
85
+        cppmData[i] = data[i];
86
+    }
87
+    sei();
88
+}
89
+
90
+static void triggerIn(uint16_t us) {
91
+    TCNT0 = 0; // Reset Timer
92
+    if (us <= (TIME_AFTER_OVERFLOW - 1)) {
93
+        triggerState = COMPARE_MATCH;
94
+        OCR0A = us * TIME_MULTIPLIER;
95
+    } else {
96
+        triggerState = OVERFLOW;
97
+        triggerTimeRemaining = us - TIME_AFTER_OVERFLOW;
98
+    }
99
+}
100
+
101
+static void nextState(void) {
102
+    state++;
103
+    if (state > MAX_STATES) {
104
+        state = 0;
105
+        delaySum = MIN_WAIT;
106
+    }
107
+    if ((state % 2) == 0) {
108
+        // pulse pause
109
+        CPPM_PORT &= ~(1 << CPPM_PIN);
110
+        triggerIn(PULSE_LOW);
111
+    } else {
112
+        CPPM_PORT |= (1 << CPPM_PIN);
113
+        if (state <= 15) {
114
+            // normal ppm pulse
115
+            uint8_t index = state / 2;
116
+            triggerIn(cppmData[index]);
117
+            delaySum += PULSE_WIDTH - cppmData[index];
118
+        } else {
119
+            // sync pulse
120
+            triggerIn(delaySum);
121
+        }
122
+    }
123
+}
124
+
125
+#ifdef DEBUG
126
+ISR(TIMER0_OVF_vect) {
127
+#else
128
+ISR(TIM0_OVF_vect) {
129
+#endif
130
+    if (triggerState == OVERFLOW) {
131
+        if (triggerTimeRemaining == 0) {
132
+            triggerState = NONE;
133
+            nextState();
134
+        } else {
135
+            triggerIn(triggerTimeRemaining);
136
+        }
137
+    }
138
+}
139
+
140
+#ifdef DEBUG
141
+ISR(TIMER0_COMPA_vect) {
142
+#else
143
+ISR(TIM0_COMPA_vect) {
144
+#endif
145
+    if (triggerState == COMPARE_MATCH) {
146
+        triggerState = NONE;
147
+        nextState();
148
+    }
149
+}
150
+

+ 36
- 0
cppm.h Datei anzeigen

@@ -0,0 +1,36 @@
1
+/*
2
+ * Combined-PPM signal generator
3
+ * Copyright 2016 by Thomas Buck <xythobuz@xythobuz.de>
4
+ *
5
+ * This program is free software; you can redistribute it and/or
6
+ * modify it under the terms of the GNU General Public License as
7
+ * published by the Free Software Foundation, version 2.
8
+ */
9
+
10
+#ifndef _CPPM_H
11
+#define _CPPM_H
12
+
13
+#include <stdint.h>
14
+
15
+#ifdef DEBUG
16
+
17
+// Arduino D10
18
+#define CPPM_PORT PORTB
19
+#define CPPM_DDR DDRB
20
+#define CPPM_PIN PB2
21
+
22
+#else
23
+
24
+#define CPPM_PORT PORTB
25
+#define CPPM_DDR DDRB
26
+#define CPPM_PIN PB5
27
+
28
+#endif
29
+
30
+extern volatile uint16_t cppmData[8];
31
+
32
+void cppmInit(void);
33
+void cppmCopy(uint16_t *data);
34
+
35
+#endif
36
+

Laden…
Abbrechen
Speichern