Merge pull request #21 from MrDham/OpenTh-V3.1-Changes

Merge changes from Open Theremin V3 - Version 3.1 + Pitch Bend Range choice extension up to 4 ocatves.
pull/23/head V2.3
MrDham 5 years ago committed by GitHub
commit c69fc962eb
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
  1. BIN
      MIDI Open Theremin V3 HMI.bmp
  2. 56
      Open_Theremin_V3/OTPinDefs.h
  3. 5
      Open_Theremin_V3/Open_Theremin_V3.ino
  4. 104
      Open_Theremin_V3/SPImcpDAC.h
  5. 70
      Open_Theremin_V3/application.cpp
  6. 63
      Open_Theremin_V3/ihandlers.cpp
  7. 2
      Open_Theremin_V3/ihandlers.h
  8. 151
      Open_Theremin_V3/mcpDac.h
  9. BIN
      Quick guide open theremin midi.bmp
  10. 26
      README.md
  11. 22
      README.md~

Binary file not shown.

Before

Width:  |  Height:  |  Size: 587 KiB

After

Width:  |  Height:  |  Size: 601 KiB

@ -1,56 +0,0 @@
/**
* \file
* Pin definitions
*/
#ifndef WavePinDefs_h
#define WavePinDefs_h
//------------------------------------------------------------------------------
// DAC pin definitions
// LDAC may be connected to ground to save a pin
/** Set USE_MCP_DAC_LDAC to 0 if LDAC is grounded. */
#define USE_MCP_DAC_LDAC 1
// use arduino pins 2, 3, 4, 5 for DAC
// pin 2 is DAC chip select
/** Data direction register for DAC chip select. */
#define MCP_DAC_CS_DDR DDRB
#define MCP_DAC2_CS_DDR DDRB
/** Port register for DAC chip select. */
#define MCP_DAC_CS_PORT PORTB
/** Port bit number for DAC chip select. */
#define MCP_DAC_CS_BIT 2
#define MCP_DAC2_CS_BIT 1
// pin 3 is DAC serial clock
/** Data direction register for DAC clock. */
#define MCP_DAC_SCK_DDR DDRB
/** Port register for DAC clock. */
#define MCP_DAC_SCK_PORT PORTB
/** Port bit number for DAC clock. */
#define MCP_DAC_SCK_BIT 5
// pin 4 is DAC serial data in
/** Data direction register for DAC serial in. */
#define MCP_DAC_SDI_DDR DDRB
/** Port register for DAC clock. */
#define MCP_DAC_SDI_PORT PORTB
/** Port bit number for DAC clock. */
#define MCP_DAC_SDI_BIT 3
// pin 5 is LDAC if used
#if USE_MCP_DAC_LDAC
/** Data direction register for Latch DAC Input. */
#define MCP_DAC_LDAC_DDR DDRD
/** Port register for Latch DAC Input. */
#define MCP_DAC_LDAC_PORT PORTD
/** Port bit number for Latch DAC Input. */
#define MCP_DAC_LDAC_BIT 7
#endif // USE_MCP_DAC_LDAC
#endif // WavePinDefs_h

@ -2,6 +2,8 @@
* Open Theremin V3 with MIDI interface control software for Arduino UNO * Open Theremin V3 with MIDI interface control software for Arduino UNO
* Based on Open Theremin V3 version 3.0 Copyright (C) 2010-2016 by Urs Gaudenz * Based on Open Theremin V3 version 3.0 Copyright (C) 2010-2016 by Urs Gaudenz
* *
* Also integrate changes from Open Theremin V3 Version 3.1 Copyright (C) 2010-2020 by Urs Gaudenz
*
* *
* Open Theremin V3 with MIDI interface control software is free software: * Open Theremin V3 with MIDI interface control software is free software:
* you can redistribute it and/or modify it under the terms of * you can redistribute it and/or modify it under the terms of
@ -19,9 +21,10 @@
* the Open Theremin V3 with MIDI interface control software. * the Open Theremin V3 with MIDI interface control software.
* If not, see <http://www.gnu.org/licenses/>. * If not, see <http://www.gnu.org/licenses/>.
* *
* Urs Gaudenz also credits for their important contributions to Open Theremin V3: * Also credited for their important contributions to Open Theremin V3:
* David Harvey * David Harvey
* Michael Margolis * Michael Margolis
* "Theremingenieur" Thierry Frenkel
*/ */
/* Midi added by Vincent Dhamelincourt - September 2017. /* Midi added by Vincent Dhamelincourt - September 2017.

@ -0,0 +1,104 @@
/* Control the mcp 4921/4922 DACs with hardware SPI of the Arduino UNO
* ...without all the overhead of the Arduino SPI lib...
* Just the needed functions in a runtime optimized way by "Theremingenieur" Thierry Frenkel
* This file 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, either version 3 of the License, or
* (at your option) any later version.
*/
#ifndef SPImcpDac_h
#define SPImcpDac_h
#include <Arduino.h>
// Data direction & Port register & Bit number for DAC Latch:
#define MCP_DAC_LDAC_DDR DDRD
#define MCP_DAC_LDAC_PORT PORTD
#define MCP_DAC_LDAC_BIT 7
// Data direction & Port register & Bit number for DAC CS
#define MCP_DAC_CS_DDR DDRB
#define MCP_DAC_CS_PORT PORTB
#define MCP_DAC_CS_BIT 2
// Data direction & Port register & Bit number for DAC2 CS
#define MCP_DAC2_CS_DDR DDRB
#define MCP_DAC2_CS_PORT PORTB
#define MCP_DAC2_CS_BIT 1
// Data direction & Port registers & Bit numbers for Hardware SPI
#define HW_SPI_DDR DDRB
#define HW_SPI_SCK_BIT 5
#define HW_SPI_MISO_BIT 4 // unused in this configuration
#define HW_SPI_MOSI_BIT 3
static inline void SPImcpDACinit()
{
// initialize the latch pin:
MCP_DAC_LDAC_DDR |= _BV(MCP_DAC_LDAC_BIT);
MCP_DAC_LDAC_PORT |= _BV(MCP_DAC_LDAC_BIT);
// initialize the CS pins:
MCP_DAC_CS_DDR |= _BV(MCP_DAC_CS_BIT);
MCP_DAC_CS_PORT |= _BV(MCP_DAC_CS_BIT);
MCP_DAC2_CS_DDR |= _BV(MCP_DAC2_CS_BIT);
MCP_DAC2_CS_PORT |= _BV(MCP_DAC2_CS_BIT);
// initialize the hardware SPI pins:
HW_SPI_DDR |= _BV(HW_SPI_SCK_BIT);
HW_SPI_DDR |= _BV(HW_SPI_MOSI_BIT);
// initialize the hardware SPI registers
SPCR = _BV(SPE) | _BV(MSTR); // no interrupt, SPI enable, MSB first, SPI master, SPI mode 0, clock = f_osc/4 (maximum)
SPSR = _BV(SPI2X); // double the SPI clock, ideally we get 8 MHz, so that a 16bit word goes out in 3.5us (5.6us when called from an interrupt) including CS asserting/deasserting
}
static inline void SPImcpDACtransmit(uint16_t data)
{
// Send highbyte and wait for complete
SPDR = highByte(data);
asm("nop");
while (!(SPSR & _BV(SPIF)))
;
// Send lowbyte and wait for complete
SPDR = lowByte(data);
asm("nop");
while (!(SPSR & _BV(SPIF)))
;
}
static inline void SPImcpDAClatch()
{
MCP_DAC_LDAC_PORT &= ~_BV(MCP_DAC_LDAC_BIT);
MCP_DAC_LDAC_PORT |= _BV(MCP_DAC_LDAC_BIT);
}
static inline void SPImcpDACsend(uint16_t data)
{
MCP_DAC_CS_PORT &= ~_BV(MCP_DAC_CS_BIT);
// Sanitize input data and add DAC config MSBs
data &= 0x0FFF;
data |= 0x7000;
SPImcpDACtransmit(data);
MCP_DAC_CS_PORT |= _BV(MCP_DAC_CS_BIT);
// Do not latch immpediately, let's do it at the very beginning of the next interrupt to get consistent timing
}
static inline void SPImcpDAC2Asend(uint16_t data)
{
MCP_DAC2_CS_PORT &= ~_BV(MCP_DAC2_CS_BIT);
// Sanitize input data and add DAC config MSBs
data &= 0x0FFF;
data |= 0x7000;
SPImcpDACtransmit(data);
MCP_DAC2_CS_PORT |= _BV(MCP_DAC2_CS_BIT);
SPImcpDAClatch();
}
static inline void SPImcpDAC2Bsend(uint16_t data)
{
MCP_DAC2_CS_PORT &= ~_BV(MCP_DAC2_CS_BIT);
// Sanitize input data and add DAC config MSBs
data &= 0x0FFF;
data |= 0xF000;
SPImcpDACtransmit(data);
MCP_DAC2_CS_PORT |= _BV(MCP_DAC2_CS_BIT);
SPImcpDAClatch();
}
#endif

@ -3,7 +3,7 @@
#include "application.h" #include "application.h"
#include "hw.h" #include "hw.h"
#include "mcpDac.h" #include "SPImcpDAC.h"
#include "ihandlers.h" #include "ihandlers.h"
#include "timer.h" #include "timer.h"
#include "EEPROM.h" #include "EEPROM.h"
@ -32,6 +32,7 @@ static uint8_t old_midi_loop_cc_val =0;
static uint8_t midi_velocity = 0; static uint8_t midi_velocity = 0;
static uint8_t loop_hand_pos = 0;
static uint8_t new_midi_rod_cc_val =0; static uint8_t new_midi_rod_cc_val =0;
static uint8_t old_midi_rod_cc_val =0; static uint8_t old_midi_rod_cc_val =0;
@ -44,7 +45,7 @@ static double double_log_freq = 0;
static double midi_key_follow = 0.5; static double midi_key_follow = 0.5;
// Configuration parameters // Configuration parameters
static uint8_t registerValue = 4; static uint8_t registerValue = 2;
// wavetable selector is defined and initialized in ihandlers.cpp // wavetable selector is defined and initialized in ihandlers.cpp
static uint8_t midi_channel = 0; static uint8_t midi_channel = 0;
static uint8_t old_midi_channel = 0; static uint8_t old_midi_channel = 0;
@ -77,13 +78,13 @@ void Application::setup() {
digitalWrite(Application::LED_PIN_1, HIGH); // turn the LED off by making the voltage LOW digitalWrite(Application::LED_PIN_1, HIGH); // turn the LED off by making the voltage LOW
mcpDacInit(); SPImcpDACinit();
EEPROM.get(0,pitchDAC); EEPROM.get(0,pitchDAC);
EEPROM.get(2,volumeDAC); EEPROM.get(2,volumeDAC);
mcpDac2ASend(pitchDAC); SPImcpDAC2Asend(pitchDAC);
mcpDac2BSend(volumeDAC); SPImcpDAC2Bsend(volumeDAC);
initialiseTimer(); initialiseTimer();
@ -281,7 +282,7 @@ void Application::loop() {
// set wave frequency for each mode // set wave frequency for each mode
switch (_mode) { switch (_mode) {
case MUTE : /* NOTHING! */; break; case MUTE : /* NOTHING! */; break;
case NORMAL : setWavetableSampleAdvance((pitchCalibrationBase-pitch_v)/registerValue+2048-(pitchPotValue<<2)); break; case NORMAL : setWavetableSampleAdvance(((pitchCalibrationBase-pitch_v)+2048-(pitchPotValue<<2))>>registerValue); break;
}; };
// HW_LED2_OFF; // HW_LED2_OFF;
@ -306,7 +307,10 @@ void Application::loop() {
// vol_v = vol_v - (1 + MAX_VOLUME - (volumePotValue << 2)); // vol_v = vol_v - (1 + MAX_VOLUME - (volumePotValue << 2));
vol_v = vol_v ; vol_v = vol_v ;
vol_v = max(vol_v, 0); vol_v = max(vol_v, 0);
vScaledVolume = vol_v >> 4; loop_hand_pos = vol_v >> 4;
// Give vScaledVolume a pseudo-exponential characteristic:
vScaledVolume = loop_hand_pos * (loop_hand_pos + 2);
volumeValueAvailable = false; volumeValueAvailable = false;
} }
@ -359,7 +363,7 @@ static long pitchfn = 0;
InitialisePitchMeasurement(); InitialisePitchMeasurement();
interrupts(); interrupts();
mcpDacInit(); SPImcpDACinit();
qMeasurement = GetQMeasurement(); // Measure Arudino clock frequency qMeasurement = GetQMeasurement(); // Measure Arudino clock frequency
@ -372,24 +376,24 @@ pitchfn = q0-PitchFreqOffset; // Add offset calue to set frequency
mcpDac2BSend(1600); SPImcpDAC2Bsend(1600);
mcpDac2ASend(pitchXn0); SPImcpDAC2Asend(pitchXn0);
delay(100); delay(100);
pitchfn0 = GetPitchMeasurement(); pitchfn0 = GetPitchMeasurement();
mcpDac2ASend(pitchXn1); SPImcpDAC2Asend(pitchXn1);
delay(100); delay(100);
pitchfn1 = GetPitchMeasurement(); pitchfn1 = GetPitchMeasurement();
while(abs(pitchfn0-pitchfn1)>CalibrationTolerance){ // max allowed pitch frequency offset while(abs(pitchfn0-pitchfn1)>CalibrationTolerance){ // max allowed pitch frequency offset
mcpDac2ASend(pitchXn0); SPImcpDAC2Asend(pitchXn0);
delay(100); delay(100);
pitchfn0 = GetPitchMeasurement()-pitchfn; pitchfn0 = GetPitchMeasurement()-pitchfn;
mcpDac2ASend(pitchXn1); SPImcpDAC2Asend(pitchXn1);
delay(100); delay(100);
pitchfn1 = GetPitchMeasurement()-pitchfn; pitchfn1 = GetPitchMeasurement()-pitchfn;
@ -425,7 +429,7 @@ static long volumefn = 0;
InitialiseVolumeMeasurement(); InitialiseVolumeMeasurement();
interrupts(); interrupts();
mcpDacInit(); SPImcpDACinit();
volumeXn0 = 0; volumeXn0 = 0;
@ -436,12 +440,12 @@ volumefn = q0-VolumeFreqOffset;
mcpDac2BSend(volumeXn0); SPImcpDAC2Bsend(volumeXn0);
delay_NOP(44316);//44316=100ms delay_NOP(44316);//44316=100ms
volumefn0 = GetVolumeMeasurement(); volumefn0 = GetVolumeMeasurement();
mcpDac2BSend(volumeXn1); SPImcpDAC2Bsend(volumeXn1);
delay_NOP(44316);//44316=100ms delay_NOP(44316);//44316=100ms
volumefn1 = GetVolumeMeasurement(); volumefn1 = GetVolumeMeasurement();
@ -450,11 +454,11 @@ volumefn1 = GetVolumeMeasurement();
while(abs(volumefn0-volumefn1)>CalibrationTolerance){ while(abs(volumefn0-volumefn1)>CalibrationTolerance){
mcpDac2BSend(volumeXn0); SPImcpDAC2Bsend(volumeXn0);
delay_NOP(44316);//44316=100ms delay_NOP(44316);//44316=100ms
volumefn0 = GetVolumeMeasurement()-volumefn; volumefn0 = GetVolumeMeasurement()-volumefn;
mcpDac2BSend(volumeXn1); SPImcpDAC2Bsend(volumeXn1);
delay_NOP(44316);//44316=100ms delay_NOP(44316);//44316=100ms
volumefn1 = GetVolumeMeasurement()-volumefn; volumefn1 = GetVolumeMeasurement()-volumefn;
@ -478,7 +482,7 @@ void Application::hzToAddVal(float hz) {
} }
void Application::playNote(float hz, uint16_t milliseconds = 500, uint8_t volume = 255) { void Application::playNote(float hz, uint16_t milliseconds = 500, uint8_t volume = 255) {
vScaledVolume = volume; vScaledVolume = volume * (volume + 2);
hzToAddVal(hz); hzToAddVal(hz);
millitimer(milliseconds); millitimer(milliseconds);
vScaledVolume = 0; vScaledVolume = 0;
@ -544,7 +548,7 @@ void Application::midi_application ()
// Calculate loop antena cc value for midi // Calculate loop antena cc value for midi
new_midi_loop_cc_val = vScaledVolume >> 1; new_midi_loop_cc_val = loop_hand_pos >> 1;
new_midi_loop_cc_val = min (new_midi_loop_cc_val, 127); new_midi_loop_cc_val = min (new_midi_loop_cc_val, 127);
delta_loop_cc_val = (double)new_midi_loop_cc_val - (double)old_midi_loop_cc_val; delta_loop_cc_val = (double)new_midi_loop_cc_val - (double)old_midi_loop_cc_val;
@ -797,7 +801,19 @@ void Application::set_parameters ()
{ {
case 0: case 0:
// Transpose // Transpose
registerValue=4-(data_pot_value>>8); switch (data_pot_value >> 8)
{
case 0:
registerValue=3; // -1 Octave
break;
case 1:
case 2:
registerValue=2; // Center
break;
default:
registerValue=1; // +1 Octave
break;
}
break; break;
case 1: case 1:
@ -850,20 +866,26 @@ void Application::set_parameters ()
midi_bend_range = 1; midi_bend_range = 1;
break; break;
case 1: case 1:
case 2:
midi_bend_range = 2; midi_bend_range = 2;
break; break;
case 2:
midi_bend_range = 4;
break;
case 3: case 3:
midi_bend_range = 5;
break;
case 4: case 4:
midi_bend_range = 7; midi_bend_range = 7;
break; break;
case 5: case 5:
case 6:
midi_bend_range = 12; midi_bend_range = 12;
break; break;
default: case 6:
midi_bend_range = 24; midi_bend_range = 24;
break; break;
default:
midi_bend_range = 48;
break;
} }
break; break;

@ -1,7 +1,7 @@
#include "Arduino.h" #include "Arduino.h"
#include "ihandlers.h" #include "ihandlers.h"
#include "mcpDac.h" #include "SPImcpDAC.h"
#include "timer.h" #include "timer.h"
#include "build.h" #include "build.h"
@ -15,7 +15,7 @@
#include "theremin_sintable7.c" #include "theremin_sintable7.c"
#include "theremin_sintable8.c" #include "theremin_sintable8.c"
const int16_t* const wavetables[] PROGMEM = { const int16_t* const wavetables[] = { //Fixed following a suggestion by Michael Freitas, does not need to be in PROGMEM
sine_table, sine_table,
sine_table2, sine_table2,
sine_table3, sine_table3,
@ -26,12 +26,12 @@ const int16_t* const wavetables[] PROGMEM = {
sine_table8 sine_table8
}; };
static const uint32_t MCP_DAC_BASE = 2047; static const uint32_t MCP_DAC_BASE = 2048;
#define INT0_STATE (PIND & (1<<PORTD2)) #define INT0_STATE (PIND & (1<<PORTD2))
#define PC_STATE (PINB & (1<<PORTB0)) #define PC_STATE (PINB & (1<<PORTB0))
volatile uint8_t vScaledVolume = 0; volatile uint16_t vScaledVolume = 0;
volatile uint16_t vPointerIncrement = 0; volatile uint16_t vPointerIncrement = 0;
volatile uint16_t pitch = 0; // Pitch value volatile uint16_t pitch = 0; // Pitch value
@ -97,69 +97,38 @@ void ihInitialiseVolumeMeasurement() //Measurement of variable frequency oscilla
} }
/* 16 bit by 8 bit multiplication */
static inline uint32_t mul_16_8(uint16_t a, uint8_t b)
{
uint32_t product;
asm (
"mul %A1, %2\n\t"
"movw %A0, r0\n\t"
"clr %C0\n\t"
"clr %D0\n\t"
"mul %B1, %2\n\t"
"add %B0, r0\n\t"
"adc %C0, r1\n\t"
"clr r1"
:
"=&r" (product)
:
"r" (a), "r" (b));
return product;
}
/* Externaly generated 31250 Hz Interrupt for WAVE generator (32us) */ /* Externaly generated 31250 Hz Interrupt for WAVE generator (32us) */
ISR (INT1_vect) { ISR (INT1_vect) {
// Interrupt takes up a total of max 25 us // Interrupt takes up normally 14us but can take up to 22us when interrupted by another interrupt.
// Latch previously written DAC value:
SPImcpDAClatch();
disableInt1(); // Disable External Interrupt INT1 to avoid recursive interrupts disableInt1(); // Disable External Interrupt INT1 to avoid recursive interrupts
// Enable Interrupts to allow counter 1 interrupts // Enable Interrupts to allow counter 1 interrupts
interrupts(); interrupts();
int16_t waveSample; int16_t waveSample;
uint32_t scaledSample; uint32_t scaledSample=0;
uint16_t offset = (uint16_t)(pointer>>6) & 0x3ff; uint16_t offset = (uint16_t)(pointer>>6) & 0x3ff;
#if CV_ENABLED // Generator for CV output #if CV_ENABLED // Generator for CV output
vPointerIncrement = min(vPointerIncrement, 4095); vPointerIncrement = min(vPointerIncrement, 4095);
mcpDacSend(vPointerIncrement); //Send result to Digital to Analogue Converter (audio out) (9.6 us) SPImcpDACsend(vPointerIncrement); //Send result to Digital to Analogue Converter (audio out) (5.5 us)
#else //Play sound #else //Play sound
// Read next wave table value (3.0us) // Read next wave table value
// The slightly odd tactic here is to provide compile-time expressions for the wavetable waveSample = (int16_t)pgm_read_word_near(wavetables[vWavetableSelector] + offset);
// positions. Making addr1 the index into the wavtables array breaks the time limit for
// the interrupt handler scaledSample = ((int32_t)waveSample * (uint32_t)vScaledVolume) >> 16; // The compiler optimizes this better than any assembly written by hand !!!
switch (vWavetableSelector) {
case 1: waveSample = (int16_t) pgm_read_word_near(wavetables[1] + offset); break;
case 2: waveSample = (int16_t) pgm_read_word_near(wavetables[2] + offset); break;
case 3: waveSample = (int16_t) pgm_read_word_near(wavetables[3] + offset); break;
case 4: waveSample = (int16_t) pgm_read_word_near(wavetables[4] + offset); break;
case 5: waveSample = (int16_t) pgm_read_word_near(wavetables[5] + offset); break;
case 6: waveSample = (int16_t) pgm_read_word_near(wavetables[6] + offset); break;
case 7: waveSample = (int16_t) pgm_read_word_near(wavetables[7] + offset); break;
default: waveSample = (int16_t) pgm_read_word_near(wavetables[0] + offset); break;
};
if (waveSample > 0) { // multiply 16 bit wave number by 8 bit volume value (11.2us / 5.4us)
scaledSample = MCP_DAC_BASE + (mul_16_8(waveSample, vScaledVolume) >> 8);
} else {
scaledSample = MCP_DAC_BASE - (mul_16_8(-waveSample, vScaledVolume) >> 8);
}
mcpDacSend(scaledSample); //Send result to Digital to Analogue Converter (audio out) (9.6 us) SPImcpDACsend(scaledSample + MCP_DAC_BASE); //Send result to Digital to Analogue Converter (audio out) (5.5 us)
pointer = pointer + vPointerIncrement; // increment table pointer (ca. 2us) pointer += vPointerIncrement; // increment table pointer
#endif //CV play sound #endif //CV play sound
incrementTimer(); // update 32us timer incrementTimer(); // update 32us timer

@ -3,7 +3,7 @@
extern volatile uint16_t pitch; // Pitch value extern volatile uint16_t pitch; // Pitch value
extern volatile uint16_t vol; // Volume value extern volatile uint16_t vol; // Volume value
extern volatile uint8_t vScaledVolume; // Volume byte extern volatile uint16_t vScaledVolume; // Volume byte
extern volatile uint16_t pitch_counter; // Pitch counter extern volatile uint16_t pitch_counter; // Pitch counter
extern volatile uint16_t pitch_counter_l; // Last value of pitch counter extern volatile uint16_t pitch_counter_l; // Last value of pitch counter

@ -1,151 +0,0 @@
/* Arduino WaveHC Library
* Copyright (C) 2009 by William Greiman
*
* This file is part of the Arduino WaveHC Library
*
* This Library 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, either version 3 of the License, or
* (at your option) any later version.
*
* This Library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with the Arduino WaveHC Library. If not, see
* <http://www.gnu.org/licenses/>.
*/
/**
* Macros and inline functions for MCP4921 DAC
*/
#ifndef mcpDac_h
#define mcpDac_h
#include <avr/io.h>
#include "OTPinDefs.h"
//------------------------------------------------------------------------------
#define mcpDacCsLow() MCP_DAC_CS_PORT &= ~_BV(MCP_DAC_CS_BIT)
#define mcpDacCsHigh() MCP_DAC_CS_PORT |= _BV(MCP_DAC_CS_BIT)
#define mcpDac2CsLow() MCP_DAC_CS_PORT &= ~_BV(MCP_DAC2_CS_BIT)
#define mcpDac2CsHigh() MCP_DAC_CS_PORT |= _BV(MCP_DAC2_CS_BIT)
#define mcpDacSckLow() MCP_DAC_SCK_PORT &= ~_BV(MCP_DAC_SCK_BIT)
#define mcpDacSckHigh() MCP_DAC_SCK_PORT |= _BV(MCP_DAC_SCK_BIT)
#define mcpDacSckPulse() {mcpDacSckHigh();mcpDacSckLow();}
#define mcpDacSdiLow() MCP_DAC_SDI_PORT &= ~_BV(MCP_DAC_SDI_BIT)
#define mcpDacSdiHigh() MCP_DAC_SDI_PORT |= _BV(MCP_DAC_SDI_BIT)
#define mcpDacSdiSet(v) if(v){mcpDacSdiHigh();}else{mcpDacSdiLow();}
// send bit b of d
#define mcpDacSendBit(d, b) {mcpDacSdiSet(d&_BV(b));mcpDacSckPulse();}
//------------------------------------------------------------------------------
// init dac I/O ports
inline void mcpDacInit(void) {
// set all to output mode
MCP_DAC_CS_DDR |= _BV(MCP_DAC_CS_BIT);
MCP_DAC2_CS_DDR |= _BV(MCP_DAC2_CS_BIT);
MCP_DAC_SCK_DDR |= _BV(MCP_DAC_SCK_BIT);
MCP_DAC_SDI_DDR |= _BV(MCP_DAC_SDI_BIT);
// chip select high
mcpDacCsHigh();
mcpDac2CsHigh();
#if USE_MCP_DAC_LDAC
// LDAC low always - use unbuffered mode
MCP_DAC_LDAC_DDR |= _BV(MCP_DAC_LDAC_BIT);
MCP_DAC_LDAC_PORT &= ~_BV(MCP_DAC_LDAC_BIT);
#endif // USE_MCP_DAC_LDAC
}
//------------------------------------------------------------------------------
// send 12 bits to dac
// trusted compiler to optimize and it does
// csLow to csHigh takes 8 - 9 usec on a 16 MHz Arduino
inline void mcpDacSend(uint16_t data) {
mcpDacCsLow();
// send DAC config bits
mcpDacSdiLow();
mcpDacSckPulse(); // DAC A
mcpDacSdiHigh();
mcpDacSckPulse(); // buffered REF
mcpDacSckPulse(); // 1X gain
mcpDacSckPulse(); // no SHDN
// send 12 data bits
mcpDacSendBit(data, 11);
mcpDacSendBit(data, 10);
mcpDacSendBit(data, 9);
mcpDacSendBit(data, 8);
mcpDacSendBit(data, 7);
mcpDacSendBit(data, 6);
mcpDacSendBit(data, 5);
mcpDacSendBit(data, 4);
mcpDacSendBit(data, 3);
mcpDacSendBit(data, 2);
mcpDacSendBit(data, 1);
mcpDacSendBit(data, 0);
mcpDacCsHigh();
}
inline void mcpDac2ASend(uint16_t data) {
mcpDac2CsLow();
// send DAC config bits
mcpDacSdiLow();
mcpDacSckPulse(); // DAC A
mcpDacSdiHigh();
mcpDacSckPulse(); // buffered REF
mcpDacSckPulse(); // 1X gain
mcpDacSckPulse(); // no SHDN
// send 12 data bits
mcpDacSendBit(data, 11);
mcpDacSendBit(data, 10);
mcpDacSendBit(data, 9);
mcpDacSendBit(data, 8);
mcpDacSendBit(data, 7);
mcpDacSendBit(data, 6);
mcpDacSendBit(data, 5);
mcpDacSendBit(data, 4);
mcpDacSendBit(data, 3);
mcpDacSendBit(data, 2);
mcpDacSendBit(data, 1);
mcpDacSendBit(data, 0);
mcpDac2CsHigh();
}
inline void mcpDac2BSend(uint16_t data) {
mcpDac2CsLow();
// send DAC config bits
mcpDacSdiHigh();
mcpDacSckPulse(); // DAC A
mcpDacSdiHigh();
mcpDacSckPulse(); // buffered REF
mcpDacSckPulse(); // 1X gain
mcpDacSckPulse(); // no SHDN
// send 12 data bits
mcpDacSendBit(data, 11);
mcpDacSendBit(data, 10);
mcpDacSendBit(data, 9);
mcpDacSendBit(data, 8);
mcpDacSendBit(data, 7);
mcpDacSendBit(data, 6);
mcpDacSendBit(data, 5);
mcpDacSendBit(data, 4);
mcpDacSendBit(data, 3);
mcpDacSendBit(data, 2);
mcpDacSendBit(data, 1);
mcpDacSendBit(data, 0);
mcpDac2CsHigh();
}
#endif //mcpDac_h

Binary file not shown.

Before

Width:  |  Height:  |  Size: 2.6 MiB

After

Width:  |  Height:  |  Size: 2.6 MiB

@ -1,10 +1,22 @@
## Open Theremin V3 with MIDI interface control software V2.0 for Arduino UNO ## Open Theremin V3 with MIDI interface control software V2.3 for Arduino UNO
Based on Arduino UNO Software for the Open.Theremin version 3.0 Copyright (C) 2010-2016 by Urs Gaudenz Based on Arduino UNO Software for the Open.Theremin version 3.0 Copyright (C) 2010-2016 by Urs Gaudenz
https://github.com/GaudiLabs/OpenTheremin_V3 https://github.com/GaudiLabs/OpenTheremin_V3
Urs also made a very clear presentation of this MIDI feature on his website: http://www.gaudi.ch/OpenTheremin/index.php?option=com_content&view=article&id=200&Itemid=121, many thanks ! This Open Theremin V3 with MIDI version V2.3 also takes into account
Changes added in Open.Theremin version 3.1 (all by @Theremingenieur):
Fix a wavetable addressing issue (found by @miguelfreitas)
Use the Arduino's hardware SPI to control the DACS and use the Latch signal to reduce audio jitter
Improve the register switch to transpose by clean octaves and keep the tone spacing and pitch tuning consistent
Improve the volume response to give a smoother start and wider dynamics (*)
(*) This relies on a recent gcc compiler version. Make sure to compile it with the Arduino IDE >= 1.8.10
Pitch Bend Range choice is also extended (Allows 4 octaves Bend)
Urs also made a very clear presentation of the MIDI feature on his website: http://www.gaudi.ch/OpenTheremin/index.php?option=com_content&view=article&id=200&Itemid=121, many thanks !
### Don't click on the files! ### Don't click on the files!
Click on the "clone or download" Button to the right. Then unpack the archive. Click on the "clone or download" Button to the right. Then unpack the archive.
@ -63,7 +75,7 @@ Let's consider a Fade-in / Picth Variation / Fade-out sequence (I use right hand
2. Pitch variation 2. Pitch variation
When right hand moves next to PITCH ANTENNA (ROD), PITCH BEND messages are generated (if activated) to reach exact pitch as long as pitch bend range will do. Beyond, a new NOTE ON followed by a NOTE OFF for the previous note are generated if legato mode is activated. Pitch bend range can be configured (1, 2, 7, 12 or 24 semitones) to align with synth's maximum capabilities. When right hand moves next to PITCH ANTENNA (ROD), PITCH BEND messages are generated (if activated) to reach exact pitch as long as pitch bend range will do. Beyond, a new NOTE ON followed by a NOTE OFF for the previous note are generated if legato mode is activated. Pitch bend range can be configured (1, 2, 4, 5, 7, 12, 24 or 48 semitones) to align with synth's maximum capabilities.
3. Fade-Out 3. Fade-Out
@ -75,12 +87,12 @@ Let's consider a Fade-in / Picth Variation / Fade-out sequence (I use right hand
"Register" pot becomes "Selected Parameter" pot and have 8 positions. "Register" pot becomes "Selected Parameter" pot and have 8 positions.
"Timbre" pot becomes "Parameter's Value" and have a variable number of positions depending on selected parameter: "Timbre" pot becomes "Parameter's Value" and have a variable number of positions depending on selected parameter:
1. Register: 4 positions as in original Open Theremin V3 1. Register: 3 positions (-1 Octave, center, +1 Octave) as in original Open Theremin V3 (version V3.1)
2. Timbre: 8 positions as in original Open Theremin V3 2. Timbre: 8 positions as in original Open Theremin V3
3. Channel: 16 positions (channel 1 to 16) 3. Channel: 16 positions (channel 1 to 16)
4. Rod antenna mode: 4 positions 4. Rod antenna mode: 4 positions
(Legato off/Pitch Bend off, Legato off/Pitch Bend on, Legato on/Pitch Bend off, Legato on/Pitch Bend on) (Legato off/Pitch Bend off, Legato off/Pitch Bend on, Legato on/Pitch Bend off, Legato on/Pitch Bend on)
5. Pitch bend range: 5 positions (1, 2, 7, 12, 24 Semitones). 5. Pitch bend range: 8 positions (1, 2, 4, 5, 7, 12, 24, 48 Semitones).
For classical glissando and in order to have same note on audio and MIDI, use exactly same pitch bend range on your synth. For classical glissando and in order to have same note on audio and MIDI, use exactly same pitch bend range on your synth.
Maximum setting possible is recomended. Maximum setting possible is recomended.
6. Volume trigger / Velocity sensitivity (how fast moves the volume loop's hand): 128 positions (0 to 127) 6. Volume trigger / Velocity sensitivity (how fast moves the volume loop's hand): 128 positions (0 to 127)
@ -101,7 +113,7 @@ Volume trigger = 127 (Maximum) won't generate any NOTE ON. It can be used to gen
Manipulation of "Rod antenna MIDI CC" and "Loop antenna MIDI CC" is not error proof. MIDI newbies should be advised to change their value in MUTE mode. Manipulation of "Rod antenna MIDI CC" and "Loop antenna MIDI CC" is not error proof. MIDI newbies should be advised to change their value in MUTE mode.
Default configuration is: Register = Lowest Register, Timbre = 1st Waveform, Channel = MIDI Channel 1, Rod antenna mode = Legato on/Pitch Bend on, Pitch bend range = 2 Semitones, Volume trigger = 0, Rod antenna MIDI CC = None, Loop antenna MIDI CC = 7-Volume. Default configuration is: Register = Center, Timbre = 1st Waveform, Channel = MIDI Channel 1, Rod antenna mode = Legato on/Pitch Bend on, Pitch bend range = 2 Semitones, Volume trigger = 0, Rod antenna MIDI CC = None, Loop antenna MIDI CC = 7-Volume.
MUTE BUTTON: MUTE BUTTON:
@ -146,7 +158,7 @@ I'll try to answer you if I can.
### LICENSE ### LICENSE
Original project ,Open Theremin, was written by Urs Gaudenz, GaudiLabs, in 2016 Original project, Open Theremin, was written by Urs Gaudenz, GaudiLabs, in 2016
GNU license. This Project inherits this 2016 GNU License. GNU license. This Project inherits this 2016 GNU License.
Check LICENSE file for more information Check LICENSE file for more information

@ -1,22 +0,0 @@
## Open.Theremin V3 control software
Arduino UNO Software for the Open.Theremin
### Don't click on the files!
Click on the "Download ZIP" Button to the right or [Click here](https://github.com/GaudiLabs/OpenTheremin_V3/archive/master.zip)
Then unpack the archive.
### Open Source Theremin based on the Arduino Platform
Open.Theremin is an arduino shield to build the legendary music instrument invented by Leon Theremin back in 1920. The theremin is played with two antennas, one to control the pitch and one for volume. The electronic shield with two ports to connect those antennas comprises two heterodyne oscillators to measure the distance of the hand to the antenna when playing the instrument. The resulting signal is fed into the arduino. After linearization and filtering the arduino generates the instruments sound that is then played through a high quality digital analog audio converter on the board. The characteristics of the sound can be determined by a wave table on the arduino.
For more info on the open source project and on availability of ready made shield see:
http://www.gaudi.ch/OpenTheremin/
### Installation
1. Open up the Arduino IDE
2. Open the File "Open_Theremin_V3.ino"
3. Selecting the correct usb port on Tools -> Serial Port
4. Select the correct arduino board from Tools -> Board
5. Upload the code by clicking on the upload button.
Loading…
Cancel
Save