Browse Source

Can now set CPPM parameters using MFD

Thomas Buck 7 years ago
parent
commit
d04e2a8ad7
7 changed files with 259 additions and 86 deletions
  1. 6
    43
      Saitek-X52-PPM.ino
  2. 30
    32
      cppm.cpp
  3. 50
    2
      cppm.h
  4. 21
    1
      events.h
  5. 149
    5
      events_buttons.cpp
  6. 2
    2
      events_cppm.cpp
  7. 1
    1
      x52.h

+ 6
- 43
Saitek-X52-PPM.ino View File

21
 
21
 
22
 #define ENABLE_SERIAL_PORT
22
 #define ENABLE_SERIAL_PORT
23
 #define DEBUG_OUTPUT
23
 #define DEBUG_OUTPUT
24
-//#define DEBUG_INPUT
24
+//#define DEBUG_MFD_UPTIME
25
 
25
 
26
 USB usb;
26
 USB usb;
27
 USBHub hub(&usb);
27
 USBHub hub(&usb);
51
         ErrorMessage<uint8_t >(PSTR("SetReportParser"), 1);
51
         ErrorMessage<uint8_t >(PSTR("SetReportParser"), 1);
52
     }
52
     }
53
 
53
 
54
-    cppmInit();
54
+    CPPM::instance().init();
55
 }
55
 }
56
 
56
 
57
 void init_joystick() {
57
 void init_joystick() {
58
     x52.initialize();
58
     x52.initialize();
59
     x52.setMFDText(0, "Arduino X52 Host");
59
     x52.setMFDText(0, "Arduino X52 Host");
60
-    x52.setMFDText(1, "  initialized!  ");
61
-    x52.setMFDText(2, "                ");
60
+    x52.setMFDText(1, "should be ready!");
61
+    x52.setMFDText(2, " OK for options ");
62
 }
62
 }
63
 
63
 
64
 void loop() {
64
 void loop() {
73
             initialized = 1;
73
             initialized = 1;
74
         }
74
         }
75
 
75
 
76
+#ifdef DEBUG_MFD_UPTIME
76
         String text = "Uptime: " + String(millis() / 1000) + "s";
77
         String text = "Uptime: " + String(millis() / 1000) + "s";
77
         x52.setMFDText(2, text.c_str());
78
         x52.setMFDText(2, text.c_str());
78
-    }
79
-
80
-#ifdef DEBUG_INPUT
81
-    if (Serial.available()) {
82
-        char c = Serial.read();
83
-        if (c == 't') {
84
-            x52.setMFDText(0, "Arduino");
85
-            x52.setMFDText(1, "Hello");
86
-            x52.setMFDText(2, "World");
87
-        } else if (c == '0') {
88
-            x52.setMFDBrightness(0);
89
-        } else if (c == '1') {
90
-            x52.setMFDBrightness(1);
91
-        } else if (c == '2') {
92
-            x52.setMFDBrightness(2);
93
-        } else if (c == '3') {
94
-            x52.setLEDBrightness(0);
95
-        } else if (c == '4') {
96
-            x52.setLEDBrightness(1);
97
-        } else if (c == '5') {
98
-            x52.setLEDBrightness(2);
99
-        } else if (c == 'q') {
100
-            x52.setShift(1);
101
-        } else if (c == 'w') {
102
-            x52.setShift(0);
103
-        } else if (c == 'a') {
104
-            x52.setBlink(1);
105
-        } else if (c == 's') {
106
-            x52.setBlink(0);
107
-        } else if (c == 'z') {
108
-            x52.setDate(1, 1, 1);
109
-        } else if (c == 'x') {
110
-            x52.setTime(12, 42);
111
-            x52.setTimeOffset(0, -120);
112
-            x52.setTimeOffset(0, 240);
113
-        } else {
114
-            Serial.println("Unknown command!");
115
-        }
116
-    }
117
 #endif
79
 #endif
80
+    }
118
 }
81
 }
119
 
82
 

+ 30
- 32
cppm.cpp View File

16
 
16
 
17
 //#define DEBUG_OUTPUT
17
 //#define DEBUG_OUTPUT
18
 
18
 
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
19
+CPPM* CPPM::inst = NULL;
24
 
20
 
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;
29
-
30
-void cppmInit(void) {
21
+void CPPM::init(void) {
31
 #ifdef DEBUG_OUTPUT
22
 #ifdef DEBUG_OUTPUT
32
     Serial.println("Initializing Timer...");
23
     Serial.println("Initializing Timer...");
33
 #endif
24
 #endif
34
 
25
 
35
-    for (uint8_t i = 0; i < CHANNELS; i++) {
36
-        cppmData[i] = CHANNEL_DEFAULT_VALUE;
26
+    state = 1;
27
+    currentChannel = channels;
28
+    calcRest = 0;
29
+    for (uint8_t i = 0; i < channels; i++) {
30
+        data[i] = CHANNEL_DEFAULT_VALUE;
37
     }
31
     }
38
 
32
 
39
     pinMode(CPPM_OUTPUT_PIN, OUTPUT);
33
     pinMode(CPPM_OUTPUT_PIN, OUTPUT);
40
-    digitalWrite(CPPM_OUTPUT_PIN, ON_STATE ? LOW : HIGH);
34
+    digitalWrite(CPPM_OUTPUT_PIN, CPPM::inst->onState ? LOW : HIGH);
41
 
35
 
42
     cli();
36
     cli();
43
     TCCR1A = 0; // set entire TCCR1 register to 0
37
     TCCR1A = 0; // set entire TCCR1 register to 0
49
     sei();
43
     sei();
50
 }
44
 }
51
 
45
 
52
-void cppmCopy(uint16_t *data) {
46
+void CPPM::copy(uint16_t* d) {
53
 #ifdef DEBUG_OUTPUT
47
 #ifdef DEBUG_OUTPUT
54
     Serial.println("New CPPM data!");
48
     Serial.println("New CPPM data!");
55
 #endif
49
 #endif
56
 
50
 
57
     cli();
51
     cli();
58
-    for (int i = 0; i < CHANNELS; i++) {
59
-        cppmData[i] = data[i];
52
+    for (int i = 0; i < channels; i++) {
53
+        data[i] = d[i];
60
     }
54
     }
61
     sei();
55
     sei();
62
 }
56
 }
63
 
57
 
64
-ISR(TIMER1_COMPA_vect){
58
+ISR(TIMER1_COMPA_vect) {
59
+    if (!CPPM::inst) {
60
+        return;
61
+    }
62
+
65
     TCNT1 = 0;
63
     TCNT1 = 0;
66
-    if (state) {
64
+    if (CPPM::inst->state) {
67
         // start pulse
65
         // start pulse
68
-        digitalWrite(CPPM_OUTPUT_PIN, ON_STATE ? HIGH : LOW);
69
-        OCR1A = PULSE_LENGTH << 1;
70
-        state = 0;
66
+        digitalWrite(CPPM_OUTPUT_PIN, CPPM::inst->onState ? HIGH : LOW);
67
+        OCR1A = CPPM::inst->pulseLength << 1;
68
+        CPPM::inst->state = 0;
71
     } else {
69
     } else {
72
         // end pulse and calculate when to start the next pulse
70
         // 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;
71
+        digitalWrite(CPPM_OUTPUT_PIN, CPPM::inst->onState ? LOW : HIGH);
72
+        CPPM::inst->state = 1;
73
+        if (CPPM::inst->currentChannel >= CPPM::inst->channels) {
74
+            CPPM::inst->currentChannel = 0;
75
+            CPPM::inst->calcRest += CPPM::inst->pulseLength;
76
+            OCR1A = (CPPM::inst->frameLength - CPPM::inst->calcRest) << 1;
77
+            CPPM::inst->calcRest = 0;
80
         } else {
78
         } else {
81
-            OCR1A = (cppmData[currentChannel] - PULSE_LENGTH) << 1;
82
-            calcRest += cppmData[currentChannel];
83
-            currentChannel++;
79
+            OCR1A = (CPPM::inst->data[CPPM::inst->currentChannel] - CPPM::inst->pulseLength) << 1;
80
+            CPPM::inst->calcRest += CPPM::inst->data[CPPM::inst->currentChannel];
81
+            CPPM::inst->currentChannel++;
84
         }
82
         }
85
     }
83
     }
86
 }
84
 }

+ 50
- 2
cppm.h View File

11
 #define __CPPM_H__
11
 #define __CPPM_H__
12
 
12
 
13
 #include <stdint.h>
13
 #include <stdint.h>
14
+#include <avr/interrupt.h>
14
 
15
 
15
 #define CPPM_OUTPUT_PIN 4
16
 #define CPPM_OUTPUT_PIN 4
17
+#define CHANNEL_DEFAULT_VALUE 1500
18
+#define CHANNELS_MAX 12
16
 
19
 
17
-void cppmInit(void);
18
-void cppmCopy(uint16_t *data);
20
+ISR(TIMER1_COMPA_vect);
21
+
22
+class CPPM {
23
+  public:
24
+    inline static CPPM& instance() {
25
+        if (!inst) {
26
+            inst = new CPPM();
27
+        }
28
+        return *inst;
29
+    }
30
+
31
+    void init(void);
32
+    void copy(uint16_t* d);
33
+
34
+    inline uint16_t getChannels() { return channels; }
35
+    inline void setChannels(uint16_t c) {
36
+        if (c > CHANNELS_MAX)
37
+            c = CHANNELS_MAX;
38
+        channels = c;
39
+    }
40
+
41
+    inline uint16_t getFrameLength() { return frameLength; }
42
+    inline void setFrameLength(uint16_t fl) { frameLength = fl; }
43
+
44
+    inline uint16_t getPulseLength() { return pulseLength; }
45
+    inline void setPulseLength(uint16_t pl) { pulseLength = pl; }
46
+
47
+    inline uint8_t getInvert() { return !onState; }
48
+    inline void setInvert(uint8_t i) { onState = !i; }
49
+
50
+  private:
51
+    CPPM() : channels(6), frameLength(20000), pulseLength(300), onState(1) { }
52
+    CPPM(CPPM&) { }
53
+
54
+    volatile uint16_t channels;
55
+    volatile uint16_t frameLength; // PPM frame length in microseconds (1ms = 1000µs)
56
+    volatile uint16_t pulseLength;
57
+    volatile uint8_t onState; // polarity of the pulses: 1 is positive, 0 is negative
58
+
59
+    volatile uint16_t data[CHANNELS_MAX];
60
+    volatile uint8_t state;
61
+    volatile uint8_t currentChannel;
62
+    volatile uint16_t calcRest;
63
+
64
+    static CPPM* inst;
65
+    friend void TIMER1_COMPA_vect(void);
66
+};
19
 
67
 
20
 #endif // __CPPM_H__
68
 #endif // __CPPM_H__
21
 
69
 

+ 21
- 1
events.h View File

58
     virtual void OnMouseMoved(uint8_t x, uint8_t y);
58
     virtual void OnMouseMoved(uint8_t x, uint8_t y);
59
 
59
 
60
   private:
60
   private:
61
-    const static uint8_t channels = 8;
61
+    const static uint8_t channels = 12;
62
     uint16_t values[channels];
62
     uint16_t values[channels];
63
 };
63
 };
64
 
64
 
72
     virtual void OnMouseMoved(uint8_t x, uint8_t y);
72
     virtual void OnMouseMoved(uint8_t x, uint8_t y);
73
 
73
 
74
   private:
74
   private:
75
+    enum MenuState {
76
+        NONE = 0,
77
+        MAINMENU,
78
+
79
+        STATES_EDIT,
80
+        EDIT_CHANNELS,
81
+        EDIT_FRAME_LENGTH,
82
+        EDIT_PULSE_LENGTH,
83
+        EDIT_INVERT,
84
+
85
+        STATES_MAX
86
+    };
87
+
88
+    void printMenu();
89
+    void menuHelper(uint8_t count, const char** menu, const char* title);
90
+    void printValue(uint16_t min, uint16_t max, const char* title);
91
+
75
     X52* x52;
92
     X52* x52;
93
+    MenuState state;
94
+    uint8_t index;
95
+    uint16_t value;
76
 };
96
 };
77
 
97
 
78
 #endif // __JOYSTICK_EVENTS_H__
98
 #endif // __JOYSTICK_EVENTS_H__

+ 149
- 5
events_buttons.cpp View File

13
 #include <Arduino.h>
13
 #include <Arduino.h>
14
 #include "data.h"
14
 #include "data.h"
15
 #include "x52.h"
15
 #include "x52.h"
16
+#include "cppm.h"
16
 #include "events.h"
17
 #include "events.h"
17
 
18
 
18
-#define DEBUG_BUTTON_MFD
19
+#define DEBUG_OUTPUT
20
+//#define DEBUG_BUTTON_MFD
21
+
22
+#define MENU_BUTTON_ENTER_1 29
23
+#define MENU_BUTTON_ENTER_2 26
24
+#define MENU_BUTTON_DOWN 27
25
+#define MENU_BUTTON_UP 28
26
+
27
+#define MODE_BUTTON_GREEN 23
28
+#define MODE_BUTTON_YELLOW 24
29
+#define MODE_BUTTON_RED 25
19
 
30
 
20
 JoystickEventsButtons::JoystickEventsButtons(X52* x, JoystickEvents* client)
31
 JoystickEventsButtons::JoystickEventsButtons(X52* x, JoystickEvents* client)
21
-        : JoystickEvents(client), x52(x) { }
32
+        : JoystickEvents(client), x52(x), state(NONE), index(0), value(0) { }
22
 
33
 
23
 void JoystickEventsButtons::OnGamePadChanged(const GamePadEventData& evt) {
34
 void JoystickEventsButtons::OnGamePadChanged(const GamePadEventData& evt) {
24
     if (client) {
35
     if (client) {
48
     }
59
     }
49
 }
60
 }
50
 
61
 
62
+void JoystickEventsButtons::menuHelper(uint8_t count, const char** menu, const char* title) {
63
+    if (index >= count) {
64
+        index = count - 1;
65
+    }
66
+
67
+    uint8_t start = 0, line = 0;
68
+    if (index > 1) {
69
+        start = index - 1;
70
+    }
71
+    uint8_t end = start + 2;
72
+    if (index == 0) {
73
+        x52->setMFDText(0, title);
74
+        line = 1;
75
+        end = start + 1;
76
+    }
77
+    if (end >= count) {
78
+        end = count - 1;
79
+    }
80
+    for (uint8_t i = start; i <= end; i++) {
81
+        String tmp = (index == i) ? "-> " : "   ";
82
+        x52->setMFDText(line++, (tmp + menu[i]).c_str());
83
+    }
84
+    if (line == 2) {
85
+        x52->setMFDText(2);
86
+    }
87
+
88
+#ifdef DEBUG_OUTPUT
89
+    Serial.print("menuHelper() state=");
90
+    Serial.print(state);
91
+    Serial.print(" index=");
92
+    Serial.print(index);
93
+    Serial.print(" start=");
94
+    Serial.print(start);
95
+    Serial.print(" end=");
96
+    Serial.println(end);
97
+#endif
98
+}
99
+
100
+void JoystickEventsButtons::printMenu() {
101
+    static const char* mainMenu[] = {
102
+        "Channels", "Frame Length",
103
+        "Pulse Length", "Invert"
104
+    };
105
+    static const uint8_t mainMenuCount = sizeof(mainMenu) / sizeof(mainMenu[0]);
106
+
107
+    if (state == MAINMENU) {
108
+        menuHelper(mainMenuCount, mainMenu, "Main Menu");
109
+    } else if (state == EDIT_CHANNELS) {
110
+        printValue(4, CHANNELS_MAX, mainMenu[0]);
111
+    } else if (state == EDIT_FRAME_LENGTH) {
112
+        printValue(10000, 30000, mainMenu[1]);
113
+    } else if (state == EDIT_PULSE_LENGTH) {
114
+        printValue(100, 1000, mainMenu[2]);
115
+    } else if (state == EDIT_INVERT) {
116
+        printValue(0, 1, mainMenu[3]);
117
+    }
118
+}
119
+
120
+void JoystickEventsButtons::printValue(uint16_t min, uint16_t max, const char* title) {
121
+#ifdef DEBUG_OUTPUT
122
+    Serial.print("printValue() state=");
123
+    Serial.print(state);
124
+    Serial.print(" index=");
125
+    Serial.print(index);
126
+    Serial.print(" min=");
127
+    Serial.print(min);
128
+    Serial.print(" max=");
129
+    Serial.println(max);
130
+#endif
131
+
132
+    if (value < min) {
133
+        value = min;
134
+    }
135
+    if (value > max) {
136
+        value = max;
137
+    }
138
+
139
+    x52->setMFDText(0, (String(title) + ":").c_str());
140
+    x52->setMFDText(1, String(value).c_str());
141
+    x52->setMFDText(2, "Press OK to save");
142
+}
143
+
51
 void JoystickEventsButtons::OnButtonDown(uint8_t but_id) {
144
 void JoystickEventsButtons::OnButtonDown(uint8_t but_id) {
52
 #ifdef DEBUG_BUTTON_MFD
145
 #ifdef DEBUG_BUTTON_MFD
53
     String text = "Button " + String(but_id) + " down";
146
     String text = "Button " + String(but_id) + " down";
54
     x52->setMFDText(1, text.c_str());
147
     x52->setMFDText(1, text.c_str());
55
 #endif
148
 #endif
56
 
149
 
57
-    if (but_id == 23) {
150
+    if (but_id == MODE_BUTTON_GREEN) {
58
         x52->setLEDBrightness(2);
151
         x52->setLEDBrightness(2);
59
         x52->setMFDBrightness(2);
152
         x52->setMFDBrightness(2);
60
-    } else if (but_id == 24) {
153
+    } else if (but_id == MODE_BUTTON_YELLOW) {
61
         x52->setLEDBrightness(1);
154
         x52->setLEDBrightness(1);
62
         x52->setMFDBrightness(1);
155
         x52->setMFDBrightness(1);
63
-    } else if (but_id == 25) {
156
+    } else if (but_id == MODE_BUTTON_RED) {
64
         x52->setLEDBrightness(0);
157
         x52->setLEDBrightness(0);
65
         x52->setMFDBrightness(0);
158
         x52->setMFDBrightness(0);
159
+    } else if ((but_id == MENU_BUTTON_ENTER_1) || (but_id == MENU_BUTTON_ENTER_2)) {
160
+        if (state == NONE) {
161
+            state = MAINMENU;
162
+        } else if (state == MAINMENU) {
163
+            if (index == 0) {
164
+                state = EDIT_CHANNELS;
165
+                value = CPPM::instance().getChannels();
166
+            } else if (index == 1) {
167
+                state = EDIT_FRAME_LENGTH;
168
+                value = CPPM::instance().getFrameLength();
169
+            } else if (index == 2) {
170
+                state = EDIT_PULSE_LENGTH;
171
+                value = CPPM::instance().getPulseLength();
172
+            } else if (index == 3) {
173
+                state = EDIT_INVERT;
174
+                value = CPPM::instance().getInvert();
175
+            }
176
+        } else if (state == EDIT_CHANNELS) {
177
+            CPPM::instance().setChannels(value);
178
+            state = MAINMENU;
179
+        } else if (state == EDIT_FRAME_LENGTH) {
180
+            CPPM::instance().setFrameLength(value);
181
+            state = MAINMENU;
182
+        } else if (state == EDIT_PULSE_LENGTH) {
183
+            CPPM::instance().setPulseLength(value);
184
+            state = MAINMENU;
185
+        } else if (state == EDIT_INVERT) {
186
+            CPPM::instance().setInvert(value);
187
+            state = MAINMENU;
188
+        }
189
+        printMenu();
190
+    } else if (but_id == MENU_BUTTON_DOWN) {
191
+        if (state > STATES_EDIT) {
192
+            if (value > 0) {
193
+                value--;
194
+            }
195
+        } else if (state != NONE) {
196
+            index++;
197
+        }
198
+        printMenu();
199
+    } else if (but_id == MENU_BUTTON_UP) {
200
+        if (state > STATES_EDIT) {
201
+            if (value < 0xFFFF) {
202
+                value++;
203
+            }
204
+        } else if (state != NONE) {
205
+            if (index > 0) {
206
+                index--;
207
+            }
208
+        }
209
+        printMenu();
66
     }
210
     }
67
 
211
 
68
     if (client) {
212
     if (client) {

+ 2
- 2
events_cppm.cpp View File

30
     values[CHANNEL_AUX1] = 1000;
30
     values[CHANNEL_AUX1] = 1000;
31
     values[CHANNEL_AUX2] = 1000;
31
     values[CHANNEL_AUX2] = 1000;
32
 
32
 
33
-    cppmCopy(values);
33
+    CPPM::instance().copy(values);
34
 }
34
 }
35
 
35
 
36
 void JoystickEventsCPPM::OnGamePadChanged(const GamePadEventData& evt) {
36
 void JoystickEventsCPPM::OnGamePadChanged(const GamePadEventData& evt) {
41
     values[CHANNEL_AUX1] = map(evt.Ry, 0, 0xFF, 1000, 2000);
41
     values[CHANNEL_AUX1] = map(evt.Ry, 0, 0xFF, 1000, 2000);
42
     values[CHANNEL_AUX2] = map(evt.Slider, 0, 0xFF, 1000, 2000);
42
     values[CHANNEL_AUX2] = map(evt.Slider, 0, 0xFF, 1000, 2000);
43
 
43
 
44
-    cppmCopy(values);
44
+    CPPM::instance().copy(values);
45
 
45
 
46
     if (client) {
46
     if (client) {
47
         client->OnGamePadChanged(evt);
47
         client->OnGamePadChanged(evt);

+ 1
- 1
x52.h View File

55
      * Print text on the MFD lines (0 - 2).
55
      * Print text on the MFD lines (0 - 2).
56
      * Maximum of 16 characters per line.
56
      * Maximum of 16 characters per line.
57
      */
57
      */
58
-    void setMFDText(uint8_t line, const char* text);
58
+    void setMFDText(uint8_t line, const char* text = "                ");
59
 
59
 
60
     /*
60
     /*
61
      * Enable (1) or Disable(0) the MFD shift indicator.
61
      * Enable (1) or Disable(0) the MFD shift indicator.

Loading…
Cancel
Save