Merge branch 'master' of git.binary-kitchen.de:buddhabrot/fusion-zauberstab into master

This commit is contained in:
Thomas Schmid 2022-09-26 22:34:51 +02:00
commit 94bcfd3451
105 changed files with 40603 additions and 952 deletions

View File

@ -1,222 +0,0 @@
#include <FastLED.h>
//lichterkette: PWM 2
//mikrofon: A1
#define LED_PIN 2
#define NUM_LEDS 240
#define SAMPLING_FREQUENCY_BP 40 // number of energy chunks per second
#define SAMPLING_FREQUENCY_CONTROL 1 // check number of times per second if the current band pass is the best one
#define Q 20. // quality factor of band pass filters
#define PI 3.1415926535897932384626433832795
#define n_BP 30 //number of band pass filters
CRGB leds[NUM_LEDS];
unsigned long sampling_period_bp = 1000000L/SAMPLING_FREQUENCY_BP;
unsigned long sampling_period_control = 1000000L/SAMPLING_FREQUENCY_CONTROL;
double energy = 0;
unsigned long last_us_bp = 0L;
unsigned long last_us_control = 0L;
float a0[n_BP];
float a1[n_BP];
float a2[n_BP];
float b0[n_BP];
//float b1[n_BP];
float b2[n_BP];
float a[n_BP];
float w0[n_BP];
float yy1[n_BP];
float yy2[n_BP];
float yy3[n_BP];
float yy4[n_BP];
float yy5[n_BP];
float yy6[n_BP];
float u1[n_BP];
float u2[n_BP];
float y[n_BP];
float y_fil[n_BP];
float angle;
float angle2;
double energy_fil = 800.;
float pos_target = NUM_LEDS/2;
float pos_target_filtered = NUM_LEDS/2;
float microphone_offset = 512;
long initial_time;
int active = 15;
int candidate = 15;
int rounds = 0;
void setup() {
Serial.begin(115200);
FastLED.addLeds<WS2812, LED_PIN, RGB>(leds, NUM_LEDS);
FastLED.setMaxPowerInVoltsAndMilliamps(5, 300);
// for(int i = 0; i < NUM_LEDS; i++)
// { int brightness = get_value(i, pos_target_filtered);
// leds[i].setRGB(brightness, brightness, brightness); }
// FastLED.show();
//
// long sumsamples = 0;
// for(int j = 1; j<1000; j++)
// {
// int sample = analogRead(1);
// sumsamples += sample;
// delay(1);
// if(j==500)
// {
// sumsamples = 0;
// }
// }
// microphone_offset = sumsamples/500;
set_filter();
initial_time = micros();
}
void set_filter() {
for(int i = 0; i < n_BP; i++)
{
float frequency = 1.75+i*(2.4-1.75)/n_BP;
w0[i] = 2.*PI*frequency/SAMPLING_FREQUENCY_BP;
a[i] = sin(w0[i]/(2.*Q));
b0[i] = a[i];
//b1[i] = 0;
b2[i] = -a[i];
a0[i] = 1.+a[i];
a1[i] = -2.*cos(w0[i]);
a2[i] = 1.-a[i];
}
}
int get_value(int pos, float pos0) {
if (abs(pos0-pos) > 20) { return 0; }
else { return (40-abs(pos0-pos)*2); }
}
void loop() {
int sample = int(analogRead(1) - microphone_offset);
energy += abs(sample)*abs(sample);
if (micros() - last_us_bp > sampling_period_bp)
{
Serial.println(sample);
microphone_offset += (analogRead(1)-microphone_offset)*0.001;
//Serial.println(microphone_offset);
last_us_bp += sampling_period_bp;
energy_fil += (energy - energy_fil) * 0.01;
//Serial.println(energy);
for(int i = 0; i < n_BP; i++)
{
y[i] = (b0[i]/a0[i])*energy + 0. + (b2[i]/a0[i])*u2[i] - (a1[i]/a0[i])*yy1[i] - (a2[i]/a0[i])*yy2[i];
u2[i] = u1[i];
u1[i] = energy;
yy6[i] = yy5[i];
yy5[i] = yy4[i];
yy4[i] = yy3[i];
yy3[i] = yy2[i];
yy2[i] = yy1[i];
yy1[i] = y[i];
y_fil[i] += (abs(y[i]) - y_fil[i]) * 0.005; //linie der scheitelpunkte
}
float delays = constrain( SAMPLING_FREQUENCY_BP * 0.25/(1.75+active*(2.4-1.75)/n_BP) , 4., 6.);
float delayed = 0;
if (delays > 5)
{delayed = yy5[active]*(1-delays+5) + yy6[active]*(delays-5); }
else
{delayed = yy4[active]*(1-delays+4) + yy5[active]*(delays-4); }
angle = atan2(delayed , y[active]);
if (PI < abs(angle - angle2) && abs(angle - angle2) < 3*PI)
{ angle2 = angle + 2*PI; }
else
{ angle2 = angle; }
pos_target = map(angle2, -PI, 3*PI, -0.3*NUM_LEDS, NUM_LEDS*1.5);
if (pos_target > pos_target_filtered)
{ pos_target_filtered += (pos_target - pos_target_filtered)*0.35; }
else
{ pos_target_filtered = pos_target; }
// Serial.print(y_fil[active]);
// Serial.print(",");
// Serial.println(y[active]);
energy = 0;
for(int i = 0; i < NUM_LEDS; i++)
{
int brightness = get_value(i, pos_target_filtered);
//leds[i].setRGB(brightness, brightness, brightness);
leds[i].setHSV( 160, (rounds == 6) ? 60 : 0, brightness);
}
FastLED.show();
}
if (micros() - last_us_control > sampling_period_control)
{
last_us_control += sampling_period_control;
int argmax = -1;
float valuemax = 0;
for(int i = 0; i < n_BP; i++)
{
if(y_fil[i] > valuemax)
{
valuemax = y_fil[i];
argmax = i;
}
}
if(argmax > -1)
{
if(argmax == candidate)
{
rounds ++;
}
else
{
rounds = 0;
candidate = argmax;
}
if(rounds > 6)
{
rounds = 0;
active = candidate;
}
}
}
}

53
firmware/.vscode/settings.json vendored Normal file
View File

@ -0,0 +1,53 @@
{
"files.associations": {
"array": "cpp",
"atomic": "cpp",
"*.tcc": "cpp",
"cctype": "cpp",
"clocale": "cpp",
"cmath": "cpp",
"complex": "cpp",
"cstdarg": "cpp",
"cstddef": "cpp",
"cstdint": "cpp",
"cstdio": "cpp",
"cstdlib": "cpp",
"cstring": "cpp",
"ctime": "cpp",
"cwchar": "cpp",
"cwctype": "cpp",
"deque": "cpp",
"unordered_map": "cpp",
"unordered_set": "cpp",
"vector": "cpp",
"exception": "cpp",
"algorithm": "cpp",
"functional": "cpp",
"iterator": "cpp",
"map": "cpp",
"memory": "cpp",
"memory_resource": "cpp",
"numeric": "cpp",
"optional": "cpp",
"random": "cpp",
"string": "cpp",
"string_view": "cpp",
"system_error": "cpp",
"tuple": "cpp",
"type_traits": "cpp",
"utility": "cpp",
"fstream": "cpp",
"initializer_list": "cpp",
"iomanip": "cpp",
"iosfwd": "cpp",
"istream": "cpp",
"limits": "cpp",
"new": "cpp",
"ostream": "cpp",
"sstream": "cpp",
"stdexcept": "cpp",
"streambuf": "cpp",
"cinttypes": "cpp",
"typeinfo": "cpp"
}
}

Binary file not shown.

After

Width:  |  Height:  |  Size: 84 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 16 KiB

Binary file not shown.

BIN
firmware/assets/grayout.bin Normal file

Binary file not shown.

BIN
firmware/assets/out.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 11 KiB

View File

@ -1,10 +1,38 @@
#ifndef ZAUBERSTAB_APP_H
#define ZAUBERSTAB_APP_H
#pragma once
struct App {
void (*loop)(void);
void (*setup)(void);
void virtual init() = 0;
void virtual deinit() = 0;
void virtual loop() = 0;
};
struct App
#endif
struct BeatDetectApp : public App {
void init();
void deinit();
void loop();
};
struct VuMeterApp: public App {
void init();
void deinit();
void loop();
};
struct FFTTestApp: public App {
void init();
void deinit();
void loop();
};
struct FackelApp: public App {
void init();
void deinit();
void loop();
};
struct ImageDisplayApp: public App {
void init();
void deinit();
void loop();
};

46
firmware/include/biquad.h Normal file
View File

@ -0,0 +1,46 @@
#pragma once
template <class T>
struct Biquad
{
T b0;
T b1;
T b2;
T a1;
T a2;
T xn1;
T xn2;
T yn1;
T yn2;
Biquad() = default;
Biquad(T a1, T a2, T b0, T b1, T b2) : b0(b0), b1(b1), b2(b2), a1(a1), a2(a2){};
Biquad(T a0, T a1, T a2, T b0, T b1, T b2)
{
this->a1 = a1 / a0;
this->a2 = a2 / a0;
this->b0 = b0 / a0;
this->b1 = b1 / a0;
this->b2 = b2 / a0;
}
T update(T x)
{
T y = this->b0 * x + this->b1 * this->xn1 + this->b2 * this->xn2 - this->yn1 * this->a1 - this->yn2 * this->a2;
this->xn2 = this->xn1;
this->xn1 = x;
this->yn2 = this->yn1;
this->yn1 = y;
return y;
}
void reset() {
this->xn1 = 0.0;
this->xn2 = 0.0;
this->yn1 = 0.0;
this->yn1 = 0.0;
}
};

View File

@ -1,11 +1,20 @@
#pragma once
struct dc_cancelation_state {
float x_n1;
float y_n1;
float R;
};
template <class T>
struct DcCancelation
{
T x_n1;
T y_n1;
T R;
void dc_cancelation_init(struct dc_cancelation_state *state, float R);
void dc_cancelation_set_R(struct dc_cancelation_state *state, float R);
float dc_cancelation_update(struct dc_cancelation_state *state, float x);
DcCancelation(T R) : R(R){};
T update(T x)
{
T y = x - this->x_n1 + this->R * this->y_n1;
this->x_n1 = x;
this->y_n1 = y;
return y;
};
};

View File

@ -2,5 +2,75 @@
#include <complex>
void fft(std::complex<float> *input, std::complex<float> *output, uint32_t N);
void rfft(std::complex<float> *input, std::complex<float> *output, uint32_t N);
template <class T>
struct FFT
{
static void fft(std::complex<T> *samples, std::complex<T> *output, uint32_t N)
{
uint8_t log2n = (uint8_t)std::log2(N) + 0.5f;
std::complex<T> I(0.0, 1.0);
if (N == 1)
{
output[0] = samples[0];
return;
}
// shuffle array
for (int i = 0; i < N; i++)
{
output[i] = samples[FFT::bitReverse(i, log2n)];
}
for (int s = 1; s <= log2n; s++)
{
uint32_t m = 1 << s; // 2^s
std::complex<T> wm = std::exp(-2.0f * (T)M_PI * I / (std::complex<T>)m);
for (int k = 0; k < N; k += m)
{
std::complex<T> w = 1.f;
for (int j = 0; j < m / 2; j++)
{
std::complex<T> t = w * output[k + j + m / 2];
std::complex<T> u = output[k + j];
output[k + j] = u + t;
output[k + j + m / 2] = u - t;
w = w * wm;
}
}
}
}
static void rfft(std::complex<T> *input, std::complex<T> *output, uint32_t N)
{
std::complex<T> I(0.0, 1.0);
for (int i = 0; i < N / 2; i++)
{
input[i] = input[i] + I * input[i + N / 2];
}
FFT<T>::fft(input, output, N / 2);
for (int i = 0; i < N / 2; i++)
{
output[i] = (output[i] + std::conj(output[(N / 2) - i])) / 2.;
}
for (int i = N / 2; i < N; i++)
{
output[i] = -I * (output[i] - std::conj(output[(N / 2) - i])) / 2.;
}
}
private:
static unsigned int bitReverse(unsigned int x, int log2n)
{
int n = 0;
for (int i = 0; i < log2n; i++)
{
n <<= 1;
n |= (x & 1);
x >>= 1;
}
return n;
}
};

View File

@ -1,10 +1,24 @@
#pragma once
struct pt1_state {
float y_n1;
float K;
float T;
};
template <class T>
struct Pt1
{
T y_n1;
T K;
T T1;
void pt1_init(struct pt1_state *state, float K, float T);
float pt1_update(struct pt1_state *state, float u, float dt);
/* PT1: y = y_(n-1) + (Ku - y_(n-1)) * dt/T1 */
Pt1(T K, T T1) : T1(T1), K(K){};
Pt1() = default;
T update(T u, T dt)
{
T y = this->y_n1 + (this->K * u - this->y_n1) * dt / this->T1;
this->y_n1 = y;
return y;
}
void reset() {
this->y_n1 = 0.f;
}
};

View File

@ -1,12 +1,20 @@
#pragma once
#include "Arduino.h"
#include <FastLED.h>
#include<Wire.h>
#include<ADXL345_WE.h>
#define ADXL345_I2CADDR 0x53 // 0x1D if SDO = HIGH
#define LED_PIN 12
#define NUM_LEDS 144
#define NUM_LEDS 48
#define MIC_PIN 15
extern CRGB leds[NUM_LEDS];
extern ADXL345_WE myAcc;
int zauberstab_init();
float get_sample();
void switch_app();
bool acc_has_event();

View File

@ -10,7 +10,9 @@
[env]
framework = arduino
lib_deps = fastled/FastLED @ ^3.5.0
lib_deps =
fastled/FastLED @ ^3.5.0
wollewald/ADXL345_WE @ ^2.1.4
[env:esp32doit-devkit-v1]
platform = espressif32

View File

@ -1,163 +0,0 @@
/* sound_wave
*
* By: Andrew Tuline
*
* Date: February, 2017
*
* Basic code to read from the Sparkfun INMP401 microphone, and create waves based on sampled input. This does NOT include sensitivity adjustment.
*
* My hardware setup:
*
* Arduino Nano & Addressable LED strips
* - Powered by USB power bank
* - APA102 or WS2812 data connected to pin 12.
* - APA102 clock connected to pin 11.
* - 5V on APA102 or WS2812 connected to 5V on Nano (good for short strips).
* - Gnd to Gnd on Nano.
*
*
* Sparkfun MEMS microphone
* - Vcc on microphone is connected to 3.3V on Nano.
* - AREF on Nano connected to 3.3V on Nano.
* - Mic out connected to A5.
* - Gnd to Gnd on Nano.
*
* Note: If you are using a microphone powered by the 3.3V signal, such as the Sparkfun MEMS microphone, then connect 3.3V to the AREF pin.
*
*/
//#define FASTLED_ALLOW_INTERRUPTS 0 // Used for ESP8266.
#include <FastLED.h> // FastLED library.
#include "zauberstab.h"
uint8_t squelch = 7; // Anything below this is background noise, so we'll make it '0'.
int sample; // Current sample.
float sampleAvg = 0; // Smoothed Average.
float micLev = 0; // Used to convert returned value to have '0' as minimum.
uint8_t maxVol = 11; // Reasonable value for constant volume for 'peak detector', as it won't always trigger.
bool samplePeak = 0; // Boolean flag for peak. Responding routine must reset this flag.
int sampleAgc, multAgc;
uint8_t targetAgc = 60; // This is our setPoint at 20% of max for the adjusted output.
// Fixed definitions cannot change on the fly.
#define LED_DT LED_PIN // Data pin to connect to the strip.
#define LED_CK 11 // Clock pin for WS2801 or APA102.
#define COLOR_ORDER GRB // It's GRB for WS2812 and BGR for APA102.
#define LED_TYPE WS2812 // Using APA102, WS2812, WS2801. Don't forget to modify LEDS.addLeds to suit.
struct CRGB leds[NUM_LEDS]; // Initialize our LED array.
int max_bright = 255;
CRGBPalette16 currentPalette = OceanColors_p;
CRGBPalette16 targetPalette = OceanColors_p;
TBlendType currentBlending = LINEARBLEND; // NOBLEND or LINEARBLEND
void setup() {
//analogReference(EXTERNAL); // 3.3V reference for analog input.
Serial.begin(115200); // Initialize serial port for debugging.
delay(1000); // Soft startup to ease the flow of electrons.
LEDS.addLeds<LED_TYPE, LED_DT, COLOR_ORDER>(leds, NUM_LEDS); // Use this for WS2812B
// LEDS.addLeds<LED_TYPE, LED_DT, LED_CK, COLOR_ORDER>(leds, NUM_LEDS); // Use this for WS2801 or APA102
FastLED.setBrightness(max_bright);
FastLED.setMaxPowerInVoltsAndMilliamps(5, 500); // FastLED Power management set at 5V, 500mA.
} // setup()
void getSample() {
int16_t micIn; // Current sample starts with negative values and large values, which is why it's 16 bit signed.
static long peakTime;
micIn = analogRead(MIC_PIN)>>2; // Poor man's analog Read.
micLev = ((micLev * 31) + micIn) / 32; // Smooth it out over the last 32 samples for automatic centering.
micIn -= micLev; // Let's center it to 0 now.
micIn = abs(micIn); // And get the absolute value of each sample.
sample = (micIn <= squelch) ? 0 : (sample + micIn) / 2; // Using a ternary operator, the resultant sample is either 0 or it's a bit smoothed out with the last sample.
sampleAvg = ((sampleAvg * 31) + sample) / 32; // Smooth it out over the last 32 samples.
if (sample > (sampleAvg+maxVol) && millis() > (peakTime + 50)) { // Poor man's beat detection by seeing if sample > Average + some value.
samplePeak = 1; // Then we got a peak, else we don't. Display routines need to reset the samplepeak value in case they miss the trigger.
peakTime=millis();
}
} // getSample()
void agcAvg() { // A simple averaging multiplier to automatically adjust sound sensitivity.
multAgc = (sampleAvg < 1) ? targetAgc : targetAgc / sampleAvg; // Make the multiplier so that sampleAvg * multiplier = setpoint
sampleAgc = sample * multAgc;
if (sampleAgc > 255) sampleAgc = 255;
//------------ Oscilloscope output ---------------------------
Serial.print(targetAgc); Serial.print(" ");
Serial.print(multAgc); Serial.print(" ");
Serial.print(sampleAgc); Serial.print(" ");
Serial.print(micLev); Serial.print(" ");
Serial.print(sample); Serial.println(" ");
// Serial.print(sampleAvg); Serial.print(" ");
// Serial.print(samplePeak); Serial.print(" "); samplePeak = 0;
// Serial.print(100); Serial.print(" ");
// Serial.print(0); Serial.print(" ");
// Serial.println(" ");
} // agcAvg()
void sndwave() {
leds[NUM_LEDS/2] = ColorFromPalette(currentPalette, sampleAgc, sampleAgc, currentBlending); // Put the sample into the center
for (int i = NUM_LEDS - 1; i > NUM_LEDS/2; i--) { //move to the left // Copy to the left, and let the fade do the rest.
leds[i] = leds[i - 1];
}
for (int i = 0; i < NUM_LEDS/2; i++) { // move to the right // Copy to the right, and let the fade to the rest.
leds[i] = leds[i + 1];
}
} // sndwave()
void loop() {
EVERY_N_SECONDS(5) { // Change the palette every 5 seconds.
for (int i = 0; i < 16; i++) {
targetPalette[i] = CHSV(random8(), 255, 255);
}
}
EVERY_N_MILLISECONDS(100) { // AWESOME palette blending capability once they do change.
uint8_t maxChanges = 24;
nblendPaletteTowardPalette(currentPalette, targetPalette, maxChanges);
}
EVERY_N_MILLIS_I(thistimer,20) { // For fun, let's make the animation have a variable rate.
uint8_t timeval = beatsin8(10,20,50); // Use a sinewave for the line below. Could also use peak/beat detection.
thistimer.setPeriod(timeval); // Allows you to change how often this routine runs.
fadeToBlackBy(leds, NUM_LEDS, 16); // 1 = slow, 255 = fast fade. Depending on the faderate, the LED's further away will fade out.
getSample();
agcAvg();
sndwave();
}
FastLED.show();
} // loop()

Binary file not shown.

View File

@ -0,0 +1,221 @@
#include <algorithm>
#include "app.h"
#include "biquad.h"
#include "pt1.h"
#include "zauberstab.h"
#undef NUM_LEDS
#define NUM_LEDS 48
#define SAMPLING_FREQUENCY_BP 40 // number of energy chunks per second
#define SAMPLING_FREQUENCY_CONTROL \
1 // check number of times per second if the current band pass is the best
// one
#define Q 30. // quality factor of band pass filters
#define PI 3.1415926535897932384626433832795
#define n_BP 40 // number of band pass filters
static const unsigned long sampling_period_bp = 1000000L / SAMPLING_FREQUENCY_BP;
static const unsigned long sampling_period_control = 1000000L / SAMPLING_FREQUENCY_CONTROL;
static float energy = 0;
static unsigned long last_us_bp = 0L;
static unsigned long last_us_control = 0L;
static Biquad<float> bp_filters[n_BP];
static Pt1<float> y_filter[n_BP];
static Pt1<float> pos_filter{1.f, 1.f};
static float yy1[n_BP];
static float yy2[n_BP];
static float yy3[n_BP];
static float yy4[n_BP];
static float yy5[n_BP];
static float yy6[n_BP];
static float y[n_BP];
static float y_fil[n_BP];
static float angle;
static float angle2;
// static double energy_fil = 800.;
static float pos_target = NUM_LEDS / 2;
static float pos_target_filtered = NUM_LEDS / 2;
static long initial_time;
static int active = 15;
static int rounds = 0;
static int n_samples = 0;
static int
get_value(int pos, float pos0)
{
if (abs(pos0 - pos) > 5)
{
return 0;
}
else
{
return (30 - abs(pos0 - pos) * 6);
}
}
static void
set_filter()
{
for (int i = 0; i < n_BP; i++)
{
float frequency = 1.75 + i * (2.5 - 1.75) / n_BP;
float a, a0, a1, a2, b0, b1, b2, w0;
w0 = 2. * PI * frequency / SAMPLING_FREQUENCY_BP;
a = sin(w0 / (2. * Q));
b0 = a;
b1 = 0.f;
b2 = -a;
a0 = 1.f + a;
a1 = -2.f * cos(w0);
a2 = 1.f - a;
bp_filters[i] = Biquad<float>{a0, a1, a2, b0, b1, b2};
y_filter[i] = Pt1<float>{1.f, 1.f};
}
}
void BeatDetectApp::init()
{
set_filter();
initial_time = micros();
pos_target = NUM_LEDS / 2;
pos_target_filtered = NUM_LEDS / 2;
active = 15;
rounds = 0;
n_samples = 0;
pos_filter.reset();
for (int i = 0; i<n_BP; i++){
bp_filters[i].reset();
}
}
void BeatDetectApp::deinit()
{
}
void BeatDetectApp::loop()
{
float sample = get_sample();
energy += std::abs(sample) * std::abs(sample);
n_samples++;
if (micros() - last_us_bp > sampling_period_bp)
{
n_samples = 0;
last_us_bp = micros();
// energy_fil += (energy - energy_fil) * 0.01;
for (int i = 0; i < n_BP; i++)
{
y[i] = bp_filters[i].update(energy);
yy6[i] = yy5[i];
yy5[i] = yy4[i];
yy4[i] = yy3[i];
yy3[i] = yy2[i];
yy2[i] = yy1[i];
yy1[i] = y[i];
y_fil[i] = y_filter[i].update(std::abs(y[i]),
0.005f); // linie der scheitelpunkte
// y_fil[i] += (abs(y[i]) - y_fil[i]) * 0.005; //linie der
// scheitelpunkte
}
float delays = constrain(SAMPLING_FREQUENCY_BP * 0.25 / (1.75 + active * (2.5 - 1.75) / n_BP),
4., 6.);
float delayed = 0;
if (delays > 5)
{
delayed = yy5[active] * (1 - delays + 5) + yy6[active] * (delays - 5);
}
else
{
delayed = yy4[active] * (1 - delays + 4) + yy5[active] * (delays - 4);
}
angle = atan2(delayed, y[active]);
if (PI < abs(angle - angle2) && abs(angle - angle2) < 3 * PI)
{
angle2 = angle + 2 * PI;
}
else
{
angle2 = angle;
}
pos_target = map(angle2, -PI, 3 * PI, -0.3 * NUM_LEDS, NUM_LEDS * 1.5);
//pos_target = NUM_LEDS * (sin(angle2)+1)/2;
if (pos_target > pos_target_filtered)
{
pos_target_filtered = pos_filter.update(pos_target, 0.35f);
}
else
{
pos_filter.y_n1 = pos_target;
pos_target_filtered = pos_target;
}
energy = 0;
for (int i = 0; i < NUM_LEDS; i++)
{
leds[i].g = get_value(i, pos_target_filtered);
leds[i].r = get_value(i, pos_target_filtered + 2);
leds[i].b = get_value(i, pos_target_filtered - 2);
//leds[i].g = get_value(i, pos_target_filtered);
//leds[i].g = get_value(i, pos_target_filtered + 2);
//leds[i].b = get_value(i, pos_target_filtered - 2);
}
FastLED.show();
}
if (micros() - last_us_control > sampling_period_control)
{
last_us_control = micros();
int argmax = -1;
float valuemax = 0;
for (int i = 0; i < n_BP; i++)
{
if (y_fil[i] > valuemax)
{
valuemax = y_fil[i];
argmax = i;
}
}
if (argmax != active)
{
rounds ++;
}
if (rounds > 5)
{
active = argmax;
rounds = 0;
}
}
}

View File

@ -0,0 +1,160 @@
#include "app.h"
#include "pt1.h"
#include "zauberstab.h"
#include <cstdlib>
#include <string>
#undef NUM_LEDS
#define NUM_LEDS 48
static unsigned long last_sample_time;
static unsigned long sample_counter;
static float rms_avg;
static uint8_t energy[NUM_LEDS + 2];
static uint8_t spark_energy[NUM_LEDS + 2];
char string[128];
Pt1<float> energy_pt1{1.f, 3.f};
Pt1<float> rms_pet1{1.f, 0.05f};
CRGB palette[128];
static void hsl_to_rgb(uint32_t hue, uint32_t sat, uint32_t lum, uint8_t *r, uint8_t *g, uint8_t *b)
{
uint32_t v;
v = (lum < 128) ? (lum * (256 + sat)) >> 8 : (((lum + sat) << 8) - lum * sat) >> 8;
if (v <= 0)
{
*r = *g = *b = 0;
}
else
{
int32_t m;
int32_t sextant;
int32_t fract, vsf, mid1, mid2;
m = lum + lum - v;
hue *= 6;
sextant = hue >> 8;
fract = hue - (sextant << 8);
vsf = v * fract * (v - m) / v >> 8;
mid1 = m + vsf;
mid2 = v - vsf;
switch (sextant)
{
case 0:
*r = v;
*g = mid1;
*b = m;
break;
case 1:
*r = mid2;
*g = v;
*b = m;
break;
case 2:
*r = m;
*g = v;
*b = mid1;
break;
case 3:
*r = m;
*g = mid2;
*b = v;
break;
case 4:
*r = mid1;
*g = m;
*b = v;
break;
case 5:
*r = v;
*g = m;
*b = mid2;
break;
}
}
}
static void update_energy(uint8_t *energy, size_t s)
{
for (int i = s; i >= 2; i--)
{
energy[i] = (uint8_t)((float)(energy[i - 1] + energy[i - 2]) * 0.45f);
}
}
void FackelApp::init()
{
memset(&energy, 0, NUM_LEDS);
memset(&spark_energy, 0, NUM_LEDS);
// generate palette
for (int i = 0; i < 128; i++)
{
uint8_t r, g, b;
hsl_to_rgb(i / 5, 255, i * 2 > 128 ? 128 : i * 2, &r, &g, &b);
//hsl_to_rgb(i / 5 + 180, 255, i * 2 > 128 ? 128 : i * 2, &r, &g, &b);
g = g == 1 ? 0 : g;
b = b == 1 ? 0 : b;
palette[i].r = r;
palette[i].g = g;
palette[i].b = b;
}
}
void FackelApp::deinit()
{
}
void FackelApp::loop()
{
if (micros() - last_sample_time >= 500)
{
last_sample_time = micros();
int32_t sample = get_sample();
float in = sample * sample;
sample_counter++;
rms_avg += (in - rms_avg) / (sample_counter + 1);
}
EVERY_N_MILLISECONDS(10)
{
float rms = rms_pet1.update(rms_avg, 0.01f);
float e_f = energy_pt1.update(rms_avg, 0.01f);
//sprintf(string, "/*%f,%f*/", 1.3 * e_f, rms);
//Serial.println(string);
Serial.print(rms_avg);
Serial.print(",");
Serial.println(e_f);
if (rms > 1.15 * e_f)
{
energy[0] = 128;
energy[1] = 128;
}
else
{
energy[0] = 0;
energy[1] = 10;
}
rms_avg = 0.0f;
sample_counter = 0;
}
EVERY_N_MILLISECONDS(45)
{
update_energy(energy, NUM_LEDS+2);
for (int i = 0; i < NUM_LEDS; i++)
{
leds[NUM_LEDS-i-1] = palette[energy[i+2]];
}
FastLED.show();
}
}

View File

@ -0,0 +1,68 @@
#include "app.h"
#include "fft.h"
#include "zauberstab.h"
#define N_SAMPLES 256
static std::complex<float> samples[N_SAMPLES];
static std::complex<float> z[N_SAMPLES];
static uint32_t sample_counter = 0;
static unsigned long max_dt = 0;
static unsigned long last_sample = 0;
void FFTTestApp::init()
{
}
void FFTTestApp::deinit()
{
}
void FFTTestApp::loop()
{
if (micros() - last_sample >= 200)
{
unsigned long dt = micros() - last_sample;
last_sample = micros();
if (dt > max_dt)
{
max_dt = dt;
}
samples[sample_counter++] = get_sample();
if (sample_counter == N_SAMPLES)
{
unsigned long start = micros();
FFT<float>::fft(samples, z, N_SAMPLES);
unsigned long end = micros();
float max = 0.f;
for (int i = 0; i < N_SAMPLES / 2; i++)
{
float v = std::log10(std::abs(z[i]));
if (v > max)
{
max = v;
}
}
for (int i = 0; i < N_SAMPLES / 2; i++)
{
float v = std::log10(std::abs(z[i]));
if (v < 2.f)
{
v = 0.f;
}
uint8_t led_value = v * 20;
leds[i].setRGB(led_value, led_value, led_value);
}
sample_counter = 0;
start = micros();
FastLED.show();
end = micros();
}
}
}

Binary file not shown.

View File

@ -0,0 +1,60 @@
#include "app.h"
#include "zauberstab.h"
#define __stringify_1(x) #x
#define __stringify(x) __stringify_1(x)
extern "C"
{
#define BASE_DIR "C:/Users/Binarykitchen/Documents/tom/fusion-zauberstab/firmware/"
asm(
".macro inc_sample name, filename\n\t"
".pushsection .rodata\n\t"
"\\name:\n\t"
".incbin \"\\filename\"\n\t"
"\\name\\()_size:\n\t"
".int \\name\\()_size - \\name\n\t"
".popsection\n\t"
".endm\n\t"
);
#define incbin(label, filename) \
asm("inc_sample " __stringify(label) ", " filename "\n\t"); \
extern const unsigned char label[]; \
extern const unsigned int label##_size; \
incbin(fusion_font, BASE_DIR "assets/fairydust.bin")
}
static CRGB get_pixel(unsigned int x, unsigned int y, unsigned int sx, const unsigned char *data) {
unsigned int idx = (x + y * sx) * 3;
CRGB color{};
color.r = data[idx];
color.g = data[idx + 1];
color.b = data[idx + 2];
return color;
}
void ImageDisplayApp::init() {
}
void ImageDisplayApp::deinit() {
}
void ImageDisplayApp::loop() {
static unsigned int col = 0;
unsigned int sx = fusion_font_size/(3*48);
for (int i = 0; i< NUM_LEDS; i++) {
leds[i] = get_pixel(col, i, sx, fusion_font);
}
col++;
col = col % 218;
FastLED.show();
}

View File

@ -1,5 +1,6 @@
#include "zauberstab.h"
#include "app.h"
#include "pt1.h"
#include "zauberstab.h"
unsigned long last_sample_time;
static int sample_counter = 0;
@ -9,21 +10,22 @@ float vu_filt = 0.0f;
float vu_filt_slow = 0.0f;
float dt;
struct pt1_state vu_pt1_fast;
struct pt1_state vu_pt1_slow;
Pt1<float> vu_pt1_fast{1.f, 0.05f};
Pt1<float> vu_pt1_slow{1.f, 1.f};
void setup()
void VuMeterApp::init()
{
zauberstab_init();
Serial.begin(115200);
FastLED.setBrightness(100);
pt1_init(&vu_pt1_slow, 1, 1.f);
pt1_init(&vu_pt1_fast, 1, 0.05);
}
void loop() {
if (micros()-last_sample_time >= 500){
void VuMeterApp::deinit()
{
}
void VuMeterApp::loop()
{
if (micros() - last_sample_time >= 500)
{
last_sample_time = micros();
int32_t sample = get_sample();
float in = sample * sample;
@ -31,24 +33,27 @@ void loop() {
rms_avg += (in - rms_avg) / (sample_counter + 1);
}
EVERY_N_MILLIS(10){
EVERY_N_MILLIS(10)
{
float vu = 20 * log10f(rms_avg);
vu_filt = pt1_update(&vu_pt1_fast, vu, 0.01f);
vu_filt_slow = pt1_update(&vu_pt1_slow, vu_filt, 0.01f);
vu_filt = vu_pt1_fast.update(vu, 0.01f);
vu_filt_slow = vu_pt1_slow.update(vu_filt, 0.01f);
// Serial.println(vu);
int max_led = vu_filt;
int top_led = vu_filt_slow;
max_led = max_led > 0xFF ? 0xFF : max_led;
if (top_led < max_led){
if (top_led < max_led)
{
vu_pt1_slow.y_n1 = vu_filt;
top_led = max_led;
}
fill_solid(leds, NUM_LEDS, CRGB::Black);
for(int i = 0; i < max_led; i++) {
for (int i = 0; i < max_led; i++)
{
int idx = map(i, 0, NUM_LEDS, 0, 0xFF);
leds[i] = ColorFromPalette(RainbowColors_p, idx);
}

View File

@ -1,18 +0,0 @@
#include "dc_cancelation.h"
void dc_cancelation_init(struct dc_cancelation_state *state, float R){
state->R = R;
state->x_n1 = 0.0f;
state->y_n1 = 0.0f;
}
void dc_cancelation_set_R(struct dc_cancelation_state *state, float R) {
state->R = R;
}
float dc_cancelation_update(struct dc_cancelation_state *state, float x) {
float y = x-state->x_n1 + state->R * state->y_n1;
state->x_n1 = x;
state->y_n1 = y;
return y;
}

View File

@ -1,62 +0,0 @@
#include "fft.h"
#include "math.h"
unsigned int bitReverse(unsigned int x, int log2n)
{
int n = 0;
for (int i = 0; i < log2n; i++)
{
n <<= 1;
n |= (x & 1);
x >>= 1;
}
return n;
}
void fft(std::complex<float> *samples, std::complex<float> *output, uint32_t N)
{
uint8_t log2n = (uint8_t)std::log2(N) + 0.5f;
std::complex<float> I(0.0, 1.0);
if (N == 1) {
output[0] = samples[0];
return;
}
//shuffle array
for (int i = 0; i < N; i++) {
output[i] = samples[bitReverse(i, log2n)];
}
for(int s = 1; s <= log2n; s++) {
uint32_t m = 1 << s; // 2^s
std::complex<float> wm = std::exp(-2.0f*(float)M_PI*I/(std::complex<float>)m);
for (int k = 0; k < N; k += m) {
std::complex<float> w = 1.f;
for (int j = 0; j < m/2; j++) {
std::complex<float> t = w * output[k+j+m/2];
std::complex<float> u = output[k+j];
output[k+j] = u+t;
output[k+j+m/2] = u-t;
w = w*wm;
}
}
}
}
void rfft(std::complex<float> *input, std::complex<float> *output, uint32_t N){
std::complex<float> I(0.0, 1.0);
for(int i = 0; i< N/2; i++){
input[i] = input[i] + I * input[i + N/2];
}
fft(input, output, N/2);
for(int i = 0; i < N/2; i++){
output[i] = (output[i] + std::conj(output[(N/2) - i]))/2.f;
}
for(int i = N/2; i < N; i++) {
output[i] = -I * (output[i] - std::conj(output[(N/2) - i]))/2.f;
}
}

93
firmware/src/main.cpp Normal file
View File

@ -0,0 +1,93 @@
#include "app.h"
#include "driver/adc.h"
#include "zauberstab.h"
#include <vector>
struct BeatDetectApp beat_detect_app
{
};
struct VuMeterApp vu_meter_app
{
};
struct FFTTestApp fft_test_app
{
};
struct FackelApp fackel_app
{
};
struct ImageDisplayApp image_display {};
std::vector<std::reference_wrapper<App>> apps = {
std::ref<App>(beat_detect_app),
std::ref<App>(fackel_app),
//std::ref<App>(image_display),
};
static unsigned int current_app = 0;
static unsigned int next_app;
static bool init_successfull = false;
static bool sleep_active=false;
void switch_app() {
if (!sleep_active) {
next_app = current_app + 1;
} else {
sleep_active = false;
next_app = 0;
}
if (next_app >= apps.size()) {
next_app = 0;
// Turn off leds before going to sleep
fadeToBlackBy(leds, NUM_LEDS, 0xFF);
FastLED.show();
//configure wakeup source
esp_sleep_enable_ext0_wakeup(GPIO_NUM_4, 1);
//bedtime
sleep_active = true;
esp_deep_sleep_start();
}
next_app = next_app % apps.size();
}
void setup()
{
next_app = current_app;
if (zauberstab_init() != 0) {
return;
}
Serial.begin(115200);
init_successfull = true;
apps[current_app].get().init();
}
void loop()
{
if (!init_successfull) {
return;
}
if (acc_has_event()) {
String axes = myAcc.getActTapStatusAsString();
byte intSource = myAcc.readAndClearInterrupts();
if (myAcc.checkInterrupt(intSource, ADXL345_DOUBLE_TAP)) {
switch_app();
}
}
if (next_app != current_app)
{
apps[current_app].get().deinit();
apps[next_app].get().init();
current_app = next_app;
fadeToBlackBy(leds, NUM_LEDS, 0xFF);
}
apps[current_app].get().loop();
}

View File

@ -1,15 +0,0 @@
#include "pt1.h"
void pt1_init(struct pt1_state *state, float K, float T)
{
state->K = K;
state->T = T;
state->y_n1 = 0.0f;
}
float pt1_update(struct pt1_state *state, float u, float dt)
{
float y = state->y_n1 + (state->K * u - state->y_n1) * dt / state->T;
state->y_n1 = y;
return y;
}

View File

@ -1,21 +1,51 @@
#include "zauberstab.h"
#include "dc_cancelation.h"
struct dc_cancelation_state dc_blocker;
DcCancelation<float> dc_blocker{0.95};
CRGB leds[NUM_LEDS];
static int16_t mic_offset = 0;
static bool acc_event = false;
ADXL345_WE myAcc = ADXL345_WE(ADXL345_I2CADDR);
static uint16_t read_mic() {
static uint16_t read_mic()
{
return analogRead(MIC_PIN);
}
int zauberstab_init() {
FastLED.addLeds<WS2812, LED_PIN, RGB>(leds, NUM_LEDS);
dc_cancelation_init(&dc_blocker, 0.95);
void double_tab_int() {
acc_event = true;
}
bool acc_has_event() {
return acc_event;
}
int zauberstab_init()
{
FastLED.addLeds<WS2812, LED_PIN, GRB>(leds, NUM_LEDS);
FastLED.addLeds<WS2812, 14, GRB>(leds, NUM_LEDS);
FastLED.addLeds<WS2812, 27, GRB>(leds, NUM_LEDS);
// FastLED.setMaxPowerInVoltsAndMilliamps(5, 300);
Wire.begin();
if (!myAcc.init()){
Serial.println("Ooops, no ADXL345 detected ... Check your wiring!");
return -1;
}
myAcc.setDataRate(ADXL345_DATA_RATE_200);
myAcc.setRange(ADXL345_RANGE_16G);
myAcc.setGeneralTapParameters(ADXL345_XY0, 5.0, 50, 100.0);
myAcc.setAdditionalDoubleTapParameters(false, 250);
myAcc.setInterrupt(ADXL345_DOUBLE_TAP, INT_PIN_1);
attachInterrupt(digitalPinToInterrupt(4), double_tab_int, RISING);
return 0;
}
float get_sample() {
int32_t raw_sample = read_mic();
return dc_cancelation_update(&dc_blocker, (float) raw_sample);
float get_sample()
{
float sample = read_mic();
sample = dc_blocker.update(sample);
return sample;
}

View File

@ -1,204 +0,0 @@
#include "zauberstab.h"
#include "app.h"
#define SAMPLING_FREQUENCY_BP 40 // number of energy chunks per second
#define SAMPLING_FREQUENCY_CONTROL 1 // check number of times per second if the current band pass is the best one
#define Q 20. // quality factor of band pass filters
#define PI 3.1415926535897932384626433832795
#define n_BP 30 //number of band pass filters
static unsigned long sampling_period_bp = 1000000L / SAMPLING_FREQUENCY_BP;
static unsigned long sampling_period_control = 1000000L / SAMPLING_FREQUENCY_CONTROL;
static double energy = 0;
static unsigned long last_us_bp = 0L;
static unsigned long last_us_control = 0L;
static float a0[n_BP];
static float a1[n_BP];
static float a2[n_BP];
static float b0[n_BP];
//static float b1[n_BP];
static float b2[n_BP];
static float a[n_BP];
static float w0[n_BP];
static float yy1[n_BP];
static float yy2[n_BP];
static float yy3[n_BP];
static float yy4[n_BP];
static float yy5[n_BP];
static float yy6[n_BP];
static float u1[n_BP];
static float u2[n_BP];
static float y[n_BP];
static float y_fil[n_BP];
static float angle;
static float angle2;
static double energy_fil = 800.;
static float pos_target = NUM_LEDS / 2;
static float pos_target_filtered = NUM_LEDS / 2;
static float microphone_offset = 675;
static long initial_time;
static int active = 15;
static int candidate = 15;
static int rounds = 0;
static int get_value(int pos, float pos0)
{
if (abs(pos0 - pos) > 20)
{
return 0;
}
else
{
return (40 - abs(pos0 - pos) * 2);
}
}
static void set_filter()
{
for (int i = 0; i < n_BP; i++)
{
float frequency = 1.75 + i * (2.4 - 1.75) / n_BP;
w0[i] = 2. * PI * frequency / SAMPLING_FREQUENCY_BP;
a[i] = sin(w0[i] / (2. * Q));
b0[i] = a[i];
//b1[i] = 0;
b2[i] = -a[i];
a0[i] = 1. + a[i];
a1[i] = -2. * cos(w0[i]);
a2[i] = 1. - a[i];
}
}
static void abeat_setup()
{
zauberstab_init();
Serial.begin(115200);
set_filter();
initial_time = micros();
}
static void abeat_loop()
{
int sample = int(analogRead(MIC_PIN) - microphone_offset);
energy += abs(sample) * abs(sample);
if (micros() - last_us_bp > sampling_period_bp)
{
Serial.println(sample);
microphone_offset += (analogRead(MIC_PIN) - microphone_offset) * 0.001;
//Serial.println(microphone_offset);
last_us_bp += sampling_period_bp;
energy_fil += (energy - energy_fil) * 0.01;
//Serial.println(energy);
for (int i = 0; i < n_BP; i++)
{
y[i] = (b0[i] / a0[i]) * energy + 0. + (b2[i] / a0[i]) * u2[i] - (a1[i] / a0[i]) * yy1[i] - (a2[i] / a0[i]) * yy2[i];
u2[i] = u1[i];
u1[i] = energy;
yy6[i] = yy5[i];
yy5[i] = yy4[i];
yy4[i] = yy3[i];
yy3[i] = yy2[i];
yy2[i] = yy1[i];
yy1[i] = y[i];
y_fil[i] += (abs(y[i]) - y_fil[i]) * 0.005; //linie der scheitelpunkte
}
float delays = constrain(SAMPLING_FREQUENCY_BP * 0.25 / (1.75 + active * (2.4 - 1.75) / n_BP), 4., 6.);
float delayed = 0;
if (delays > 5)
{
delayed = yy5[active] * (1 - delays + 5) + yy6[active] * (delays - 5);
}
else
{
delayed = yy4[active] * (1 - delays + 4) + yy5[active] * (delays - 4);
}
angle = atan2(delayed, y[active]);
if (PI < abs(angle - angle2) && abs(angle - angle2) < 3 * PI)
{
angle2 = angle + 2 * PI;
}
else
{
angle2 = angle;
}
pos_target = map(angle2, -PI, 3 * PI, -0.3 * NUM_LEDS, NUM_LEDS * 1.5);
if (pos_target > pos_target_filtered)
{
pos_target_filtered += (pos_target - pos_target_filtered) * 0.35;
}
else
{
pos_target_filtered = pos_target;
}
// Serial.print(y_fil[active]);
// Serial.print(",");
// Serial.println(y[active]);
energy = 0;
for (int i = 0; i < NUM_LEDS; i++)
{
int brightness = get_value(i, pos_target_filtered);
//leds[i].setRGB(brightness, brightness, brightness);
//leds[i].setHSV(160, (rounds == 6) ? 0xFF : 0, brightness);
leds[i] = CRGB::White;
}
FastLED.show();
}
if (micros() - last_us_control > sampling_period_control)
{
last_us_control += sampling_period_control;
int argmax = -1;
float valuemax = 0;
for (int i = 0; i < n_BP; i++)
{
if (y_fil[i] > valuemax)
{
valuemax = y_fil[i];
argmax = i;
}
}
if (argmax > -1)
{
if (argmax == candidate)
{
rounds++;
}
else
{
rounds = 0;
candidate = argmax;
}
if (rounds > 6)
{
rounds = 0;
active = candidate;
}
}
}
}

View File

@ -1,203 +0,0 @@
#include "zauberstab.h"
#define SAMPLING_FREQUENCY_BP 40 // number of energy chunks per second
#define SAMPLING_FREQUENCY_CONTROL 1 // check number of times per second if the current band pass is the best one
#define Q 20. // quality factor of band pass filters
#define PI 3.1415926535897932384626433832795
#define n_BP 30 //number of band pass filters
static unsigned long sampling_period_bp = 1000000L / SAMPLING_FREQUENCY_BP;
static unsigned long sampling_period_control = 1000000L / SAMPLING_FREQUENCY_CONTROL;
static double energy = 0;
static unsigned long last_us_bp = 0L;
static unsigned long last_us_control = 0L;
static float a0[n_BP];
static float a1[n_BP];
static float a2[n_BP];
static float b0[n_BP];
//static float b1[n_BP];
static float b2[n_BP];
static float a[n_BP];
static float w0[n_BP];
static float yy1[n_BP];
static float yy2[n_BP];
static float yy3[n_BP];
static float yy4[n_BP];
static float yy5[n_BP];
static float yy6[n_BP];
static float u1[n_BP];
static float u2[n_BP];
static float y[n_BP];
static float y_fil[n_BP];
static float angle;
static float angle2;
static double energy_fil = 800.;
static float pos_target = NUM_LEDS / 2;
static float pos_target_filtered = NUM_LEDS / 2;
static float microphone_offset = 675;
static long initial_time;
static int active = 15;
static int candidate = 15;
static int rounds = 0;
static int get_value(int pos, float pos0)
{
if (abs(pos0 - pos) > 20)
{
return 0;
}
else
{
return (40 - abs(pos0 - pos) * 2);
}
}
static void set_filter()
{
for (int i = 0; i < n_BP; i++)
{
float frequency = 1.75 + i * (2.4 - 1.75) / n_BP;
w0[i] = 2. * PI * frequency / SAMPLING_FREQUENCY_BP;
a[i] = sin(w0[i] / (2. * Q));
b0[i] = a[i];
//b1[i] = 0;
b2[i] = -a[i];
a0[i] = 1. + a[i];
a1[i] = -2. * cos(w0[i]);
a2[i] = 1. - a[i];
}
}
void setup()
{
zauberstab_init();
Serial.begin(115200);
set_filter();
initial_time = micros();
}
void loop()
{
int sample = int(analogRead(MIC_PIN) - microphone_offset);
energy += abs(sample) * abs(sample);
if (micros() - last_us_bp > sampling_period_bp)
{
Serial.println(sample);
microphone_offset += (analogRead(MIC_PIN) - microphone_offset) * 0.001;
//Serial.println(microphone_offset);
last_us_bp += sampling_period_bp;
energy_fil += (energy - energy_fil) * 0.01;
//Serial.println(energy);
for (int i = 0; i < n_BP; i++)
{
y[i] = (b0[i] / a0[i]) * energy + 0. + (b2[i] / a0[i]) * u2[i] - (a1[i] / a0[i]) * yy1[i] - (a2[i] / a0[i]) * yy2[i];
u2[i] = u1[i];
u1[i] = energy;
yy6[i] = yy5[i];
yy5[i] = yy4[i];
yy4[i] = yy3[i];
yy3[i] = yy2[i];
yy2[i] = yy1[i];
yy1[i] = y[i];
y_fil[i] += (abs(y[i]) - y_fil[i]) * 0.005; //linie der scheitelpunkte
}
float delays = constrain(SAMPLING_FREQUENCY_BP * 0.25 / (1.75 + active * (2.4 - 1.75) / n_BP), 4., 6.);
float delayed = 0;
if (delays > 5)
{
delayed = yy5[active] * (1 - delays + 5) + yy6[active] * (delays - 5);
}
else
{
delayed = yy4[active] * (1 - delays + 4) + yy5[active] * (delays - 4);
}
angle = atan2(delayed, y[active]);
if (PI < abs(angle - angle2) && abs(angle - angle2) < 3 * PI)
{
angle2 = angle + 2 * PI;
}
else
{
angle2 = angle;
}
pos_target = map(angle2, -PI, 3 * PI, -0.3 * NUM_LEDS, NUM_LEDS * 1.5);
if (pos_target > pos_target_filtered)
{
pos_target_filtered += (pos_target - pos_target_filtered) * 0.35;
}
else
{
pos_target_filtered = pos_target;
}
// Serial.print(y_fil[active]);
// Serial.print(",");
// Serial.println(y[active]);
energy = 0;
for (int i = 0; i < NUM_LEDS; i++)
{
int brightness = get_value(i, pos_target_filtered);
if (brightness >= 1) {
brightness = 10;
}
//leds[i].setRGB(brightness, brightness, brightness);
leds[i].setHSV(160, (rounds == 6) ? 0xFF : 0, brightness);
}
FastLED.show();
}
if (micros() - last_us_control > sampling_period_control)
{
last_us_control += sampling_period_control;
int argmax = -1;
float valuemax = 0;
for (int i = 0; i < n_BP; i++)
{
if (y_fil[i] > valuemax)
{
valuemax = y_fil[i];
argmax = i;
}
}
if (argmax > -1)
{
if (argmax == candidate)
{
rounds++;
}
else
{
rounds = 0;
candidate = argmax;
}
if (rounds > 6)
{
rounds = 0;
active = candidate;
}
}
}
}

View File

@ -1,9 +0,0 @@
#include "zauberstab.h"
void setup() {
zauberstab_init();
}
void loop() {
}

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

BIN
inventor/SpantA.ipt Normal file

Binary file not shown.

BIN
inventor/assembly.iam Normal file

Binary file not shown.

BIN
inventor/boden.ipt Normal file

Binary file not shown.

BIN
inventor/boden.stl Normal file

Binary file not shown.

BIN
inventor/deckel.ipt Normal file

Binary file not shown.

BIN
inventor/deckel.stl Normal file

Binary file not shown.

39492
inventor/exports/assembly.stp Normal file

File diff suppressed because it is too large Load Diff

BIN
inventor/klaue.stl Normal file

Binary file not shown.

BIN
inventor/lasercutter.dwg Normal file

Binary file not shown.

BIN
inventor/lasercutter.pdf Normal file

Binary file not shown.

Binary file not shown.

BIN
inventor/mutter-halter.stl Normal file

Binary file not shown.

BIN
inventor/platte.ipt Normal file

Binary file not shown.

BIN
inventor/ring_oben.ipt Normal file

Binary file not shown.

BIN
inventor/ring_unten.ipt Normal file

Binary file not shown.

BIN
inventor/staender.stl Normal file

Binary file not shown.

Binary file not shown.

Binary file not shown.

BIN
inventor/vase.ipt Normal file

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

20
make_artikel/3d-druck.md Normal file
View File

@ -0,0 +1,20 @@
# 3D-Druck - Vase mode mal anders
In einer idealen Welt würden wir das gesamte Ei einfach ganz normal drucken. Leider sagte der Slicer für unsere naive erste Konstruktion eine Druckzeit fast einer Woche voraus.
Die zweite und entgültige Konstruktion nutzt zwei Tricks um das 32 Zentimeter hohe Ei in etwa einem Tag drucken zu können.
Der erste Trick ist ein Umstieg auf eine 0.8mm breite Düse.
Der zweite Trick ist eine kreative Verwendung des Vasenmodus. Auf den ersten Blick scheidet eine Vase aus, da zur Befestigung der LED-stripes ein gewisses Innenleben notwendig ist.
Wir nutzen hier die Definition einer Vase aus. Der Slicer fährt auf jeder Lage sturr die äußere Kontur ab. "Außere Kontur" ist hier rein mathematisch definiert. Indem wir einen Volumenkörper von außen dünn einschlitzen, können wir also auch im Innenraum des Eis einen Tunnel für die LED-stripes erzeugen. Das ist in den Abbildungen (vase mode 1) und (vase mode 2) illustriert.
![vase mode 1](grafiken/illustrationen/vase_cad.PNG "Geometrie laut CAD")
![vase mode 2](grafiken/illustrationen/vase_sliced.PNG "Tatsächlich gedruckte Geometrie")
An Boden und Deckel ist der Vasenmodus ungeeignet, da die Überlappung aufeinanderfolgender Lagen bei hier zunehmend klein wird. Daher wird das Ei in drei Teile geteilt, die äußeren beiden drucken wir normal. Trotz dieser Aufteilung ist das verbliebene Vasenteil recht groß, ein Drucker mit mindestens 250mm Bauraumhöhe ist also Voraussetzung.

55
make_artikel/artikel.md Normal file
View File

@ -0,0 +1,55 @@
Fusion Zauberstab
=================
<!--- Vorspann --->
<!--- Artikel --->
# Motivation
# Konzept
- (Explosionzeichung Ei)
# 3D-Druck - Vase-Mode mal anders
> Info Vase-Mode
- Vor und Nachteile größere Düse
- Vase Mode (Abbildung, 2D Schnitt CAD-Modell)
- Druckeinstellungen
# Holzskelett
- Lasercutter (Bild Lasercutter)
- Verschraubung Boden und Deckel (Bild einpressen Einschlagmutter)
# Elektronik
- (Übersichtszeichnung (Fritzing))
- (Bild Elektronikschlitten)
- ESP32
- Mikrofon
- Beschleunigungssensor
- Akku
- WS2812
# Platformio
# Software-Struktur
- Verwendete Bibliotheken
- FastLED
- ADXL345 Bibliothek
- Aufbau des Projekts
- Apps
# Bedienung
- Double tap
- Verwendung von Interrupts
- ESP32 Deep Sleep
# Beaterkennung
> Info: Biquad
- (Blockdiagramm)
# Fackel
- Algorithmus Feuer
- "Seeding" mit Sound
- (Blockdiagramm)
# Praxistest
- (Fusion Bilder)
- beaterkennung funktioniert je nach musik, fackel immer

View File

@ -0,0 +1,19 @@
# Beaterkennung
Die erste von zwei Animationen besteht aus einer Welle, welche von jedem zweiten beat bis zum jeweils nächten beat von oben nach unten läuft.
Dafür muss zu jedem Zeitpunkt sowohl die Frequenz als auch die Phase des beats bekannt sein, und das auch über kürzere Störungen oder komplexere Rythmen hinweg.
Die zentrale Idee des Algorithmus ist es, Bandpassfilter mit schwacher Dämpfung als Phasenschätzer zu missbrauchen.
Hierfür wird eine ganze Reihe an Bandpässen mit unterschiedlichen Durchlassfrequenzen parallel geschaltet. Diese Durchlassfrequenzen gehören zu unterschiedlichen beat-Geschwindigkeiten. In unserem Fall von 105 bis 150bpm, weil sich hier die elektronische Tanzmusik meistens abspielt. Auf jeden dieser Bandpässe wird nun die Signalenergie gegeben. Der Bandpass, der sich daraufhin am meisten aufschwingt, hat dann offensichtlich am besten die richtige Geschwindigkeit getroffen.
Jetzt nochmal von vorne und im Detail - diesen Abschnitt gerne überspringen: Zuerst sammeln wir samples vom Mikrofon. Wir ziehen den gleitenden Durchschnitt ab, um ein Audiosignal zu erzeugen, welches um Null herum schwingt. Über jeweils ein chunk - eine Vierzigstelsekunde - summieren wir über quadrierte samples, um die Signalenergie in diesem chunk zu erhalten. Alles weitere passiert nun ebenfalls 40 mal die Sekunde. Wir geben die Signalenergie gleichzeitig auf alle Bandpässe - ebenfalls 40 an der Zahl - und schauen welcher davon sich am weitesten aufschwingt. Als relativen Amplitudenschätzer filtern wir die Absolutwerte aller Bandpassausgänge und setzen regelmäßig den Bandpass mit dem höchsten entsprechenden Wert auf aktiv. Nun haben wir das Problem, dass der Bandpass einmal pro beat schwingt, unsere gewollte Animation aber zwei beats benötigt. Wir müssen also irgendwie die Frequenz halbieren. Dafür verzögern wir das Signal um Pi/4 und schätzen mit der atan2-Funktion die Phase. Mit der bekannten Phase und einem einfachen Zustandsautomat konstruieren wir uns eine neue Phase, die nur halb so schnell steigt. Diese skalieren wir linear auf eine Sollposition des Maximums der Lichtwelle.
Wir wissen nun also zu jedem Zeitpunkt die Position des Scheitelpunktes der Lichtwelle. Die LEDs davor und dahinter werden ebenfalls angesteuert aber mit abfallender Helligkeit, so dass ein Verlauf entsteht.
Die Maxima für den roten und blauen Kanal sind dabei gegenläufig verschoben, so dass ein räumlicher Farbverlauf entsteht.
Das Ganze ist hier illustriert:
![Blockdiagramm Beaterkennung](grafiken/illustrationen/beaterkennung.PNG "Blockdiagramm Beaterkennung")

Binary file not shown.

After

Width:  |  Height:  |  Size: 693 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 767 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 546 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 618 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 892 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 107 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 68 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 100 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 201 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 783 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 18 KiB

Binary file not shown.

Binary file not shown.

After

Width:  |  Height:  |  Size: 95 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 134 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 3.6 MiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 3.9 MiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 4.4 MiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 5.1 MiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 4.3 MiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 5.1 MiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 3.9 MiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 5.1 MiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 5.1 MiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 5.0 MiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 4.0 MiB

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