Browse Source

Configurable CPPM output pin

Thomas Buck 7 years ago
parent
commit
5b1c1554d9
8 changed files with 56 additions and 20 deletions
  1. 4
    2
      README.md
  2. 9
    7
      Saitek-X52-PPM.ino
  3. 11
    2
      config.cpp
  4. 3
    3
      config.h
  5. 13
    4
      cppm.cpp
  6. 6
    1
      cppm.h
  7. 1
    0
      events.h
  8. 9
    1
      events_buttons.cpp

+ 4
- 2
README.md View File

2
 
2
 
3
 This sketch allows connecting a [Saitek X52](http://www.saitek.com/uk/prod/x52.html) or [Saitek X52 Pro](http://www.saitek.com/uk/prod/x52pro.html) to an [Arduino](https://www.arduino.cc/en/Main/ArduinoBoardUno) with a [USB Host Shield](https://www.arduino.cc/en/Main/ArduinoUSBHostShield). It uses the [USB_Host_Shield_2.0 Library](https://github.com/felis/USB_Host_Shield_2.0).
3
 This sketch allows connecting a [Saitek X52](http://www.saitek.com/uk/prod/x52.html) or [Saitek X52 Pro](http://www.saitek.com/uk/prod/x52pro.html) to an [Arduino](https://www.arduino.cc/en/Main/ArduinoBoardUno) with a [USB Host Shield](https://www.arduino.cc/en/Main/ArduinoUSBHostShield). It uses the [USB_Host_Shield_2.0 Library](https://github.com/felis/USB_Host_Shield_2.0).
4
 
4
 
5
-A CPPM signal is generated on a configurable pin (4 by default, can be changed in `cppm.h`).
5
+A CPPM signal is generated on a configurable pin and can be fed into a transmitter module or directly into a flight controller.
6
 
6
 
7
-It includes code to interface with the Multi-Function-Display on the Joystick to display text and change the LED and background lighting.
7
+Using the Multi-Function-Display on the Joystick, every config option can be changed. These values can be stored on the EEPROM and will be loaded on every start.
8
 
8
 
9
 I'm connecting the Arduino to the [FrSky DHT module](http://www.frsky-rc.com/product/pro.php?pro_id=7) in my modified transmitter to control my Tricopter.
9
 I'm connecting the Arduino to the [FrSky DHT module](http://www.frsky-rc.com/product/pro.php?pro_id=7) in my modified transmitter to control my Tricopter.
10
 
10
 
11
+A modified (ie. non-inverted) FrSky Host Telemetry Port (D-Port) can be connected to the hardware serial port of the Arduino so the Telemetry data (link quality and voltages) will be displayed on the Multi-Function-Display of the joystick.
12
+
11
 ## License
13
 ## License
12
 
14
 
13
 This program is free software; you can redistribute it and/or modify it under the terms of the GNU General Public License as published by the Free Software Foundation, version 2.
15
 This program is free software; you can redistribute it and/or modify it under the terms of the GNU General Public License as published by the Free Software Foundation, version 2.

+ 9
- 7
Saitek-X52-PPM.ino View File

22
 #include "frsky.h"
22
 #include "frsky.h"
23
 #include "config.h"
23
 #include "config.h"
24
 
24
 
25
-#define ENABLE_SERIAL_PORT
25
+#define ENABLE_SERIAL_PORT 9600
26
 //#define DEBUG_OUTPUT Serial
26
 //#define DEBUG_OUTPUT Serial
27
 //#define DEBUG_MFD_UPTIME
27
 //#define DEBUG_MFD_UPTIME
28
 
28
 
29
+#define LED_STATUS_PIN 13
30
+
29
 USB usb;
31
 USB usb;
30
 USBHub hub(&usb);
32
 USBHub hub(&usb);
31
 HIDUniversal hid(&usb);
33
 HIDUniversal hid(&usb);
65
 
67
 
66
 void setup() {
68
 void setup() {
67
 #ifdef ENABLE_SERIAL_PORT
69
 #ifdef ENABLE_SERIAL_PORT
68
-    Serial.begin(115200);
70
+    Serial.begin(ENABLE_SERIAL_PORT);
69
 #endif
71
 #endif
70
 
72
 
71
 #ifdef DEBUG_OUTPUT
73
 #ifdef DEBUG_OUTPUT
72
     DEBUG_OUTPUT.println("Start");
74
     DEBUG_OUTPUT.println("Start");
73
 #endif
75
 #endif
74
 
76
 
75
-    pinMode(13, OUTPUT);
76
-    digitalWrite(13, LOW);
77
+    pinMode(LED_STATUS_PIN, OUTPUT);
78
+    digitalWrite(LED_STATUS_PIN, LOW);
77
 
79
 
78
     eepromRead();
80
     eepromRead();
79
 
81
 
80
     if (usb.Init() == -1) {
82
     if (usb.Init() == -1) {
81
-        digitalWrite(13, HIGH);
83
+        digitalWrite(LED_STATUS_PIN, HIGH);
82
 #ifdef DEBUG_OUTPUT
84
 #ifdef DEBUG_OUTPUT
83
         DEBUG_OUTPUT.println("OSC did not start.");
85
         DEBUG_OUTPUT.println("OSC did not start.");
84
 #endif
86
 #endif
85
     }
87
     }
86
 
88
 
87
     if (!hid.SetReportParser(0, &joy)) {
89
     if (!hid.SetReportParser(0, &joy)) {
88
-        digitalWrite(13, HIGH);
90
+        digitalWrite(LED_STATUS_PIN, HIGH);
89
 #ifdef DEBUG_OUTPUT
91
 #ifdef DEBUG_OUTPUT
90
         DEBUG_OUTPUT.println("Error adding report parser.");
92
         DEBUG_OUTPUT.println("Error adding report parser.");
91
 #endif
93
 #endif
93
 
95
 
94
     CPPM::instance().init();
96
     CPPM::instance().init();
95
     frsky.setDataHandler(&statusCallback);
97
     frsky.setDataHandler(&statusCallback);
96
-    wdt_enable(WDTO_500MS);
98
+    wdt_enable(WDTO_1S);
97
 }
99
 }
98
 
100
 
99
 void init_joystick() {
101
 void init_joystick() {

+ 11
- 2
config.cpp View File

6
  * modify it under the terms of the GNU General Public License as
6
  * modify it under the terms of the GNU General Public License as
7
  * published by the Free Software Foundation, version 2.
7
  * published by the Free Software Foundation, version 2.
8
  */
8
  */
9
+
9
 #include <EEPROM.h>
10
 #include <EEPROM.h>
10
 #include "cppm.h"
11
 #include "cppm.h"
11
 #include "events.h"
12
 #include "events.h"
67
 
68
 
68
 void eepromRead() {
69
 void eepromRead() {
69
     ConfigData data;
70
     ConfigData data;
71
+
70
     if (fromEEPROM(data) != 0) {
72
     if (fromEEPROM(data) != 0) {
71
         data.channels = DEFAULT_CHANNELS;
73
         data.channels = DEFAULT_CHANNELS;
72
         data.frameLength = DEFAULT_FRAME_LENGTH;
74
         data.frameLength = DEFAULT_FRAME_LENGTH;
73
         data.pulseLength = DEFAULT_PULSE_LENGTH;
75
         data.pulseLength = DEFAULT_PULSE_LENGTH;
74
         data.inverted = DEFAULT_INVERT_STATE;
76
         data.inverted = DEFAULT_INVERT_STATE;
77
+        data.cppmPin = CPPM_OUTPUT_PIN_DEFAULT;
75
         for (uint8_t i = 0; i < CHANNELS_MAX; i++) {
78
         for (uint8_t i = 0; i < CHANNELS_MAX; i++) {
76
             data.invert[i] = 0;
79
             data.invert[i] = 0;
77
             data.minimum[i] = CHANNEL_MINIMUM_VALUE;
80
             data.minimum[i] = CHANNEL_MINIMUM_VALUE;
79
             data.trim[i] = 0;
82
             data.trim[i] = 0;
80
         }
83
         }
81
 
84
 
85
+        // Should be correct for every device
86
+        data.invert[CHANNEL_THROTTLE] = 1;
87
+        data.invert[CHANNEL_PITCH] = 1;
88
+
82
         /*
89
         /*
83
          * Default values to match my personal setup.
90
          * Default values to match my personal setup.
84
          * Can be changed using the on-screen menu.
91
          * Can be changed using the on-screen menu.
85
          */
92
          */
86
-        data.invert[CHANNEL_THROTTLE] = 1;
87
-        data.invert[CHANNEL_PITCH] = 1;
88
         data.minimum[CHANNEL_THROTTLE] = 1010;
93
         data.minimum[CHANNEL_THROTTLE] = 1010;
89
         data.maximum[CHANNEL_THROTTLE] = 1950;
94
         data.maximum[CHANNEL_THROTTLE] = 1950;
90
         data.minimum[CHANNEL_ROLL] = 1050;
95
         data.minimum[CHANNEL_ROLL] = 1050;
103
     CPPM::instance().setFrameLength(data.frameLength);
108
     CPPM::instance().setFrameLength(data.frameLength);
104
     CPPM::instance().setPulseLength(data.pulseLength);
109
     CPPM::instance().setPulseLength(data.pulseLength);
105
     CPPM::instance().setInvert(data.inverted);
110
     CPPM::instance().setInvert(data.inverted);
111
+    CPPM::instance().setOutput(data.cppmPin);
106
     for (uint8_t i = 0; i < CHANNELS_MAX; i++) {
112
     for (uint8_t i = 0; i < CHANNELS_MAX; i++) {
107
         joyCPPM.setInvert(i, data.invert[i]);
113
         joyCPPM.setInvert(i, data.invert[i]);
108
         joyCPPM.setMinimum(i, data.minimum[i]);
114
         joyCPPM.setMinimum(i, data.minimum[i]);
113
 
119
 
114
 void eepromWrite() {
120
 void eepromWrite() {
115
     ConfigData data;
121
     ConfigData data;
122
+
116
     data.channels = CPPM::instance().getChannels();
123
     data.channels = CPPM::instance().getChannels();
117
     data.frameLength = CPPM::instance().getFrameLength();
124
     data.frameLength = CPPM::instance().getFrameLength();
118
     data.pulseLength = CPPM::instance().getPulseLength();
125
     data.pulseLength = CPPM::instance().getPulseLength();
119
     data.inverted = CPPM::instance().getInvert();
126
     data.inverted = CPPM::instance().getInvert();
127
+    data.cppmPin = CPPM::instance().getOutput();
120
     for (uint8_t i = 0; i < CHANNELS_MAX; i++) {
128
     for (uint8_t i = 0; i < CHANNELS_MAX; i++) {
121
         data.invert[i] = joyCPPM.getInvert(i);
129
         data.invert[i] = joyCPPM.getInvert(i);
122
         data.minimum[i] = joyCPPM.getMinimum(i);
130
         data.minimum[i] = joyCPPM.getMinimum(i);
123
         data.maximum[i] = joyCPPM.getMaximum(i);
131
         data.maximum[i] = joyCPPM.getMaximum(i);
124
         data.trim[i] = joyCPPM.getTrim(i);
132
         data.trim[i] = joyCPPM.getTrim(i);
125
     }
133
     }
134
+
126
     toEEPROM(data);
135
     toEEPROM(data);
127
 }
136
 }
128
 
137
 

+ 3
- 3
config.h View File

12
 
12
 
13
 #include <stdint.h>
13
 #include <stdint.h>
14
 
14
 
15
-#define CPPM_OUTPUT_PIN 4
15
+#define CPPM_OUTPUT_PIN_DEFAULT 4
16
 #define CHANNEL_MINIMUM_VALUE 1000
16
 #define CHANNEL_MINIMUM_VALUE 1000
17
 #define CHANNEL_DEFAULT_VALUE 1500
17
 #define CHANNEL_DEFAULT_VALUE 1500
18
 #define CHANNEL_MAXIMUM_VALUE 2000
18
 #define CHANNEL_MAXIMUM_VALUE 2000
32
 };
32
 };
33
 
33
 
34
 // Increase string number when struct changes!
34
 // Increase string number when struct changes!
35
-#define CONFIG_VERSION "USBCPPM-01"
35
+#define CONFIG_VERSION "USBCPPM-02"
36
 #define CONFIG_VERSION_LENGTH (sizeof(CONFIG_VERSION) - 1)
36
 #define CONFIG_VERSION_LENGTH (sizeof(CONFIG_VERSION) - 1)
37
 
37
 
38
 struct ConfigData {
38
 struct ConfigData {
39
-    uint16_t channels, frameLength, pulseLength, inverted;
39
+    uint16_t channels, frameLength, pulseLength, inverted, cppmPin;
40
     uint16_t minimum[CHANNELS_MAX];
40
     uint16_t minimum[CHANNELS_MAX];
41
     uint16_t maximum[CHANNELS_MAX];
41
     uint16_t maximum[CHANNELS_MAX];
42
     uint16_t invert[CHANNELS_MAX];
42
     uint16_t invert[CHANNELS_MAX];

+ 13
- 4
cppm.cpp View File

11
  * modify it under the terms of the GNU General Public License as
11
  * modify it under the terms of the GNU General Public License as
12
  * published by the Free Software Foundation, version 2.
12
  * published by the Free Software Foundation, version 2.
13
  */
13
  */
14
+
14
 #include <Arduino.h>
15
 #include <Arduino.h>
15
 #include "cppm.h"
16
 #include "cppm.h"
16
 
17
 
30
         data[i] = CHANNEL_DEFAULT_VALUE;
31
         data[i] = CHANNEL_DEFAULT_VALUE;
31
     }
32
     }
32
 
33
 
33
-    pinMode(CPPM_OUTPUT_PIN, OUTPUT);
34
-    digitalWrite(CPPM_OUTPUT_PIN, CPPM::inst->onState ? LOW : HIGH);
34
+    pinMode(output, OUTPUT);
35
+    digitalWrite(output, CPPM::inst->onState ? LOW : HIGH);
35
 
36
 
36
     cli();
37
     cli();
37
     TCCR1A = 0; // set entire TCCR1 register to 0
38
     TCCR1A = 0; // set entire TCCR1 register to 0
43
     sei();
44
     sei();
44
 }
45
 }
45
 
46
 
47
+void CPPM::setOutput(uint8_t i) {
48
+    digitalWrite(output, LOW);
49
+    pinMode(output, INPUT);
50
+    output = i;
51
+    pinMode(output, OUTPUT);
52
+    digitalWrite(output, CPPM::inst->onState ? LOW : HIGH);
53
+}
54
+
46
 void CPPM::copy(uint16_t* d) {
55
 void CPPM::copy(uint16_t* d) {
47
 #ifdef DEBUG_OUTPUT
56
 #ifdef DEBUG_OUTPUT
48
     DEBUG_OUTPUT.println("New CPPM data!");
57
     DEBUG_OUTPUT.println("New CPPM data!");
63
     TCNT1 = 0;
72
     TCNT1 = 0;
64
     if (CPPM::inst->state) {
73
     if (CPPM::inst->state) {
65
         // start pulse
74
         // start pulse
66
-        digitalWrite(CPPM_OUTPUT_PIN, CPPM::inst->onState ? HIGH : LOW);
75
+        digitalWrite(CPPM::inst->output, CPPM::inst->onState ? HIGH : LOW);
67
         OCR1A = CPPM::inst->pulseLength << 1;
76
         OCR1A = CPPM::inst->pulseLength << 1;
68
         CPPM::inst->state = 0;
77
         CPPM::inst->state = 0;
69
     } else {
78
     } else {
70
         // end pulse and calculate when to start the next pulse
79
         // end pulse and calculate when to start the next pulse
71
-        digitalWrite(CPPM_OUTPUT_PIN, CPPM::inst->onState ? LOW : HIGH);
80
+        digitalWrite(CPPM::inst->output, CPPM::inst->onState ? LOW : HIGH);
72
         CPPM::inst->state = 1;
81
         CPPM::inst->state = 1;
73
         if (CPPM::inst->currentChannel >= CPPM::inst->channels) {
82
         if (CPPM::inst->currentChannel >= CPPM::inst->channels) {
74
             CPPM::inst->currentChannel = 0;
83
             CPPM::inst->currentChannel = 0;

+ 6
- 1
cppm.h View File

44
     inline uint8_t getInvert() { return !onState; }
44
     inline uint8_t getInvert() { return !onState; }
45
     inline void setInvert(uint8_t i) { onState = !i; }
45
     inline void setInvert(uint8_t i) { onState = !i; }
46
 
46
 
47
+    inline uint8_t getOutput() { return output; }
48
+    void setOutput(uint8_t i);
49
+
47
   private:
50
   private:
48
     CPPM() : channels(DEFAULT_CHANNELS), frameLength(DEFAULT_FRAME_LENGTH),
51
     CPPM() : channels(DEFAULT_CHANNELS), frameLength(DEFAULT_FRAME_LENGTH),
49
-            pulseLength(DEFAULT_PULSE_LENGTH), onState(!DEFAULT_INVERT_STATE) { }
52
+            pulseLength(DEFAULT_PULSE_LENGTH), onState(!DEFAULT_INVERT_STATE),
53
+            output(CPPM_OUTPUT_PIN_DEFAULT) { }
50
     CPPM(CPPM&) { }
54
     CPPM(CPPM&) { }
51
 
55
 
52
     volatile uint16_t channels;
56
     volatile uint16_t channels;
53
     volatile uint16_t frameLength; // PPM frame length in microseconds (1ms = 1000µs)
57
     volatile uint16_t frameLength; // PPM frame length in microseconds (1ms = 1000µs)
54
     volatile uint16_t pulseLength;
58
     volatile uint16_t pulseLength;
55
     volatile uint8_t onState; // polarity of the pulses: 1 is positive, 0 is negative
59
     volatile uint8_t onState; // polarity of the pulses: 1 is positive, 0 is negative
60
+    volatile uint8_t output;
56
 
61
 
57
     volatile uint16_t data[CHANNELS_MAX];
62
     volatile uint16_t data[CHANNELS_MAX];
58
     volatile uint8_t state;
63
     volatile uint8_t state;

+ 1
- 0
events.h View File

118
         EDIT_FRAME_LENGTH,
118
         EDIT_FRAME_LENGTH,
119
         EDIT_PULSE_LENGTH,
119
         EDIT_PULSE_LENGTH,
120
         EDIT_INVERT,
120
         EDIT_INVERT,
121
+        EDIT_CPPM_PIN,
121
         EDIT_MIN_ROLL,
122
         EDIT_MIN_ROLL,
122
         EDIT_MAX_ROLL,
123
         EDIT_MAX_ROLL,
123
         EDIT_MIN_PITCH,
124
         EDIT_MIN_PITCH,

+ 9
- 1
events_buttons.cpp View File

54
     static const uint8_t mainMenuCount = sizeof(mainMenu) / sizeof(mainMenu[0]);
54
     static const uint8_t mainMenuCount = sizeof(mainMenu) / sizeof(mainMenu[0]);
55
 
55
 
56
     static const char* cppmMenu[] = {
56
     static const char* cppmMenu[] = {
57
-        "Channels", "Frame Length", "Pulse Length", "Invert", "Main Menu"
57
+        "Channels", "Frame Length", "Pulse Length", "Invert", "Output Pin", "Main Menu"
58
     };
58
     };
59
     static const uint8_t cppmMenuCount = sizeof(cppmMenu) / sizeof(cppmMenu[0]);
59
     static const uint8_t cppmMenuCount = sizeof(cppmMenu) / sizeof(cppmMenu[0]);
60
 
60
 
90
         printValue(MIN_PULSE_LENGTH, MAX_PULSE_LENGTH, cppmMenu[2]);
90
         printValue(MIN_PULSE_LENGTH, MAX_PULSE_LENGTH, cppmMenu[2]);
91
     } else if (state == EDIT_INVERT) {
91
     } else if (state == EDIT_INVERT) {
92
         printValue(0, 1, cppmMenu[3]);
92
         printValue(0, 1, cppmMenu[3]);
93
+    } else if (state == EDIT_CPPM_PIN) {
94
+        printValue(0, 13, cppmMenu[4]);
93
     } else if ((state >= EDIT_INVERT_ROLL) && (state <= EDIT_INVERT_AUX2)) {
95
     } else if ((state >= EDIT_INVERT_ROLL) && (state <= EDIT_INVERT_AUX2)) {
94
         uint8_t index = state - EDIT_INVERT_ROLL;
96
         uint8_t index = state - EDIT_INVERT_ROLL;
95
         printValue(0, 1, (String("Invert ") + axisMenu[index]).c_str());
97
         printValue(0, 1, (String("Invert ") + axisMenu[index]).c_str());
252
                 state = EDIT_INVERT;
254
                 state = EDIT_INVERT;
253
                 value = CPPM::instance().getInvert();
255
                 value = CPPM::instance().getInvert();
254
             } else if (index == 4) {
256
             } else if (index == 4) {
257
+                state = EDIT_CPPM_PIN;
258
+                value = CPPM::instance().getOutput();
259
+            } else if (index == 5) {
255
                 state = MAINMENU;
260
                 state = MAINMENU;
256
                 index = 0;
261
                 index = 0;
257
             }
262
             }
267
         } else if (state == EDIT_INVERT) {
272
         } else if (state == EDIT_INVERT) {
268
             CPPM::instance().setInvert(value);
273
             CPPM::instance().setInvert(value);
269
             state = CPPMMENU;
274
             state = CPPMMENU;
275
+        } else if (state == EDIT_CPPM_PIN) {
276
+            CPPM::instance().setOutput(value);
277
+            state = CPPMMENU;
270
         } else if (state == EDIT_INVERT_ROLL) {
278
         } else if (state == EDIT_INVERT_ROLL) {
271
             joyCPPM.setInvert(CHANNEL_ROLL, value);
279
             joyCPPM.setInvert(CHANNEL_ROLL, value);
272
             state = INVERTAXISMENU;
280
             state = INVERTAXISMENU;

Loading…
Cancel
Save