Browse Source

might just work

Zoadian 10 years ago
parent
commit
0ceeeec606

+ 49 - 21
Visual Micro/.drumduino_firmware.vsarduino.h

@@ -5,51 +5,79 @@
 	        all non-arduino files created by visual micro and all visual studio project or solution files can be freely deleted and are not required to compile a sketch (do not delete your own code!).
 	        note: debugger breakpoints are stored in '.sln' or '.asln' files, knowledge of last uploaded breakpoints is stored in the upload.vmps.xml file. Both files are required to continue a previous debug session without needing to compile and upload again
 	
-	Hardware: Arduino Duemilanove or Diecimila w/ ATmega328, Platform=avr, Package=arduino
+	Hardware: Arduino Uno, Platform=avr, Package=arduino
 */
 
 #ifndef _VSARDUINO_H_
 #define _VSARDUINO_H_
 #define __AVR_ATmega328p__
 #define __AVR_ATmega328P__
-#define ARDUINO 156
+#define ARDUINO 163
 #define ARDUINO_MAIN
 #define __AVR__
 #define __avr__
 #define F_CPU 16000000L
 #define __cplusplus
+#define GCC_VERSION 40801
+#define ARDUINO_ARCH_AVR
+#define ARDUINO_AVR_UNO
 #define __inline__
 #define __asm__(x)
 #define __extension__
-#define __ATTR_PURE__
-#define __ATTR_CONST__
+//#define __ATTR_PURE__
+//#define __ATTR_CONST__
 #define __inline__
-#define __asm__ 
+//#define __asm__ 
 #define __volatile__
+#define GCC_VERSION 40801
+#define volatile(va_arg) 
 
-#define __builtin_va_list
+typedef void *__builtin_va_list;
 #define __builtin_va_start
 #define __builtin_va_end
-#define __DOXYGEN__
+//#define __DOXYGEN__
 #define __attribute__(x)
 #define NOINLINE __attribute__((noinline))
 #define prog_void
 #define PGM_VOID_P int
-            
+#define NEW_H
+/*
+#ifndef __ATTR_CONST__
+#define __ATTR_CONST__ __attribute__((__const__))
+#endif
+
+#ifndef __ATTR_MALLOC__
+#define __ATTR_MALLOC__ __attribute__((__malloc__))
+#endif
+
+#ifndef __ATTR_NORETURN__
+#define __ATTR_NORETURN__ __attribute__((__noreturn__))
+#endif
+
+#ifndef __ATTR_PURE__
+#define __ATTR_PURE__ __attribute__((__pure__))
+#endif            
+*/
 typedef unsigned char byte;
 extern "C" void __cxa_pure_virtual() {;}
 
-inline void setPrescaler(int prescaler);
-inline void setAdPin(int adPin);
-inline void setADAlignment(int align);
-inline void startADCConversion();
-inline void disableAnalogComparator();
-inline void multiplexSelectChan(uint8_t chan);
-//
-inline void output();
-//
-
-#include "C:\Program Files (x86)\Arduino\hardware\arduino\avr\cores\arduino\arduino.h"
-#include "C:\Program Files (x86)\Arduino\hardware\arduino\avr\variants\standard\pins_arduino.h" 
-#include "C:\Users\micro_000\Desktop\github\drumduino_firmware\drumduino_firmware.ino"
+
+
+#include <arduino.h>
+#include <pins_arduino.h> 
+#undef F
+#define F(string_literal) ((const PROGMEM char *)(string_literal))
+#undef cli
+#define cli()
+#define pgm_read_byte(address_short)
+#define pgm_read_word(address_short)
+#define pgm_read_word2(address_short)
+#define digitalPinToPort(P)
+#define digitalPinToBitMask(P) 
+#define digitalPinToTimer(P)
+#define analogInPinToBit(P)
+#define portOutputRegister(P)
+#define portInputRegister(P)
+#define portModeRegister(P)
+#include <drumduino_firmware.ino>
 #endif

File diff suppressed because it is too large
+ 0 - 2
Visual Micro/Compile.vmps.xml


File diff suppressed because it is too large
+ 0 - 2
Visual Micro/Configuration.Debug.vmps.xml


+ 313 - 77
drumduino_firmware.ino

@@ -1,10 +1,25 @@
-#define PORT_CNT 6
-#define CHAN_CNT 8
+#include <SoftwareSerial.h>
 
-#define MULTIPLEX_PIN_A 2
-#define MULTIPLEX_PIN_B 3
-#define MULTIPLEX_PIN_C 4
+enum DrumduinoFirmwareSettings {
+	PORT_CNT = 6,
+	CHAN_PER_PORT_CNT = 8,
+	PAD_CNT = PORT_CNT * CHAN_PER_PORT_CNT,
+	FRAME_BUFFER_SIZE = 3,
+};
+
+enum Pins {
+	PIN_MULTIPLEX_A = 2,
+	PIN_MULTIPLEX_B = 3 ,
+	PIN_MULTIPLEX_C = 4 ,
+
+	PIN_SOFTSERIAL_RX = 5,
+	PIN_SOFTSERIAL_TX = 6,
+};
 
+
+//=================================================================================
+// Set Bit and Clwear Bit Helpers
+//=================================================================================
 #ifndef cbi
 #define cbi(sfr, bit) (_SFR_BYTE(sfr) &= ~_BV(bit))
 #endif
@@ -17,37 +32,39 @@
 // Prescaler
 //=================================================================================
 // Maximum sampling frequency    // Resolution
-#define Prescaler_2   B00000000 // 16 MHz / 2 = 8 MHz            //
-#define Prescaler_4   B00000010 // 16 MHz / 4 = 4 MHz            // ~5.9
-#define Prescaler_8   B00000011 // 16 MHz / 8 = 2 MHz            // ~7.4
-#define Prescaler_16  B00000100 // 16 MHz / 16 = 1 MHz           // ~8.6
-#define Prescaler_32  B00000101 // 16 MHz / 32 = 500 kHz         // ~8.9
-#define Prescaler_64  B00000110 // 16 MHz / 64 = 250 kHz         // ~9.0
-#define Prescaler_128 B00000111 // 16 MHz / 128 = 125 kHz        // ~9.1
-
-inline void setPrescaler(int prescaler)
-{
+enum Prescaler {
+	Prescaler_2   = B00000000, // 16 MHz / 2 = 8 MHz            //
+	Prescaler_4   = B00000010, // 16 MHz / 4 = 4 MHz            // ~5.9
+	Prescaler_8   = B00000011, // 16 MHz / 8 = 2 MHz            // ~7.4
+	Prescaler_16  = B00000100, // 16 MHz / 16 = 1 MHz           // ~8.6
+	Prescaler_32  = B00000101, // 16 MHz / 32 = 500 kHz         // ~8.9
+	Prescaler_64  = B00000110, // 16 MHz / 64 = 250 kHz         // ~9.0
+	Prescaler_128 = B00000111, // 16 MHz / 128 = 125 kHz        // ~9.1
+};
+
+inline void setPrescaler(int prescaler) {
 	ADCSRA &= B11111000;
 	ADCSRA |= prescaler;
 }
 
 
 //=================================================================================
-//  Adc Pin
+//  Ad Pin
 //=================================================================================
-#define AdPin_0   B00000000
-#define AdPin_1   B00000001
-#define AdPin_2   B00000010
-#define AdPin_3   B00000011
-#define AdPin_4   B00000100
-#define AdPin_5   B00000101
-#define AdPin_6   B00000110 // Bei Atmega8 nur in der Gehäusebauform TQFP und MLF verfügbar, nicht in PDIP
-#define AdPin_7   B00000111 // Bei Atmega8 nur in der Gehäusebauform TQFP und MLF verfügbar, nicht in PDIP
-#define AdPin_Vbg B00001110 // 1.23V
-#define AdPin_GND B00001111 // 0V
+enum AdPin {
+	AdPin_0   = B00000000,
+	AdPin_1   = B00000001,
+	AdPin_2   = B00000010,
+	AdPin_3   = B00000011,
+	AdPin_4   = B00000100,
+	AdPin_5   = B00000101,
+	AdPin_6   = B00000110, // Bei Atmega8 nur in der Gehäusebauform TQFP und MLF verfügbar, nicht in PDIP
+	AdPin_7   = B00000111, // Bei Atmega8 nur in der Gehäusebauform TQFP und MLF verfügbar, nicht in PDIP
+	AdPin_Vbg = B00001110, // 1.23V
+	AdPin_GND = B00001111, // 0V
+};
 
-inline void setAdPin(int adPin)
-{
+inline void setAdPin(int adPin) {
 	ADMUX &= B11110000;
 	ADMUX |= adPin;
 }
@@ -58,62 +75,216 @@ inline void setAdPin(int adPin)
 // Das Ergebnis wird in den Registern ADCH/ADCL linksbündig ausgerichtet.
 // Die 8 höchstwertigen Bits des Ergebnisses werden in ADCH abgelegt.
 // Die verbleibenden 2 niederwertigen Bits werden im Register ADCL in den Bits 6 und 7 abgelegt.
-#define ADAlignmentLeft  B00100000
-#define ADAlignmentRight B00000000
+enum AdcAlignment {
+	ADAlignmentLeft  = B00100000,
+	ADAlignmentRight = B00000000,
+};
 
 
-inline void setADAlignment(int align)
-{
+inline void setADAlignment(int align) {
 	ADMUX &= ~B00100000;
 	ADMUX |= align;
 }
 
 //=================================================================================
-inline void startADCConversion()
-{
+inline void startADCConversion() {
 	ADCSRA |= B01000000;
 }
 
 //=================================================================================
 
-inline void disableAnalogComparator()
-{
+inline void disableAnalogComparator() {
 	ACSR = B10000000;
 }
 
-inline void multiplexSelectChan(uint8_t chan)
-{
+inline void multiplexSelectChan(uint8_t chan) {
 	PORTD = B00011100 & (chan << 2);
 }
 
-struct SysexFrame {
-	byte begin;
-	byte manufacturer;
-	unsigned long time1;
-	unsigned long time2;
-	byte values[CHAN_CNT* PORT_CNT];
-	byte end;
-
-	SysexFrame()
-		: begin(0xf0)
-		, manufacturer(42)
-		, end(0xF7)
-	{
-		memset(values, 0, sizeof(values));
+//=================================================================================
+// MIDI
+//=================================================================================
+namespace midi {
+	/// http://www.midi.org/techspecs/midimessages.php
+#if 0
+	struct SysexFrame {
+		byte begin = 0xf0;
+		byte manufacturer = 42;
+		unsigned long time1 = 0;
+		unsigned long time2 = 0;
+		byte values[PAD_CNT] = { 0 };
+		byte end = 0xF7;
+	};
+#endif
+
+	/**
+	Note Off event. 
+	This message is sent when a note is released (ended).
+	*/
+	template<typename SERIAL_IF>
+	void noteOn(SERIAL_IF& serial, int note, int velocity) {
+		serial.write(0x90);
+		serial.write(note);
+		serial.write(velocity);
 	}
-};
 
-SysexFrame _frame;
+	/**
+	Note On event. 
+	This message is sent when a note is depressed (start).
+	*/
+	template<typename SERIAL_IF>
+	void noteOff(SERIAL_IF& serial, int note, int velocity) {
+		serial.write(0x80);
+		serial.write(note);
+		serial.write(velocity);
+	}
+
+	/**
+	Polyphonic Key Pressure (Aftertouch). 
+	This message is most often sent by pressing down on the key after it "bottoms out". 
+	*/
+	template<typename SERIAL_IF>
+	void polyphonicKeyPressure(SERIAL_IF& serial, int note, int pressure) {
+		serial.write(0xA0);
+		serial.write(note);
+		serial.write(pressure);
+	}
+
+	/**
+	Control Change. 
+	This message is sent when a controller value changes. 
+	Controllers include devices such as pedals and levers. 
+	Controller numbers 120-127 are reserved as "Channel Mode Messages" (below).
+	*/
+	template<typename SERIAL_IF>
+	void controlChange(SERIAL_IF& serial, int controllerNumber, int controllerValue) {
+		serial.write(0xB0);
+		serial.write(controllerNumber);
+		serial.write(controllerValue);
+	}
+}
+
+
+
+//=================================================================================
+// 
+//=================================================================================
+struct Configuration {
+	enum Type {
+		TypeDisabled,
+		TypePiezo,
+	} type[PAD_CNT] = { TypeDisabled };
+
+	struct CurveSettings {
+		enum CurveType {
+			CurveNormal,
+			CurveExp,
+			CurveLog,
+			CurveSigma,
+			CurveFlat,
+			CurveExtra,
+		};
+
+		CurveType type = CurveNormal;
+		uint8_t value = 127;
+		int8_t offset = 0;
+		uint8_t factor = 127;
+	} curve[PAD_CNT];
+
+	uint8_t note[PAD_CNT] = { 0 };
+	uint8_t threshold[PAD_CNT] = { 25 };
+	uint8_t scanTime[PAD_CNT] = { 25 };
+	uint8_t maskTime[PAD_CNT] = { 35 };
+
+} g_configuration;
+
+
+//=================================================================================
+// 
+//=================================================================================
+struct Runtime {
+	SoftwareSerial softSerial{ PIN_SOFTSERIAL_RX, PIN_SOFTSERIAL_TX }; // RX, TX
+
+	uint8_t value[PAD_CNT][FRAME_BUFFER_SIZE];
 
+	enum State {
+		StateAwait,
+		StateScan,
+		StateMask,
+	} state[PAD_CNT] = { StateAwait };
 
+	uint8_t  trigger[PAD_CNT] = { 0 };
+	uint8_t max[PAD_CNT] = { 0 };
+	//uint64_t sum[PAD_CNT] = { 0 };
 
+	uint64_t frameCounter = 0;
+} g_runtime;
+
+
+//=================================================================================
+// 
+//=================================================================================
+inline uint8_t calcCurve(const Configuration::CurveSettings& curveSettings, uint8_t value) {
+	uint8_t ret = 0;
+
+	float x = value * 8.0;
+	float f = ((float)curveSettings.value) / 64.0; //[1;127]->[0.;2.0]
+
+	switch (curveSettings.type) {
+		//[0-1023]x[0-127]
+	case Configuration::CurveSettings::CurveNormal:
+		ret = x * f / 16.0;
+		break;
+
+	case Configuration::CurveSettings::CurveExp:
+		ret = (127.0 / (exp(2.0 * f) - 1)) * (exp(f * x / 512.0) - 1.0);
+		break; //Exp 4*(exp(x/256)-1)
+
+	case Configuration::CurveSettings::CurveLog:
+		ret = log(1.0 + (f * x / 128.0)) * (127.0 / log((8 * f) + 1));
+		break; //Log 64*log(1+x/128)
+
+	case Configuration::CurveSettings::CurveSigma:
+		ret = (127.0 / (1.0 + exp(f * (512.0 - x) / 64.0)));
+		break; //Sigma
+
+	case Configuration::CurveSettings::CurveFlat:
+		ret = (64.0 - ((8.0 / f) * log((1024 / (1 + x)) - 1)));
+		break; //Flat
+
+	case Configuration::CurveSettings::CurveExtra:
+		ret = (x + 0x20) * f / 16.0;
+
+	}
+
+	ret = ret * (curveSettings.factor / 127.0) + curveSettings.offset;
+
+	if (ret <= 0) {
+		return 0;
+	}
+
+	if (ret >= 127) {
+		return 127;    //127
+	}
+
+	return ret;
+}
+
+
+//=================================================================================
+// 
+//=================================================================================
+void setup() {
+	// generate note mapping
+	for(uint8_t pad = 0; pad < PAD_CNT; ++pad) {
+		uint8_t note = 0x1E + pad;
+		g_configuration.note[pad] = note;
+	}
 
-void setup()
-{
 	// Setup MultiplexSelection Pins
-	pinMode(MULTIPLEX_PIN_A, OUTPUT);
-	pinMode(MULTIPLEX_PIN_B, OUTPUT);
-	pinMode(MULTIPLEX_PIN_C, OUTPUT);
+	pinMode(PIN_MULTIPLEX_A, OUTPUT);
+	pinMode(PIN_MULTIPLEX_B, OUTPUT);
+	pinMode(PIN_MULTIPLEX_C, OUTPUT);
 
 	// Setup ADCs
 	analogReference(DEFAULT);
@@ -125,35 +296,100 @@ void setup()
 	DIDR0 = DIDR0 | B00111111;
 
 	// Setup Serial
-	//Serial.begin(115200);
 	Serial.begin(2000000);
 	Serial.flush();
+
+	g_runtime.softSerial.begin(31250);
+	g_runtime.softSerial.flush();
 }
 
 
-inline void output()
-{
-	_frame.time1 = micros();
+//=================================================================================
+// 
+//=================================================================================
+void loop() {
+	uint64_t& frameCounter = g_runtime.frameCounter;
+	size_t curFrameIdx = frameCounter % FRAME_BUFFER_SIZE;
+	size_t lastFrameIdx = (frameCounter - 1) % FRAME_BUFFER_SIZE;
+
+	//unsigned long time1 = micros();
 
-	for(uint8_t chan = 0; chan < CHAN_CNT; ++chan) {
+	for(uint8_t chan = 0; chan < CHAN_PER_PORT_CNT; ++chan) {
 		multiplexSelectChan(chan);
 
 		for(uint8_t port = 0; port < PORT_CNT; ++port) {
-
-			int channelNumber = port * CHAN_CNT + chan;
-
-			byte& value = *(_frame.values + channelNumber);
-			
-			value = byte(analogRead(port) >> 3);
+			int pad = port * CHAN_PER_PORT_CNT + chan;
+
+			// shortcuts!
+			uint8_t& currentValue = g_runtime.value[pad][curFrameIdx];
+			const uint8_t& lastValue = g_runtime.value[pad][lastFrameIdx];
+
+			Runtime::State& state = g_runtime.state[pad];
+			uint8_t& triggerFrame = g_runtime.trigger[pad];
+			uint8_t& maxValue = g_runtime.max[pad];
+			//const uint8_t& sumValue = g_runtime.sum[pad];
+
+			const Configuration::Type& type = g_configuration.type[pad];
+			const uint8_t& threshold = g_configuration.threshold[pad];
+			const uint8_t& scanTime = g_configuration.scanTime[pad];
+			const uint8_t& maskTime = g_configuration.maskTime[pad];
+
+			// real processing
+			currentValue = uint8_t(analogRead(port) >> 3);
+
+			switch(type) {
+				case Configuration::TypePiezo: {
+					switch(state) {
+						// In this state we wait for a signal to trigger
+						default:
+						case Runtime::StateAwait: {
+STATE_AGAIN:
+
+							if(currentValue < lastValue + threshold) {
+								break;
+							}
+
+							state = Runtime::StateScan;
+							triggerFrame = frameCounter;
+							maxValue = currentValue;
+							//sumValue = currentValue;
+							//### fallthrough
+						}
+
+						// In this state we measure the value for the given time period to get the max value
+						case Runtime::StateScan: {
+							if(frameCounter < triggerFrame + scanTime) {
+								maxValue = max(currentValue, maxValue);
+								//sumValue += currentValue;
+								break;
+							}
+
+							const Configuration::CurveSettings& curve = g_configuration.curve[pad];
+							uint8_t velocity = calcCurve(curve, maxValue);
+
+							const uint8_t& note = g_configuration.note[pad];
+							midi::noteOn(g_runtime.softSerial, note, velocity);
+
+							state = Runtime::StateMask;
+							//### fallthrough
+						}
+
+						// In this state we do nothing to prevent retriggering
+						case Runtime::StateMask: {
+							if(frameCounter < triggerFrame + scanTime + maskTime) {
+								break;
+							}
+
+							state = Runtime::StateAwait;
+							goto STATE_AGAIN;
+						}
+					}
+				}
+			}
 		}
 	}
 
-	_frame.time2 = micros();
-	Serial.write((byte*)&_frame, sizeof(_frame));
-}
+	//unsigned long time2 = micros();
 
-void loop()
-{
-	//input();
-	output();
+	++frameCounter;
 }

BIN
drumduino_firmware.v12.suo


File diff suppressed because it is too large
+ 5 - 3
drumduino_firmware.vcxproj


Some files were not shown because too many files changed in this diff