Compare commits

...

11 commits

20 changed files with 2060 additions and 184 deletions

3
.gitignore vendored Normal file
View file

@ -0,0 +1,3 @@
.clangd
compile_commands.json

3
.gitmodules vendored Normal file
View file

@ -0,0 +1,3 @@
[submodule "lib/pico-ssd1306"]
path = lib/pico-ssd1306
url = https://github.com/Harbys/pico-ssd1306

View file

@ -16,18 +16,33 @@ include_directories(include)
add_executable(clock
src/main.cpp
src/Output.cpp
src/Gate.cpp
src/Mod.cpp
src/Settings.cpp
src/DisplayHandler.cpp
src/EncoderHandler.cpp
)
# Enable USB output (useful for later printf debugging)
pico_enable_stdio_usb(clock 1)
pico_enable_stdio_uart(clock 0)
target_include_directories(clock PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}/lib)
add_subdirectory(lib/pico-ssd1306)
pico_generate_pio_header(clock ${CMAKE_CURRENT_LIST_DIR}/quadrature_encoder.pio)
# Pull in standard library and hardware abstraction
target_link_libraries(clock
pico_stdlib
hardware_pwm
hardware_gpio
hardware_pio
hardware_i2c
pico_multicore
pico_ssd1306
)
# Create the .uf2 file

71
include/DisplayHandler.h Normal file
View file

@ -0,0 +1,71 @@
// DisplayHandler.h
#ifndef DisplayHandler_h
#define DisplayHandler_h
#include <cstdint>
#include <string>
#include <array>
#include "Gate.h"
class DisplayHandler {
private:
char buffer[32];
uint8_t currentScreen;
std::string screens[7];
std::array<std::string, 19> out_pages = {
"Exit",
"Mod",
"Shape",
"Level",
"Width",
"Swing",
"Prob",
"Sticky",
"CV1 ON",
"CV1 SRC",
"CV1 TO",
"CV1 AMT",
"CV1 INV",
"CV2 ON",
"CV2 SRC",
"CV2 TO",
"CV2 AMT",
"CV2 INV",
"Mute"
};
bool onOutScreen = 0;
bool onSettingsScreen = 0;
std::array<std::string, 6> settings = {
"Save",
"Load",
"Reset",
"PPQN",
"Run",
"Exit"
};
void renderMainPage();
void renderOutPage();
void renderSettingsPage();
public:
DisplayHandler(Gate* outputs[]);
Gate** outputs;
bool updateScreen;
int8_t cursorPosition;
uint8_t mainMaxCursorPosition;
uint8_t outMaxCursorPosition;
int8_t currentOut;
bool cursorClick;
void setup();
void render();
void handleClick();
void exitSettingsScreen();
void flashMessage(std::string msg);
void moveCursor(bool dir = 1);
};
#endif

29
include/EncoderHandler.h Normal file
View file

@ -0,0 +1,29 @@
// EncoderHandler.h
#ifndef EncoderHandler_h
#define EncoderHandler_h
#include "DisplayHandler.h"
#include "pico/multicore.h"
#include <cstdint>
#include <string>
class EncoderHandler {
private:
uint sm;
uint last_count;
public:
EncoderHandler(DisplayHandler *display_handler);
DisplayHandler *display_handler;
uint8_t encoder_pos;
bool button_pressed;
uint16_t clk_last_state;
void setup();
// static void gpio_callback(uint gpio, uint32_t events);
void moveCursor(bool dir = 1);
void update();
};
#endif

View file

@ -2,35 +2,84 @@
#ifndef Gate_h
#define Gate_h
#include "Output.h"
#include "Settings.h"
#include "globals.h"
#include <cstdint>
#include <string>
class Gate {
private:
bool state;
int16_t cycle;
struct GateSettings {
uint32_t dur;
uint32_t len;
uint8_t width;
uint8_t divideMode;
uint16_t div;
uint16_t modifier;
std::string divString;
int8_t modifierSelectionIndex;
uint8_t divideMode;
uint8_t width;
uint8_t p;
uint8_t level;
uint8_t shape;
};
class Gate : public Output {
private:
float currentRandomVal;
uint32_t len;
uint64_t startTimeUs;
uint32_t pulseDurationUs;
public:
Gate(uint8_t pin);
uint8_t pin;
uint32_t dur;
Gate(uint8_t pin, uint8_t idx, uint8_t slotIdx1, uint8_t slotIdx2);
void turnOn();
void turnOff();
uint8_t modDest1;
uint8_t modDest2;
uint8_t level;
float levelMod = 0.0f;
uint8_t width;
float widthMod = 0.0f;
uint8_t p;
float pMod = 0.0f;
uint8_t swing = 50;
float swingMod = 0.0f;
void resetMods() {
levelMod = 0.0f;
pMod = 0.0f;
widthMod = 0.0f;
swingMod = 0.0f;
}
float lastOutVal = 0.0f;
uint32_t triggerCount;
uint32_t scheduledTick;
uint32_t lastTriggerTick = 0xFFFFFFFF;
WaveShape shape = SQUARE;
uint32_t startTick = 0;
uint32_t pulseWidthTicks = 0;
bool sticky = false;
int8_t modifierSelectionIndex;
uint8_t divideMode;
uint16_t modifier;
uint16_t tickInterval;
void turnOn() override;
void update();
void turnOff() override;
void calculatePulseWidth();
void setupPatches();
void writeAnalog(uint16_t val);
void setLen(uint32_t currentPeriod);
void setDiv(uint16_t newDiv, uint8_t divide = 1);
void setDiv(uint8_t modifier_selection_index);
void setWidth(uint16_t newWidth);
void setP(uint16_t prob);
bool getState();
void pack(OutputConfig &cfg);
void unpack(const OutputConfig &cfg);
};
#endif

39
include/Mod.h Normal file
View file

@ -0,0 +1,39 @@
// Mod.h
#ifndef Mod_h
#define Mod_h
#include <cstdint>
class Gate;
enum ModDest {
DEST_LEVEL = 0,
DEST_PROBABILITY = 1,
DEST_WIDTH = 2,
DEST_COUNT = 3
};
struct ModSlot {
uint8_t sourceIdx;
uint8_t destIdx;
uint8_t destParam;
uint8_t amount;
uint8_t active;
uint8_t inverted;
uint8_t reserved1;
uint8_t reserved2;
};
class ModMatrix {
public:
ModSlot slots[16];
void patch(uint8_t slotIdx, uint8_t src, uint8_t dest, ModDest param,
float amt, bool active);
void process(Gate **gates, uint8_t gateCount);
void clearPatch(uint8_t slotIdx);
;
};
#endif

24
include/Output.h Normal file
View file

@ -0,0 +1,24 @@
// Output.h
#ifndef Output_h
#define Output_h
#include <cstdint>
class Output {
private:
public:
Output(uint8_t pin, uint8_t idx, uint8_t slotIdx1, uint8_t slotIdx2);
bool state;
uint8_t pin;
uint8_t idx;
uint8_t slotIdx1;
uint8_t slotIdx2;
uint8_t editing;
bool isEnabled;
virtual ~Output() {};
virtual void turnOn();
virtual void turnOff();
};
#endif

36
include/Settings.h Normal file
View file

@ -0,0 +1,36 @@
// Settings.h
#ifndef Settings_h
#define Settings_h
#include "Mod.h"
#include <cstdint>
#define MAX_OUTPUTS 8
#define DATA_PER_OUTPUT 64
enum OutputType : uint8_t { TYPE_GATE };
struct OutputConfig {
uint8_t type;
uint8_t _padding[3];
alignas(4) uint8_t data[DATA_PER_OUTPUT];
};
struct DeviceSettings {
uint32_t magic;
uint32_t version;
OutputConfig configs[MAX_OUTPUTS];
ModSlot slots[16];
bool play;
uint8_t bpm;
bool run;
uint8_t ppqnidx;
};
void save();
bool load();
void load_default();
extern DeviceSettings globalSettings;
#endif

View file

@ -1,47 +1,100 @@
#ifndef GLOBALS_H
#define GLOBALS_H
#include "pico/stdlib.h"
#include "Mod.h"
#include <cstdint>
#include <array>
#include <string>
// PINS
static constexpr uint8_t OUT_1_PIN = 0;
static constexpr uint8_t OUT_2_PIN = 2;
static constexpr uint8_t OUT_3_PIN = 4;
static constexpr uint8_t OUT_4_PIN = 6;
static constexpr uint8_t OUT_5_PIN = 8;
static constexpr uint8_t OUT_6_PIN = 10;
static constexpr uint8_t OUT_7_PIN = 12;
static constexpr uint8_t OUT_8_PIN = 14;
static constexpr uint8_t IN_RUN_PIN = 17;
static constexpr uint8_t SCREEN_SCL_PIN = 18;
static constexpr uint8_t SCREEN_SDA_PIN = 19;
// Modify moves per detent if your encoder is acting weird
// for me, with 20 detents per full rotation, 4 works
static constexpr uint8_t TICKS_PER_DETENT = 4;
static constexpr uint8_t ENCODER_CLK_PIN = 20;
static constexpr uint8_t ENCODER_DT_PIN = 21;
static constexpr uint8_t ENCODER_SW_PIN = 22;
void gpio_callback(uint gpio, uint32_t events);
// TIME BASED
extern volatile bool PLAY;
extern volatile uint8_t BPM;
static constexpr uint32_t MINUTE_US = 60000000;
static constexpr uint8_t PPQN = 96;
extern volatile uint32_t MASTER_TICK;
extern volatile bool RUN;
extern volatile uint8_t EXTPPQNIdx;
#define PPQN_OPTS_LEN 5
extern const uint16_t PPQNOPTS[PPQN_OPTS_LEN];
enum WaveShape { SQUARE, TRIANGLE, SAW, RAMP, EXP, HALFSINE, REXP, LOG, SINE, BOUNCE, SIGMO, WOBBLE, STEPDW, STEPUP, SH, SHAPE_COUNT};
inline const char* waveShapeToString(WaveShape shape) {
switch (shape) {
case SQUARE: return "SQR";
case SINE: return "SINE";
case TRIANGLE: return "TRI";
case SAW: return "SAW";
case EXP: return "EXP";
case REXP: return "REXP";
case RAMP: return "RAMP";
case LOG: return "LOG";
case BOUNCE: return "BNC";
case WOBBLE: return "WOB";
case SIGMO: return "SIG";
case STEPDW: return "STPD";
case STEPUP: return "STPU";
case SH: return "S&H";
case HALFSINE: return "HUMP";
default: return "?";
}
}
// Modifiers in UI order
static std::array<uint8_t, 17> MODIFIERS = {32, 16, 12, 8, 6, 4, 3, 2, 0, 1, 2, 3, 4, 6, 8, 16, 32};
// Modifier type; 0 = multiplicaton, 1 = division; matched with MODIFIERS
static std::array<uint8_t, 17> MOD_TYPES = {0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1};
// Modifier string
static std::array<std::string, 17> MODIFIER_STRINGS = {"x32", "x16", "x12", "x8", "x6", "x4", "x3", "x2", "x0", "/1", "/2", "/3", "/4", "/6", "/8", "/16", "/32"};
extern ModMatrix matrix;
inline const char* modDestToString(ModDest modType) {
switch (modType) {
case DEST_LEVEL: return "LVL";
case DEST_PROBABILITY: return "PROB";
case DEST_WIDTH: return "WIDTH";
default: return "?";
}
}
inline uint32_t millis() {
return to_ms_since_boot(get_absolute_time());
}
inline uint32_t micros() {
return to_us_since_boot(get_absolute_time());
}
#endif // GLOBALS_H
/*
TODO:
PRE-DAC:
[x] Figure out multiplicative beats X2 X4 X8 X16 X32?
[ ] Swing/Phase (same thing)
[x] Probability
[ ] Humanization
[ ] Euclidian Rhythms
[ ] Steps - # of steps for a full pattern
[ ] Hits - how many hits across the steps, must be less than steps
[ ] Offset - move the starting point of the pattern
[ ] Logic (NO | AND | OR | XOR)
[ ] Mute
[ ] Save
[ ] Load
POST-DAC:
[ ] Different Wave Forms
[ ] Different Voltage levels
[ ] v/oct?
100BPM
4800BPM
POSSIBLE DIVISIONS:
1: x48
16: x32
32: x16
40: x8
44: x4
46: x2
---
48*1: 1 ** THIS NEEDS TO BE PASSED IN AS DIVIDE MODE
48*2 = 96: /2
48*4 = 192: /4
48*8 = /8
48*16 = /16
*/

1
lib/pico-ssd1306 Submodule

@ -0,0 +1 @@
Subproject commit 2cec467a06bb8cd89363e12091bfd2318f7feab6

153
master_clock.drawio Normal file
View file

@ -0,0 +1,153 @@
<mxfile host="app.diagrams.net" agent="Mozilla/5.0 (X11; Linux x86_64) AppleWebKit/537.36 (KHTML, like Gecko) Chrome/143.0.0.0 Safari/537.36" version="29.5.2">
<diagram name="Page-1" id="-HQHJa_EQfKjo97XYqHl">
<mxGraphModel dx="2038" dy="736" grid="1" gridSize="10" guides="1" tooltips="1" connect="1" arrows="1" fold="1" page="1" pageScale="1" pageWidth="850" pageHeight="1100" math="0" shadow="0">
<root>
<mxCell id="0" />
<mxCell id="1" parent="0" />
<mxCell id="kG_PlTG_f92uMrFnHzwW-1" parent="1" style="rounded=1;whiteSpace=wrap;html=1;fillColor=#76608a;fontColor=#ffffff;strokeColor=#432D57;align=left;verticalAlign=top;" value="&lt;font face=&quot;Lucida Console&quot;&gt;&amp;nbsp; BPM: 120&amp;nbsp;&amp;nbsp;&lt;/font&gt;&lt;div&gt;&lt;font face=&quot;Lucida Console&quot;&gt;&amp;nbsp; &amp;nbsp; &amp;nbsp; &amp;nbsp; &amp;nbsp; &amp;nbsp; &amp;nbsp; &amp;nbsp; &amp;nbsp; &amp;nbsp; &amp;nbsp; &amp;nbsp; &amp;nbsp; &amp;nbsp; &amp;nbsp; &amp;nbsp;*&lt;br&gt;&lt;/font&gt;&lt;div&gt;&lt;font face=&quot;Lucida Console&quot;&gt;&amp;nbsp; 1&amp;nbsp; &amp;nbsp; 2&amp;nbsp; &amp;nbsp; 3&amp;nbsp; &amp;nbsp; 4&amp;nbsp; &amp;nbsp; &amp;nbsp; &amp;nbsp;&amp;nbsp;&lt;/font&gt;&lt;/div&gt;&lt;div&gt;&lt;font face=&quot;Lucida Console&quot;&gt;&amp;nbsp; 5&amp;nbsp; &amp;nbsp; 6&amp;nbsp; &amp;nbsp; 7&amp;nbsp; &amp;nbsp; 8&amp;nbsp;&lt;/font&gt;&lt;/div&gt;&lt;/div&gt;" vertex="1">
<mxGeometry height="70" width="120" x="180" y="170" as="geometry" />
</mxCell>
<mxCell id="7CsQrmOhY3FsypGgTNEZ-16" edge="1" parent="1" source="kG_PlTG_f92uMrFnHzwW-3" style="edgeStyle=none;curved=1;rounded=0;orthogonalLoop=1;jettySize=auto;html=1;fontSize=12;startSize=8;endSize=8;" target="7CsQrmOhY3FsypGgTNEZ-15" value="">
<mxGeometry relative="1" as="geometry" />
</mxCell>
<mxCell id="kG_PlTG_f92uMrFnHzwW-3" parent="1" style="rounded=1;whiteSpace=wrap;html=1;fillColor=#76608a;fontColor=#ffffff;strokeColor=#432D57;align=left;verticalAlign=top;" value="&amp;nbsp; 1: Division&lt;div&gt;&lt;br&gt;&lt;/div&gt;&lt;div&gt;&amp;nbsp; /4&lt;span style=&quot;background-color: transparent; color: light-dark(rgb(255, 255, 255), rgb(18, 18, 18));&quot;&gt;&amp;nbsp;&lt;/span&gt;&lt;/div&gt;" vertex="1">
<mxGeometry height="70" width="120" x="330" y="170" as="geometry" />
</mxCell>
<mxCell id="kG_PlTG_f92uMrFnHzwW-4" parent="1" style="rounded=1;whiteSpace=wrap;html=1;fillColor=#76608a;fontColor=#ffffff;strokeColor=#432D57;align=left;verticalAlign=top;" value="&amp;nbsp; 1: Width&lt;div&gt;&lt;br&gt;&lt;/div&gt;&lt;div&gt;&amp;nbsp; 50%&lt;/div&gt;" vertex="1">
<mxGeometry height="70" width="120" x="330" y="260" as="geometry" />
</mxCell>
<mxCell id="kG_PlTG_f92uMrFnHzwW-5" parent="1" style="rounded=1;whiteSpace=wrap;html=1;fillColor=#76608a;fontColor=#ffffff;strokeColor=#432D57;align=left;verticalAlign=top;" value="&amp;nbsp; 1: Shape&lt;div&gt;&lt;br&gt;&lt;/div&gt;&lt;div&gt;&amp;nbsp; Pulse&lt;/div&gt;" vertex="1">
<mxGeometry height="70" width="120" x="330" y="350" as="geometry" />
</mxCell>
<mxCell id="kG_PlTG_f92uMrFnHzwW-6" parent="1" style="rounded=1;whiteSpace=wrap;html=1;fillColor=#76608a;fontColor=#ffffff;strokeColor=#432D57;align=left;verticalAlign=top;" value="&amp;nbsp; 1: Level&lt;div&gt;&lt;br&gt;&lt;/div&gt;&lt;div&gt;&amp;nbsp; 90%&lt;/div&gt;" vertex="1">
<mxGeometry height="70" width="120" x="330" y="440" as="geometry" />
</mxCell>
<mxCell id="kG_PlTG_f92uMrFnHzwW-7" parent="1" style="rounded=1;whiteSpace=wrap;html=1;fillColor=#76608a;fontColor=#ffffff;strokeColor=#432D57;align=left;verticalAlign=top;" value="&amp;nbsp; 1: Probability&lt;div&gt;&lt;br&gt;&lt;/div&gt;&lt;div&gt;&amp;nbsp; 100%&lt;/div&gt;" vertex="1">
<mxGeometry height="70" width="120" x="330" y="530" as="geometry" />
</mxCell>
<mxCell id="kG_PlTG_f92uMrFnHzwW-10" parent="1" style="triangle;whiteSpace=wrap;html=1;" value="" vertex="1">
<mxGeometry height="10" width="10" x="280" y="178" as="geometry" />
</mxCell>
<mxCell id="7CsQrmOhY3FsypGgTNEZ-11" parent="1" style="pointerEvents=1;verticalLabelPosition=bottom;shadow=0;dashed=0;align=center;html=1;verticalAlign=top;shape=mxgraph.electrical.waveforms.sine_wave;" value="" vertex="1">
<mxGeometry height="6.18" width="10" x="280" y="210" as="geometry" />
</mxCell>
<mxCell id="7CsQrmOhY3FsypGgTNEZ-12" connectable="0" parent="1" style="group" value="" vertex="1">
<mxGeometry height="70" width="120" x="-120" y="170" as="geometry" />
</mxCell>
<mxCell id="7CsQrmOhY3FsypGgTNEZ-1" parent="7CsQrmOhY3FsypGgTNEZ-12" style="rounded=1;whiteSpace=wrap;html=1;fillColor=#76608a;fontColor=#ffffff;strokeColor=#432D57;align=left;verticalAlign=top;" value="&lt;font size=&quot;1&quot;&gt;&amp;nbsp; 1&lt;/font&gt;" vertex="1">
<mxGeometry height="70" width="120" as="geometry" />
</mxCell>
<mxCell id="7CsQrmOhY3FsypGgTNEZ-2" parent="7CsQrmOhY3FsypGgTNEZ-12" style="pointerEvents=1;verticalLabelPosition=bottom;shadow=0;dashed=0;align=center;html=1;verticalAlign=top;shape=mxgraph.electrical.waveforms.sine_wave;" value="" vertex="1">
<mxGeometry height="40" width="100" x="10" y="15" as="geometry" />
</mxCell>
<mxCell id="7CsQrmOhY3FsypGgTNEZ-3" parent="7CsQrmOhY3FsypGgTNEZ-12" style="rounded=0;whiteSpace=wrap;html=1;fillColor=none;" value="" vertex="1">
<mxGeometry height="10" width="10" x="20" y="55" as="geometry" />
</mxCell>
<mxCell id="7CsQrmOhY3FsypGgTNEZ-4" parent="7CsQrmOhY3FsypGgTNEZ-12" style="rounded=0;whiteSpace=wrap;html=1;" value="" vertex="1">
<mxGeometry height="10" width="10" x="30" y="55" as="geometry" />
</mxCell>
<mxCell id="7CsQrmOhY3FsypGgTNEZ-5" parent="7CsQrmOhY3FsypGgTNEZ-12" style="rounded=0;whiteSpace=wrap;html=1;fillColor=none;" value="" vertex="1">
<mxGeometry height="10" width="10" x="40" y="55" as="geometry" />
</mxCell>
<mxCell id="7CsQrmOhY3FsypGgTNEZ-6" parent="7CsQrmOhY3FsypGgTNEZ-12" style="rounded=0;whiteSpace=wrap;html=1;fillColor=none;" value="" vertex="1">
<mxGeometry height="10" width="10" x="50" y="55" as="geometry" />
</mxCell>
<mxCell id="7CsQrmOhY3FsypGgTNEZ-7" parent="7CsQrmOhY3FsypGgTNEZ-12" style="rounded=0;whiteSpace=wrap;html=1;fillColor=none;" value="" vertex="1">
<mxGeometry height="10" width="10" x="60" y="55" as="geometry" />
</mxCell>
<mxCell id="7CsQrmOhY3FsypGgTNEZ-8" parent="7CsQrmOhY3FsypGgTNEZ-12" style="rounded=0;whiteSpace=wrap;html=1;" value="" vertex="1">
<mxGeometry height="10" width="10" x="70" y="55" as="geometry" />
</mxCell>
<mxCell id="7CsQrmOhY3FsypGgTNEZ-9" parent="7CsQrmOhY3FsypGgTNEZ-12" style="rounded=0;whiteSpace=wrap;html=1;fillColor=none;" value="" vertex="1">
<mxGeometry height="10" width="10" x="80" y="55" as="geometry" />
</mxCell>
<mxCell id="7CsQrmOhY3FsypGgTNEZ-10" parent="7CsQrmOhY3FsypGgTNEZ-12" style="rounded=0;whiteSpace=wrap;html=1;" value="" vertex="1">
<mxGeometry height="10" width="10" x="90" y="55" as="geometry" />
</mxCell>
<mxCell id="7CsQrmOhY3FsypGgTNEZ-13" parent="1" style="text;html=1;whiteSpace=wrap;strokeColor=none;fillColor=none;align=center;verticalAlign=middle;rounded=0;" value="scope mode,&amp;nbsp;&lt;div&gt;long press to main&lt;div&gt;scroll thru channels&lt;/div&gt;&lt;div&gt;squares at bottom light up when signal is high&lt;/div&gt;&lt;/div&gt;" vertex="1">
<mxGeometry height="30" width="120" x="-120" y="280" as="geometry" />
</mxCell>
<mxCell id="7CsQrmOhY3FsypGgTNEZ-18" edge="1" parent="1" source="7CsQrmOhY3FsypGgTNEZ-15" style="edgeStyle=none;curved=1;rounded=0;orthogonalLoop=1;jettySize=auto;html=1;fontSize=12;startSize=8;endSize=8;" target="7CsQrmOhY3FsypGgTNEZ-17" value="">
<mxGeometry relative="1" as="geometry" />
</mxCell>
<mxCell id="7CsQrmOhY3FsypGgTNEZ-15" parent="1" style="text;html=1;whiteSpace=wrap;strokeColor=none;fillColor=none;align=center;verticalAlign=middle;rounded=0;" value="long press anywhere to change output mode" vertex="1">
<mxGeometry height="30" width="120" x="480" y="190" as="geometry" />
</mxCell>
<mxCell id="7CsQrmOhY3FsypGgTNEZ-20" edge="1" parent="1" source="7CsQrmOhY3FsypGgTNEZ-17" style="edgeStyle=none;curved=1;rounded=0;orthogonalLoop=1;jettySize=auto;html=1;fontSize=12;startSize=8;endSize=8;">
<mxGeometry relative="1" as="geometry">
<mxPoint x="540" y="360" as="targetPoint" />
</mxGeometry>
</mxCell>
<mxCell id="7CsQrmOhY3FsypGgTNEZ-17" parent="1" style="rounded=1;whiteSpace=wrap;html=1;fillColor=#76608a;fontColor=#ffffff;strokeColor=#432D57;align=left;verticalAlign=top;" value="&amp;nbsp; 1: MODE&lt;div&gt;&lt;br&gt;&lt;/div&gt;&lt;div&gt;GATE, LFO, STRANGE&lt;/div&gt;&lt;div&gt;TURING, ETC&lt;/div&gt;" vertex="1">
<mxGeometry height="70" width="120" x="480" y="260" as="geometry" />
</mxCell>
<mxCell id="7CsQrmOhY3FsypGgTNEZ-19" parent="1" style="text;html=1;whiteSpace=wrap;strokeColor=none;fillColor=none;align=center;verticalAlign=middle;rounded=0;" value="On Select, go back to settings, they will change based on mode" vertex="1">
<mxGeometry height="30" width="150" x="470" y="370" as="geometry" />
</mxCell>
<mxCell id="7CsQrmOhY3FsypGgTNEZ-21" parent="1" style="text;html=1;whiteSpace=wrap;strokeColor=none;fillColor=none;align=center;verticalAlign=middle;rounded=0;" value="GATE MODE" vertex="1">
<mxGeometry height="30" width="120" x="330" y="130" as="geometry" />
</mxCell>
<mxCell id="7CsQrmOhY3FsypGgTNEZ-22" parent="1" style="text;html=1;whiteSpace=wrap;strokeColor=none;fillColor=none;align=center;verticalAlign=middle;rounded=0;" value="HOME PAGE" vertex="1">
<mxGeometry height="30" width="120" x="180" y="130" as="geometry" />
</mxCell>
<mxCell id="7CsQrmOhY3FsypGgTNEZ-23" parent="1" style="text;html=1;whiteSpace=wrap;strokeColor=none;fillColor=none;align=center;verticalAlign=middle;rounded=0;" value="SCOPE" vertex="1">
<mxGeometry height="30" width="120" x="-120" y="130" as="geometry" />
</mxCell>
<mxCell id="7CsQrmOhY3FsypGgTNEZ-24" parent="1" style="text;html=1;whiteSpace=wrap;strokeColor=none;fillColor=none;align=center;verticalAlign=middle;rounded=0;" value="MODE SELECT" vertex="1">
<mxGeometry height="30" width="120" x="480" y="130" as="geometry" />
</mxCell>
<mxCell id="7CsQrmOhY3FsypGgTNEZ-25" parent="1" style="text;html=1;whiteSpace=wrap;strokeColor=none;fillColor=none;align=center;verticalAlign=middle;rounded=0;" value="STRANGE ATTRACTOR" vertex="1">
<mxGeometry height="30" width="120" x="630" y="130" as="geometry" />
</mxCell>
<mxCell id="7CsQrmOhY3FsypGgTNEZ-26" parent="1" style="rounded=1;whiteSpace=wrap;html=1;fillColor=#76608a;fontColor=#ffffff;strokeColor=#432D57;align=left;verticalAlign=top;" value="&amp;nbsp; 1: TYPE&lt;div&gt;&lt;br&gt;&lt;/div&gt;&lt;div&gt;&amp;nbsp; LORENZ&lt;/div&gt;" vertex="1">
<mxGeometry height="70" width="120" x="630" y="170" as="geometry" />
</mxCell>
<mxCell id="7CsQrmOhY3FsypGgTNEZ-27" parent="1" style="rounded=1;whiteSpace=wrap;html=1;fillColor=#76608a;fontColor=#ffffff;strokeColor=#432D57;align=left;verticalAlign=top;" value="&amp;nbsp; 1: SPEED&lt;div&gt;&lt;br&gt;&lt;/div&gt;&lt;div&gt;&amp;nbsp; SLOW&lt;/div&gt;" vertex="1">
<mxGeometry height="70" width="120" x="630" y="260" as="geometry" />
</mxCell>
<mxCell id="7CsQrmOhY3FsypGgTNEZ-28" parent="1" style="rounded=1;whiteSpace=wrap;html=1;fillColor=#76608a;fontColor=#ffffff;strokeColor=#432D57;align=left;verticalAlign=top;" value="&amp;nbsp; 1: OUTPUT&lt;div&gt;&lt;br&gt;&lt;/div&gt;&lt;div&gt;&amp;nbsp; X, Y, Z&lt;/div&gt;" vertex="1">
<mxGeometry height="70" width="120" x="630" y="350" as="geometry" />
</mxCell>
<mxCell id="7CsQrmOhY3FsypGgTNEZ-29" parent="1" style="rounded=1;whiteSpace=wrap;html=1;fillColor=#76608a;fontColor=#ffffff;strokeColor=#432D57;align=left;verticalAlign=top;" value="&amp;nbsp; 1: RAND TARGET&lt;div&gt;&lt;br&gt;&lt;/div&gt;&lt;div&gt;&amp;nbsp; X, Y, Z&lt;/div&gt;" vertex="1">
<mxGeometry height="70" width="120" x="630" y="440" as="geometry" />
</mxCell>
<mxCell id="7CsQrmOhY3FsypGgTNEZ-30" parent="1" style="rounded=1;whiteSpace=wrap;html=1;fillColor=#76608a;fontColor=#ffffff;strokeColor=#432D57;align=left;verticalAlign=top;" value="&amp;nbsp; 1: RAND AMT&lt;div&gt;&lt;br&gt;&lt;/div&gt;&lt;div&gt;&amp;nbsp; 100%&lt;/div&gt;" vertex="1">
<mxGeometry height="70" width="120" x="630" y="530" as="geometry" />
</mxCell>
<mxCell id="7CsQrmOhY3FsypGgTNEZ-43" parent="1" style="text;html=1;whiteSpace=wrap;strokeColor=none;fillColor=none;align=center;verticalAlign=middle;rounded=0;" value="SETTINGS" vertex="1">
<mxGeometry height="30" width="120" x="30" y="130" as="geometry" />
</mxCell>
<mxCell id="7CsQrmOhY3FsypGgTNEZ-44" parent="1" style="rounded=1;whiteSpace=wrap;html=1;fillColor=#76608a;fontColor=#ffffff;strokeColor=#432D57;align=left;verticalAlign=top;" value="&amp;nbsp; SAVE/LOAD&lt;div&gt;&lt;br&gt;&lt;/div&gt;&lt;div&gt;&amp;nbsp; SAVE&lt;/div&gt;&lt;div&gt;&lt;div&gt;&lt;br&gt;&lt;/div&gt;&lt;div&gt;&amp;nbsp;&amp;nbsp;&lt;/div&gt;&lt;/div&gt;" vertex="1">
<mxGeometry height="70" width="120" x="30" y="170" as="geometry" />
</mxCell>
<mxCell id="7CsQrmOhY3FsypGgTNEZ-46" parent="1" style="rounded=1;whiteSpace=wrap;html=1;fillColor=#76608a;fontColor=#ffffff;strokeColor=#432D57;align=left;verticalAlign=top;" value="&amp;nbsp; PPQN&lt;div&gt;&lt;br&gt;&lt;/div&gt;&lt;div&gt;&amp;nbsp; 24&lt;/div&gt;" vertex="1">
<mxGeometry height="70" width="120" x="30" y="260" as="geometry" />
</mxCell>
<mxCell id="7CsQrmOhY3FsypGgTNEZ-47" parent="1" style="rounded=1;whiteSpace=wrap;html=1;fillColor=#76608a;fontColor=#ffffff;strokeColor=#432D57;align=left;verticalAlign=top;" value="&amp;nbsp; RESET&lt;div&gt;&lt;br&gt;&lt;/div&gt;&lt;div&gt;&amp;nbsp; YES&lt;/div&gt;" vertex="1">
<mxGeometry height="70" width="120" x="30" y="350" as="geometry" />
</mxCell>
<mxCell id="7CsQrmOhY3FsypGgTNEZ-48" parent="1" style="rounded=1;whiteSpace=wrap;html=1;fillColor=#76608a;fontColor=#ffffff;strokeColor=#432D57;align=left;verticalAlign=top;" value="&amp;nbsp; EXIT&lt;div&gt;&lt;br&gt;&lt;/div&gt;&lt;div&gt;&amp;nbsp; &amp;lt;--&lt;/div&gt;" vertex="1">
<mxGeometry height="70" width="120" x="30" y="440" as="geometry" />
</mxCell>
<mxCell id="7CsQrmOhY3FsypGgTNEZ-49" parent="1" style="rounded=1;whiteSpace=wrap;html=1;fillColor=#76608a;fontColor=#ffffff;strokeColor=#432D57;align=left;verticalAlign=top;" value="&amp;nbsp; 1: CV SOURCE&lt;div&gt;&lt;br&gt;&lt;div&gt;&amp;nbsp; EXT 1, EXT 2, INT 1&lt;/div&gt;&lt;/div&gt;" vertex="1">
<mxGeometry height="70" width="120" x="330" y="620" as="geometry" />
</mxCell>
<mxCell id="7CsQrmOhY3FsypGgTNEZ-50" parent="1" style="rounded=1;whiteSpace=wrap;html=1;fillColor=#76608a;fontColor=#ffffff;strokeColor=#432D57;align=left;verticalAlign=top;" value="&amp;nbsp; 1: CV TARGET&lt;div&gt;&lt;br&gt;&lt;div&gt;&amp;nbsp; Width&lt;/div&gt;&lt;/div&gt;" vertex="1">
<mxGeometry height="70" width="120" x="330" y="710" as="geometry" />
</mxCell>
<mxCell id="7CsQrmOhY3FsypGgTNEZ-51" parent="1" style="rounded=1;whiteSpace=wrap;html=1;fillColor=#76608a;fontColor=#ffffff;strokeColor=#432D57;align=left;verticalAlign=top;" value="&amp;nbsp; 1: CV LEVEL&lt;div&gt;&lt;br&gt;&lt;div&gt;&amp;nbsp; 100%&lt;/div&gt;&lt;/div&gt;" vertex="1">
<mxGeometry height="70" width="120" x="330" y="800" as="geometry" />
</mxCell>
<mxCell id="7CsQrmOhY3FsypGgTNEZ-52" parent="1" style="rounded=1;whiteSpace=wrap;html=1;fillColor=#76608a;fontColor=#ffffff;strokeColor=#432D57;align=left;verticalAlign=top;" value="&amp;nbsp; 1: CV SOURCE&lt;div&gt;&lt;br&gt;&lt;div&gt;&amp;nbsp; EXT 1, EXT 2, INT 1&lt;/div&gt;&lt;/div&gt;" vertex="1">
<mxGeometry height="70" width="120" x="630" y="620" as="geometry" />
</mxCell>
<mxCell id="7CsQrmOhY3FsypGgTNEZ-53" parent="1" style="rounded=1;whiteSpace=wrap;html=1;fillColor=#76608a;fontColor=#ffffff;strokeColor=#432D57;align=left;verticalAlign=top;" value="&amp;nbsp; 1: CV TARGET&lt;div&gt;&lt;br&gt;&lt;div&gt;&amp;nbsp; Width&lt;/div&gt;&lt;/div&gt;" vertex="1">
<mxGeometry height="70" width="120" x="630" y="710" as="geometry" />
</mxCell>
<mxCell id="7CsQrmOhY3FsypGgTNEZ-54" parent="1" style="rounded=1;whiteSpace=wrap;html=1;fillColor=#76608a;fontColor=#ffffff;strokeColor=#432D57;align=left;verticalAlign=top;" value="&amp;nbsp; 1: CV LEVEL&lt;div&gt;&lt;br&gt;&lt;div&gt;&amp;nbsp; 100%&lt;/div&gt;&lt;/div&gt;" vertex="1">
<mxGeometry height="70" width="120" x="630" y="800" as="geometry" />
</mxCell>
</root>
</mxGraphModel>
</diagram>
</mxfile>

145
quadrature_encoder.pio Normal file
View file

@ -0,0 +1,145 @@
;
; Copyright (c) 2023 Raspberry Pi (Trading) Ltd.
;
; SPDX-License-Identifier: BSD-3-Clause
;
.pio_version 0 // only requires PIO version 0
.program quadrature_encoder
; the code must be loaded at address 0, because it uses computed jumps
.origin 0
; the code works by running a loop that continuously shifts the 2 phase pins into
; ISR and looks at the lower 4 bits to do a computed jump to an instruction that
; does the proper "do nothing" | "increment" | "decrement" action for that pin
; state change (or no change)
; ISR holds the last state of the 2 pins during most of the code. The Y register
; keeps the current encoder count and is incremented / decremented according to
; the steps sampled
; the program keeps trying to write the current count to the RX FIFO without
; blocking. To read the current count, the user code must drain the FIFO first
; and wait for a fresh sample (takes ~4 SM cycles on average). The worst case
; sampling loop takes 10 cycles, so this program is able to read step rates up
; to sysclk / 10 (e.g., sysclk 125MHz, max step rate = 12.5 Msteps/sec)
; 00 state
JMP update ; read 00
JMP decrement ; read 01
JMP increment ; read 10
JMP update ; read 11
; 01 state
JMP increment ; read 00
JMP update ; read 01
JMP update ; read 10
JMP decrement ; read 11
; 10 state
JMP decrement ; read 00
JMP update ; read 01
JMP update ; read 10
JMP increment ; read 11
; to reduce code size, the last 2 states are implemented in place and become the
; target for the other jumps
; 11 state
JMP update ; read 00
JMP increment ; read 01
decrement:
; note: the target of this instruction must be the next address, so that
; the effect of the instruction does not depend on the value of Y. The
; same is true for the "JMP X--" below. Basically "JMP Y--, <next addr>"
; is just a pure "decrement Y" instruction, with no other side effects
JMP Y--, update ; read 10
; this is where the main loop starts
.wrap_target
update:
MOV ISR, Y ; read 11
PUSH noblock
sample_pins:
; we shift into ISR the last state of the 2 input pins (now in OSR) and
; the new state of the 2 pins, thus producing the 4 bit target for the
; computed jump into the correct action for this state. Both the PUSH
; above and the OUT below zero out the other bits in ISR
OUT ISR, 2
IN PINS, 2
; save the state in the OSR, so that we can use ISR for other purposes
MOV OSR, ISR
; jump to the correct state machine action
MOV PC, ISR
; the PIO does not have a increment instruction, so to do that we do a
; negate, decrement, negate sequence
increment:
MOV Y, ~Y
JMP Y--, increment_cont
increment_cont:
MOV Y, ~Y
.wrap ; the .wrap here avoids one jump instruction and saves a cycle too
% c-sdk {
#include "hardware/clocks.h"
#include "hardware/gpio.h"
// max_step_rate is used to lower the clock of the state machine to save power
// if the application doesn't require a very high sampling rate. Passing zero
// will set the clock to the maximum
static inline void quadrature_encoder_program_init(PIO pio, uint sm, uint pin, int max_step_rate)
{
pio_sm_set_consecutive_pindirs(pio, sm, pin, 2, false);
pio_gpio_init(pio, pin);
pio_gpio_init(pio, pin + 1);
gpio_pull_up(pin);
gpio_pull_up(pin + 1);
pio_sm_config c = quadrature_encoder_program_get_default_config(0);
sm_config_set_in_pins(&c, pin); // for WAIT, IN
sm_config_set_jmp_pin(&c, pin); // for JMP
// shift to left, autopull disabled
sm_config_set_in_shift(&c, false, false, 32);
// don't join FIFO's
sm_config_set_fifo_join(&c, PIO_FIFO_JOIN_NONE);
// passing "0" as the sample frequency,
if (max_step_rate == 0) {
sm_config_set_clkdiv(&c, 1.0);
} else {
// one state machine loop takes at most 10 cycles
float div = (float)clock_get_hz(clk_sys) / (10 * max_step_rate);
sm_config_set_clkdiv(&c, div);
}
pio_sm_init(pio, sm, 0, &c);
pio_sm_set_enabled(pio, sm, true);
}
static inline int32_t quadrature_encoder_get_count(PIO pio, uint sm)
{
uint ret;
int n;
// if the FIFO has N entries, we fetch them to drain the FIFO,
// plus one entry which will be guaranteed to not be stale
n = pio_sm_get_rx_fifo_level(pio, sm) + 1;
while (n > 0) {
ret = pio_sm_get_blocking(pio, sm);
n--;
}
return ret;
}
%}

642
src/DisplayHandler.cpp Normal file
View file

@ -0,0 +1,642 @@
// DisplayHandler.cpp
#include "DisplayHandler.h"
#include "Mod.h"
#include "Settings.h"
#include "globals.h"
#include "pico/stdlib.h"
#include <cstdint>
#include <cstdlib>
#include <pico/time.h>
#include <string>
#include "hardware/i2c.h"
#include "pico-ssd1306/shapeRenderer/ShapeRenderer.h"
#include "pico-ssd1306/ssd1306.h"
#include "pico-ssd1306/textRenderer/TextRenderer.h"
#include "textRenderer/12x16_font.h"
#include "textRenderer/8x8_font.h"
pico_ssd1306::SSD1306 *display = nullptr;
extern void update_BPM(bool up);
DisplayHandler::DisplayHandler(Gate *outputs[]) {
this->outputs = outputs;
currentScreen = 0;
currentOut = -1;
updateScreen = 1;
cursorPosition = 0;
mainMaxCursorPosition = 10;
outMaxCursorPosition = std::size(out_pages) - 1;
cursorClick = 0;
}
void DisplayHandler::setup() {
i2c_init(i2c1, 400 * 1000);
gpio_set_function(SCREEN_SDA_PIN, GPIO_FUNC_I2C);
gpio_set_function(SCREEN_SCL_PIN, GPIO_FUNC_I2C);
gpio_pull_up(SCREEN_SDA_PIN);
gpio_pull_up(SCREEN_SCL_PIN);
display = new pico_ssd1306::SSD1306(i2c1, 0x3C, pico_ssd1306::Size::W128xH64);
display->setOrientation(0);
}
void DisplayHandler::moveCursor(bool dir) {
if (onOutScreen) {
if (cursorClick == 0) {
if (dir == 1) {
cursorPosition++;
currentScreen++;
} else {
cursorPosition--;
currentScreen--;
}
if (cursorPosition > outMaxCursorPosition) {
cursorPosition = 0;
currentScreen = 0;
}
if (cursorPosition < 0) {
cursorPosition = outMaxCursorPosition;
currentScreen = outMaxCursorPosition;
}
} else { // click = 1
if (currentScreen == 1) { // mod screen
outputs[currentOut]->editing = 1;
if (dir == 1) {
outputs[currentOut]->modifierSelectionIndex++;
} else {
outputs[currentOut]->modifierSelectionIndex--;
}
if (outputs[currentOut]->modifierSelectionIndex < 0) {
outputs[currentOut]->modifierSelectionIndex = 0;
}
if (outputs[currentOut]->modifierSelectionIndex >
std::size(MOD_TYPES) - 1) {
outputs[currentOut]->modifierSelectionIndex =
std::size(MOD_TYPES) - 1;
}
} else if (currentScreen == 2) { // shape control
int currentShape = (int)outputs[currentOut]->shape;
if (dir == 1) {
currentShape++;
} else {
currentShape--;
}
if (currentShape >= SHAPE_COUNT) {
currentShape = 0;
}
if (currentShape < 0) {
currentShape = SHAPE_COUNT - 1;
}
outputs[currentOut]->shape = (WaveShape)currentShape;
outputs[currentOut]->writeAnalog(0);
} else if (currentScreen == 3) { // level control
outputs[currentOut]->editing = 1;
if (dir == 1) {
outputs[currentOut]->level++;
} else {
outputs[currentOut]->level--;
}
if (outputs[currentOut]->level > 100) {
outputs[currentOut]->level = 100;
}
if (outputs[currentOut]->level < 1) {
outputs[currentOut]->level = 1;
}
} else if (currentScreen == 4) { // width control
outputs[currentOut]->editing = 1;
if (dir == 1) {
outputs[currentOut]->width++;
} else {
outputs[currentOut]->width--;
}
if (outputs[currentOut]->width > 100) {
outputs[currentOut]->width = 100;
}
if (outputs[currentOut]->width < 1) {
outputs[currentOut]->width = 1;
}
outputs[currentOut]->setWidth(outputs[currentOut]->width);
} else if (currentScreen == 5) { // SWING
outputs[currentOut]->editing = 1;
if (dir == 1) {
outputs[currentOut]->swing++;
} else {
outputs[currentOut]->swing--;
}
if (outputs[currentOut]->swing > 100) {
outputs[currentOut]->swing = 100;
}
if (outputs[currentOut]->swing < 50) {
outputs[currentOut]->swing = 50;
}
} else if (currentScreen == 6) { // PROBABILITY
outputs[currentOut]->editing = 1;
if (dir == 1) {
outputs[currentOut]->p++;
} else {
outputs[currentOut]->p--;
}
if (outputs[currentOut]->p > 100) {
outputs[currentOut]->p = 100;
}
if (outputs[currentOut]->p < 0) {
outputs[currentOut]->p = 0;
}
} else if (currentScreen == 7) { // STICKY
outputs[currentOut]->sticky ^= true;
} else if (currentScreen == 8) { // CV1 Active
matrix.slots[outputs[currentOut]->slotIdx1].active ^= true;
} else if (currentScreen == 9) { // CV1 Source
if (dir == 1) {
matrix.slots[outputs[currentOut]->slotIdx1].sourceIdx++;
if (matrix.slots[outputs[currentOut]->slotIdx1].sourceIdx ==
currentOut) {
matrix.slots[outputs[currentOut]->slotIdx1].sourceIdx++;
}
} else {
matrix.slots[outputs[currentOut]->slotIdx1].sourceIdx--;
if (matrix.slots[outputs[currentOut]->slotIdx1].sourceIdx ==
currentOut) {
matrix.slots[outputs[currentOut]->slotIdx1].sourceIdx--;
}
}
if (matrix.slots[outputs[currentOut]->slotIdx1].sourceIdx > 7) {
matrix.slots[outputs[currentOut]->slotIdx1].sourceIdx = 0;
}
if (matrix.slots[outputs[currentOut]->slotIdx1].sourceIdx < 0) {
matrix.slots[outputs[currentOut]->slotIdx1].sourceIdx = 7;
}
} else if (currentScreen == 10) { // CV1 DEST
int currentDest =
(int)matrix.slots[outputs[currentOut]->slotIdx1].destParam;
if (dir == 1) {
currentDest++;
} else {
currentDest--;
}
if (currentDest >= DEST_COUNT) {
currentDest = 0;
}
if (currentDest < 0) {
currentDest = DEST_COUNT - 1;
}
matrix.slots[outputs[currentOut]->slotIdx1].destParam =
(ModDest)currentDest;
} else if (currentScreen == 11) { // CV1 AMT
if (dir == 1) {
matrix.slots[outputs[currentOut]->slotIdx1].amount++;
} else {
matrix.slots[outputs[currentOut]->slotIdx1].amount--;
}
} else if (currentScreen == 12) { // CV1 INV
matrix.slots[outputs[currentOut]->slotIdx1].inverted ^= true;
} else if (currentScreen == 13) { // CV2 Active
matrix.slots[outputs[currentOut]->slotIdx2].active ^= true;
} else if (currentScreen == 14) { // CV2 Source
if (dir == 1) {
matrix.slots[outputs[currentOut]->slotIdx2].sourceIdx++;
} else {
matrix.slots[outputs[currentOut]->slotIdx2].sourceIdx--;
}
if (matrix.slots[outputs[currentOut]->slotIdx2].sourceIdx > 7) {
matrix.slots[outputs[currentOut]->slotIdx2].sourceIdx = 0;
}
if (matrix.slots[outputs[currentOut]->slotIdx2].sourceIdx < 0) {
matrix.slots[outputs[currentOut]->slotIdx2].sourceIdx = 7;
}
} else if (currentScreen == 15) { // CV2 DEST
int currentDest =
(int)matrix.slots[outputs[currentOut]->slotIdx2].destParam;
if (dir == 1) {
currentDest++;
} else {
currentDest--;
}
if (currentDest >= DEST_COUNT) {
currentDest = 0;
}
if (currentDest < 0) {
currentDest = DEST_COUNT - 1;
}
matrix.slots[outputs[currentOut]->slotIdx2].destParam =
(ModDest)currentDest;
} else if (currentScreen == 16) { // CV2 AMT
if (dir == 1) {
matrix.slots[outputs[currentOut]->slotIdx2].amount++;
} else {
matrix.slots[outputs[currentOut]->slotIdx2].amount--;
}
} else if (currentScreen == 17) { // CV2 INV
matrix.slots[outputs[currentOut]->slotIdx2].inverted ^= true;
} else if (currentScreen == 18) { // MUTE
outputs[currentOut]->editing = 1;
outputs[currentOut]->isEnabled ^= true;
}
}
} else {
if (cursorPosition == 0 && cursorClick == 1) { // Engage BPM on Main Screen
update_BPM(dir);
} else {
if (dir == 1) {
cursorPosition++;
} else {
cursorPosition--;
}
if (!onSettingsScreen) {
if (cursorPosition > mainMaxCursorPosition) {
cursorPosition = 0;
}
if (cursorPosition < 0) {
cursorPosition = mainMaxCursorPosition;
}
} else if (onSettingsScreen) {
if (cursorPosition > 5) {
cursorPosition = 0;
}
if (cursorPosition < 0) {
cursorPosition = 5;
}
}
}
}
updateScreen = 1;
}
void DisplayHandler::handleClick() {
cursorClick ^= true;
if (onOutScreen && !onSettingsScreen) {
if (currentScreen == 0) { // exit screen
cursorPosition = currentOut + 1;
currentOut = -1;
currentScreen = 0;
onOutScreen = 0;
cursorClick = false;
}
if (currentScreen == 1 && outputs[currentOut]->editing == 1) {
outputs[currentOut]->setDiv(outputs[currentOut]->modifierSelectionIndex);
outputs[currentOut]->editing = 0;
cursorClick = false;
}
} else {
if (currentScreen == 0 && !onSettingsScreen) { // on main screen
if (cursorPosition == 0) { // Change BPM
} else if (cursorPosition > 0 && cursorPosition < 9) { // go to out screen
currentOut = cursorPosition - 1;
cursorPosition = 1;
currentScreen = 1;
onOutScreen = 1;
cursorClick = 0;
} else if (cursorPosition == 9) { // PLAY/PAUSE BUTTON
PLAY ^= true;
} else if (cursorPosition == 10) { // GLOBAL SETTINGS
cursorPosition = 0;
onSettingsScreen = 1;
cursorClick = 0;
}
} else if (onSettingsScreen) {
if (cursorPosition == 0) { // SAVE
flashMessage("Saving...");
for (int i = 0; i < 8; i++) {
outputs[i]->pack(globalSettings.configs[i]);
}
globalSettings.bpm = BPM;
globalSettings.play = PLAY;
globalSettings.run = RUN;
globalSettings.ppqnidx = EXTPPQNIdx;
memcpy(globalSettings.slots, matrix.slots, sizeof(ModSlot) * 16);
save();
exitSettingsScreen();
} else if (cursorPosition == 1) { // LOAD
flashMessage("Loading...");
PLAY = false;
bool loaded_defaults = load();
if (!loaded_defaults) {
for (int i = 0; i < 16; i++) {
matrix.slots[i] = globalSettings.slots[i];
}
BPM = globalSettings.bpm;
PLAY = globalSettings.play;
RUN = globalSettings.run;
EXTPPQNIdx = globalSettings.ppqnidx;
}
for (int i = 0; i < 8; i++) {
outputs[i]->unpack(globalSettings.configs[i]);
}
exitSettingsScreen();
} else if (cursorPosition == 2) { // RESET
flashMessage("Resetting...");
PLAY = false;
load_default();
for (int i = 0; i < 8; i++) {
outputs[i]->unpack(globalSettings.configs[i]);
}
for (int i = 0; i < sizeof(outputs); i++) {
outputs[i]->setupPatches();
}
PLAY = true;
exitSettingsScreen();
} else if (cursorPosition == 3) { // PPQN
EXTPPQNIdx++;
if (EXTPPQNIdx >= PPQN_OPTS_LEN) {
EXTPPQNIdx = 0;
}
} else if (cursorPosition == 4) { // RUN
RUN ^= true;
if (RUN) {
PLAY = false;
}
} else if (cursorPosition == 5) { // EXIT
exitSettingsScreen();
}
}
}
updateScreen = 1;
}
void DisplayHandler::exitSettingsScreen() {
onOutScreen = 0;
onSettingsScreen = 0;
cursorPosition = 10;
cursorClick = 0;
currentScreen = 0;
}
void DisplayHandler::render() {
if (updateScreen) {
display->clear();
if (!onSettingsScreen && currentScreen == 0 &&
currentOut == -1) { // main screen
renderMainPage();
} else if (!onSettingsScreen && currentOut != -1) {
renderOutPage();
} else if (onSettingsScreen) {
renderSettingsPage();
}
display->sendBuffer();
updateScreen = 0;
}
}
void DisplayHandler::renderMainPage() {
std::string bpm_string = "BPM: " + std::to_string(BPM);
if (cursorPosition == 0) {
if (cursorClick == 1) {
pico_ssd1306::fillRect(display, 0, 0, 100, 18);
pico_ssd1306::drawText(display, font_12x16, bpm_string.c_str(), 1, 2,
pico_ssd1306::WriteMode::SUBTRACT);
} else {
pico_ssd1306::drawRect(display, 0, 0, 100, 18,
pico_ssd1306::WriteMode::ADD);
pico_ssd1306::drawText(display, font_12x16, bpm_string.c_str(), 1, 2);
}
} else {
pico_ssd1306::drawText(display, font_12x16, bpm_string.c_str(), 1, 2);
}
uint8_t cursor_x = 2;
uint8_t cursor_y = 25;
for (uint8_t i = 1; i < 9; i++) {
if (i == 5) {
cursor_x = 2;
cursor_y += 20;
}
if (cursorPosition == i) {
pico_ssd1306::drawRect(display, cursor_x - 2, cursor_y - 4, cursor_x + 14,
cursor_y + 16, pico_ssd1306::WriteMode::ADD);
}
pico_ssd1306::drawText(display, font_12x16, std::to_string(i).c_str(),
cursor_x, cursor_y);
cursor_x += 30;
}
if (cursorPosition == 9) { // PLAY BUTTON
pico_ssd1306::fillRect(display, 120, 8, 130, 18,
pico_ssd1306::WriteMode::ADD);
pico_ssd1306::drawText(display, font_8x8, PLAY ? ">" : "#", 120, 10,
pico_ssd1306::WriteMode::SUBTRACT);
} else {
pico_ssd1306::drawText(display, font_8x8, PLAY ? ">" : "#", 120, 10);
}
if (cursorPosition == 10) { // OPTIONS BUTTON
pico_ssd1306::fillRect(display, 120, 28, 130, 38,
pico_ssd1306::WriteMode::ADD);
pico_ssd1306::drawText(display, font_8x8, "*", 120, 30,
pico_ssd1306::WriteMode::SUBTRACT);
} else {
pico_ssd1306::drawText(display, font_8x8, "*", 120, 30);
}
}
void DisplayHandler::renderOutPage() {
uint8_t visualOut = currentOut + 1;
std::string title =
std::to_string(visualOut) + "| " + out_pages[currentScreen];
pico_ssd1306::drawText(display, font_12x16, title.c_str(), 1, 2);
std::string param_string;
if (currentScreen == 0) { // exit screen
param_string = "<--";
} else if (currentScreen == 1) { // modifier screen
uint8_t modifier_selection_index =
outputs[currentOut]->modifierSelectionIndex;
param_string = MODIFIER_STRINGS[modifier_selection_index];
} else if (currentScreen == 2) { // shape screen
param_string = waveShapeToString(outputs[currentOut]->shape);
} else if (currentScreen == 3) { // level screen
param_string = std::to_string(outputs[currentOut]->level) + "%";
} else if (currentScreen == 4) { // Width screen
param_string = std::to_string(outputs[currentOut]->width) + "%";
} else if (currentScreen == 5) { // Swing screen
param_string = std::to_string(outputs[currentOut]->swing) + "%";
} else if (currentScreen == 6) { // Probability screen
param_string = std::to_string(outputs[currentOut]->p) + "%";
} else if (currentScreen == 7) { // STICKY Screen
param_string = outputs[currentOut]->sticky ? "ON" : "OFF";
} else if (currentScreen == 8) { // CV1 Active Screen
param_string =
matrix.slots[outputs[currentOut]->slotIdx1].active ? "ON" : "OFF";
} else if (currentScreen == 9) { // CV1 Source Chan Screen
param_string = std::to_string(
matrix.slots[outputs[currentOut]->slotIdx1].sourceIdx + 1);
} else if (currentScreen == 10) { // CV1 DEST Screen
param_string = modDestToString(
(ModDest)matrix.slots[outputs[currentOut]->slotIdx1].destParam);
} else if (currentScreen == 11) { // CV1 AMT Screen
param_string =
std::to_string(
(int)matrix.slots[outputs[currentOut]->slotIdx1].amount) +
"%";
} else if (currentScreen == 12) { // CV1 INV Screen
param_string =
matrix.slots[outputs[currentOut]->slotIdx1].inverted ? "ON" : "OFF";
} else if (currentScreen == 13) { // CV2 Active Screen
param_string =
matrix.slots[outputs[currentOut]->slotIdx2].active ? "ON" : "OFF";
} else if (currentScreen == 14) { // CV2 Source Chan Screen
param_string = std::to_string(
matrix.slots[outputs[currentOut]->slotIdx2].sourceIdx + 1);
} else if (currentScreen == 15) { // CV2 DEST Screen
param_string = modDestToString(
(ModDest)matrix.slots[outputs[currentOut]->slotIdx2].destParam);
} else if (currentScreen == 16) { // CV2 AMT Screen
param_string =
std::to_string(
(int)matrix.slots[outputs[currentOut]->slotIdx2].amount) +
"%";
} else if (currentScreen == 17) { // CV1 INV Screen
param_string =
matrix.slots[outputs[currentOut]->slotIdx2].inverted ? "ON" : "OFF";
} else if (currentScreen == 18) { // Mute Screen
param_string = outputs[currentOut]->isEnabled ? "ON" : "OFF";
}
if (cursorClick) {
pico_ssd1306::fillRect(display, 1, 42, 50, 60);
pico_ssd1306::drawText(display, font_12x16, param_string.c_str(), 1, 45,
pico_ssd1306::WriteMode::SUBTRACT);
} else {
pico_ssd1306::drawText(display, font_12x16, param_string.c_str(), 1, 45);
}
}
void DisplayHandler::flashMessage(std::string msg) {
display->clear();
pico_ssd1306::drawText(display, font_12x16, msg.c_str(), 1, 1);
display->sendBuffer();
}
void DisplayHandler::renderSettingsPage() {
uint8_t y = 3;
for (int i = 0; i < settings.size(); i++) {
if (cursorPosition == i) {
pico_ssd1306::fillRect(display, 0, y, 50, y + 8);
pico_ssd1306::drawText(display, font_8x8, settings[i].c_str(), 1, y,
pico_ssd1306::WriteMode::SUBTRACT);
if (settings[i] == "Run") {
std::string param = RUN ? "ON" : "OFF";
pico_ssd1306::drawText(display, font_12x16, param.c_str(), 70, 20);
}
if (settings[i] == "PPQN") {
std::string param = std::to_string(PPQNOPTS[EXTPPQNIdx]);
pico_ssd1306::drawText(display, font_12x16, param.c_str(), 70, 20);
}
} else {
pico_ssd1306::drawText(display, font_8x8, settings[i].c_str(), 1, y);
}
y += 10;
}
}

58
src/EncoderHandler.cpp Normal file
View file

@ -0,0 +1,58 @@
// EncoderHandler.cpp
#include "EncoderHandler.h"
#include "DisplayHandler.h"
#include "globals.h"
#include "hardware/pio.h"
#include "pico/stdlib.h"
#include "quadrature_encoder.pio.h"
#include <cstdlib>
#include <string>
static EncoderHandler *self = nullptr;
EncoderHandler::EncoderHandler(DisplayHandler *display_handler) {
this->display_handler = display_handler;
self = this;
encoder_pos = 0;
button_pressed = 0;
}
void EncoderHandler::setup() {
self = this;
gpio_init(ENCODER_SW_PIN);
gpio_set_dir(ENCODER_SW_PIN, GPIO_IN);
gpio_pull_up(ENCODER_SW_PIN);
gpio_set_irq_enabled_with_callback(ENCODER_SW_PIN, GPIO_IRQ_EDGE_FALL, true, &gpio_callback);
PIO pio = pio0;
uint offset = pio_add_program(pio, &quadrature_encoder_program);
this->sm = pio_claim_unused_sm(pio, true);
gpio_init(ENCODER_CLK_PIN);
gpio_pull_up(ENCODER_CLK_PIN);
gpio_init(ENCODER_DT_PIN);
gpio_pull_up(ENCODER_DT_PIN);
quadrature_encoder_program_init(pio, sm, ENCODER_CLK_PIN, 0);
this->last_count = 0;
}
void EncoderHandler::update() {
int32_t current_count = quadrature_encoder_get_count(pio0, this->sm);
int32_t delta = current_count - last_count;
if (abs(delta) >= TICKS_PER_DETENT) {
if (delta < 0) {
display_handler->moveCursor();
} else {
display_handler->moveCursor(0);
}
last_count = current_count - (delta % TICKS_PER_DETENT);
}
}

View file

@ -1,86 +1,384 @@
// Gate.cpp
#include "pico/stdlib.h"
#include "Gate.h"
#include "Mod.h"
#include "Settings.h"
#include "globals.h"
#include <string>
#include "hardware/pwm.h"
#include <cstdlib>
#include <cstring>
#include <math.h>
Gate::Gate(uint8_t pin) {
Gate::Gate(uint8_t pin, uint8_t idx, uint8_t slotIdx1, uint8_t slotIdx2) : Output(pin, idx, slotIdx1, slotIdx2) {
this->pin = pin;
this->idx = idx;
this->slotIdx1 = slotIdx1;
this->slotIdx2 = slotIdx2;
state = 0;
divideMode = 1; // 1 divison | 0 multiplication
modifier = 1; // divide mode modifier (4x, /32, etc)
div = 1; // cycles needed before a pulse based on divide mode and modifier
cycle = 0; // how many cycles have passed since last pulse
divString = ""; // string for screen .. probably does not belong here
editing = 0;
modifierSelectionIndex = 8;
divideMode = 0; // 1 divison | 0 multiplication
modifier = 0; // divide mode modifier (4x, /32, etc)
dur = 0; // how long pulse is on
width = 50; // pulse width
len = 0; // max len a pulse can be on, as determined by width
p = 100; // probability of a pulse
level = 100;
modDest1 = (idx + 1) % 8;
modDest2 = (idx + 2) % 8;
}
bool Gate::getState() {
return state;
void Gate::pack(OutputConfig &cfg) {
cfg.type = TYPE_GATE;
GateSettings* s = (GateSettings*)cfg.data;
s->modifierSelectionIndex = this->modifierSelectionIndex;
s->divideMode = this->divideMode;
s->modifier = this->modifier;
s->width = this->width;
s->p = this->p;
s->level = this->level;
s->shape = (uint8_t)this->shape;
}
void Gate::unpack(const OutputConfig &cfg) {
if (cfg.type != TYPE_GATE) return;
GateSettings s;
memcpy(&s, cfg.data, sizeof(GateSettings));
this->modifierSelectionIndex = s.modifierSelectionIndex;
this->divideMode = s.divideMode;
this->modifier = s.modifier;
this->width = s.width;
this->p = s.p;
this->level = s.level;
this->shape = (WaveShape)s.shape;
setDiv(this->modifierSelectionIndex);
setWidth(this->width);
}
void Gate::setupPatches() {
matrix.patch(this->slotIdx1, this->modDest1, this->idx, DEST_LEVEL, 100, false);
matrix.patch(this->slotIdx2, this->modDest2, this->idx, DEST_LEVEL, 100, false);
}
void Gate::setLen(uint32_t currentPeriod) {
len = (uint32_t)((double)currentPeriod * (width / 100.0) / 1000.0);
}
void Gate::setDiv(uint16_t modifier, uint8_t divide) {
if (divide == 1) {
div = ppqn * modifier;
divString = "/" + std::to_string(modifier);
} else {
div = ppqn / modifier;
divString = "x" + std::to_string(modifier);
void Gate::setDiv(uint8_t modifier_selecton_index) {
switch (modifier_selecton_index) {
case 0: // x32
tickInterval = 3;
isEnabled = true;
divideMode = 0;
modifier = 32;
break;
case 1: // x16
tickInterval = 6;
isEnabled = true;
divideMode = 0;
modifier = 16;
break;
case 2: // x12
tickInterval = 8;
isEnabled = true;
divideMode = 0;
modifier = 12;
break;
case 3: // x8
tickInterval = 12;
isEnabled = true;
divideMode = 0;
modifier = 8;
break;
case 4: // x6
tickInterval = 16;
isEnabled = true;
divideMode = 0;
modifier = 6;
break;
case 5: // x4
tickInterval = 24;
isEnabled = true;
divideMode = 0;
modifier = 4;
break;
case 6: // x3
tickInterval = 32;
isEnabled = true;
divideMode = 0;
modifier = 3;
break;
case 7: // x2
tickInterval = 48;
isEnabled = true;
divideMode = 0;
modifier = 2;
break;
case 8: // 0 (OFF)
tickInterval = 0;
isEnabled = false;
divideMode = 0;
modifier = 0;
break;
case 9: // /1
tickInterval = 96;
isEnabled = true;
divideMode = 1;
modifier = 1;
break;
case 10: // /2
tickInterval = 192;
isEnabled = true;
divideMode = 1;
modifier = 2;
break;
case 11: // /3
tickInterval = 288;
isEnabled = true;
divideMode = 1;
modifier = 3;
break;
case 12: // /4
tickInterval = 384;
isEnabled = true;
divideMode = 1;
modifier = 4;
break;
case 13: // /6
tickInterval = 576;
isEnabled = true;
divideMode = 1;
modifier = 4;
break;
case 14: // /8
tickInterval = 768;
isEnabled = true;
divideMode = 1;
modifier = 8;
break;
case 15: // /16
tickInterval = 1536;
isEnabled = true;
divideMode = 1;
modifier = 16;
break;
case 16: // /32
tickInterval = 3072;
isEnabled = true;
divideMode = 1;
modifier = 16;
break;
default:
tickInterval = 96;
isEnabled = true;
divideMode = 1;
}
divideMode = divide;
this->modifier = modifier;
this->triggerCount = 0;
this->lastTriggerTick = 0xFFFFFFFF;
setWidth(this->width);
// this is called in width, check if needed still?
calculatePulseWidth();
};
void Gate::setWidth(uint16_t newWidth) {
width = newWidth;
if (divideMode == 1) {
len = (uint32_t)((double)(minute / BPM) * (width / 100.0) / 1000.0);
} else {
len = (uint32_t)((double)(minute / BPM / modifier) * (width / 100.0) / 1000.0);
}
};
this->width = newWidth;
void Gate::setP(uint16_t prob) {
this->p = prob;
double ms_per_tick = (60000.0 / (double)BPM) / 96.0;
double ms_between_triggers = ms_per_tick * (double)this->tickInterval;
this->len = (uint32_t)(ms_between_triggers * (this->width / 100.0));
uint32_t max_allowed_len =
(ms_between_triggers > 5) ? (uint32_t)ms_between_triggers - 2 : 1;
if (this->len > max_allowed_len) {
this->len = max_allowed_len;
}
if (this->len < 1)
this->len = 1;
double us_per_tick = 625000.0 / (double)BPM;
calculatePulseWidth();
this->pulseDurationUs =
(uint32_t)(us_per_tick * (double)this->pulseWidthTicks);
if (this->pulseDurationUs < 100)
this->pulseDurationUs = 100;
}
void Gate::calculatePulseWidth() {
if (tickInterval == 0 || !isEnabled) {
pulseWidthTicks = 0;
return;
}
this->pulseWidthTicks =
(uint32_t)((float)this->tickInterval * (this->width / 100.0f));
if (this->width > 0 && this->pulseWidthTicks == 0) {
this->pulseWidthTicks = 1;
}
}
void Gate::turnOn() {
cycle += 1;
uint8_t pRes = 1;
if (!isEnabled || tickInterval == 0)
return;
if (cycle == div) {
if (p < 100) {
uint32_t r = (rand() % 100) + 1;
if (r > p) {
pRes = 0;
if (MASTER_TICK % tickInterval == 0) {
if (MASTER_TICK != lastTriggerTick) {
lastTriggerTick = MASTER_TICK;
float baseP = (float)this->p;
float effectiveP = baseP + (this->pMod * 100.0f);
if (effectiveP > 100.0f) effectiveP = 100.0f;
if (effectiveP < 0.0f) effectiveP = 0.0f;
if ((rand() % 100) + 1 > (uint8_t)effectiveP) {
scheduledTick = 0xFFFFFFFF;
return;
}
// swing
triggerCount++;
uint32_t swingDelayTicks =
(uint32_t)((float)tickInterval * ((float)swing - 50.0f) / 100.0f);
if (triggerCount % 2 == 0) {
scheduledTick = MASTER_TICK + swingDelayTicks;
} else {
scheduledTick = MASTER_TICK;
}
}
}
if (pRes == 1) {
if (MASTER_TICK >= scheduledTick && !state) {
state = 1;
digitalWrite(pin, state);
dur = millis();
startTick = MASTER_TICK;
startTimeUs = time_us_64();
scheduledTick = 0xFFFFFFFF;
currentRandomVal = (float)rand() / (float)RAND_MAX;
}
cycle = 0;
};
}
void Gate::turnOff() {
if (state == 1 && millis() - dur >= len) {
void Gate::update() {
if (!state && !sticky) {
lastOutVal = 0.0f;
return;
}
uint64_t now = time_us_64();
uint32_t elapsedUs = (uint32_t)(now - startTimeUs);
if (elapsedUs >= pulseDurationUs) {
state = 0;
digitalWrite(pin, state);
dur = 0;
};
if (!sticky)
writeAnalog(0);
return;
}
float phase = (float)elapsedUs / (float)pulseDurationUs;
float outVal = 0;
switch (shape) {
case SINE:
outVal = (sinf(phase * 2.0f * 3.14159f) * 0.5f) + 0.5f;
break;
case HALFSINE: // AKA HUMP
outVal = sinf(phase * 3.14159f);
break;
case TRIANGLE:
outVal = (phase < 0.5f) ? (phase * 2.0f) : (2.0f - (phase * 2.0f));
break;
case SAW:
outVal = 1.0f - phase;
break;
case RAMP:
outVal = phase;
break;
case EXP:
outVal = expf(-5.0f * phase);
break;
case REXP:
outVal = expf(5.0f * (phase - 1.0f));
break;
case LOG:
outVal = 1.0f - expf(-5.0f * phase);
break;
case SQUARE:
outVal = 1.0f;
break;
case BOUNCE:
outVal = fabsf(sinf(phase * 3.14159f * 2.0f));
break;
case SIGMO:
outVal = phase * phase * (3.0f - 2.0f * phase);
break;
case WOBBLE:
outVal = expf(-3.0f * phase) * cosf(phase * 3.14159f * 4.0f);
if (outVal < 0)
outVal = 0;
break;
case STEPDW:
outVal = 1.0f - (floorf(phase * 4.0f) / 3.0f);
break;
case STEPUP:
outVal = floorf(phase * 4.0f) / 3.0f;
break;
case SH:
outVal = currentRandomVal;
break;
}
this->lastOutVal = outVal;
// handle width mod
float effectiveWidth = (float)width + (widthMod * 100.0f);
if (effectiveWidth > 100.0f) effectiveWidth = 100.0f;
if (effectiveWidth < 1.0f) effectiveWidth = 1.0f;
double us_per_tick = 625000.0 / (double)BPM;
uint32_t modulatedTicks = (uint32_t)((float)this->tickInterval * (effectiveWidth / 100.0f));
if (modulatedTicks < 1) modulatedTicks = 1;
this->pulseDurationUs = (uint32_t)(us_per_tick * (double)modulatedTicks);
float baseLevel = (float)this->level / 100.0f;
float normalizedMod = this->levelMod;
if (normalizedMod > 1.0f || normalizedMod < -1.0f) {
normalizedMod /= 100.0f;
}
float finalLevel = baseLevel + normalizedMod;
if (finalLevel > 1.0f) finalLevel = 1.0f;
if (finalLevel < 0.0f) finalLevel = 0.0f;
writeAnalog((uint16_t)(outVal * 1023.0f * finalLevel));}
void Gate::writeAnalog(uint16_t val) { pwm_set_gpio_level(pin, val); }
void Gate::turnOff() { writeAnalog(0); }

53
src/Mod.cpp Normal file
View file

@ -0,0 +1,53 @@
#include "Mod.h"
#include "Gate.h"
#include <cstdint>
void ModMatrix::patch(uint8_t slotIdx, uint8_t src, uint8_t dest, ModDest param,
float amt, bool active) {
slots[slotIdx].sourceIdx = src;
slots[slotIdx].destIdx = dest;
slots[slotIdx].destParam = (uint8_t)param;
slots[slotIdx].amount = (uint8_t)amt;
slots[slotIdx].active = active ? 1 : 0;
slots[slotIdx].inverted = 0;
return;
}
void ModMatrix::process(Gate **gates, uint8_t gateCount) {
for (int i = 0; i < gateCount; i++) {
gates[i]->resetMods();
}
for (int i = 0; i < 16; i++) {
if (slots[i].active == 0)
continue;
float srcVal = gates[slots[i].sourceIdx]->lastOutVal;
float amt = (float)slots[i].amount;
float normalizedAmt = amt / 100.0f;
if (slots[i].inverted == 1) {
normalizedAmt *= -1.0f;
}
float modValue = srcVal * normalizedAmt;
Gate *dstGate = gates[slots[i].destIdx];
switch ((ModDest)slots[i].destParam) {
case DEST_LEVEL:
dstGate->levelMod += modValue;
break;
case DEST_PROBABILITY:
dstGate->pMod += modValue;
break;
case DEST_WIDTH:
dstGate->widthMod += modValue;
break;
default:
break;
}
}
}

12
src/Output.cpp Normal file
View file

@ -0,0 +1,12 @@
#include "Output.h"
#include <cstdint>
Output::Output(uint8_t pin, uint8_t idx, uint8_t slotIdx1, uint8_t slotIdx2) {
this->pin = pin;
this->idx = idx;
state = 0;
isEnabled = false;
}
void Output::turnOn() {}
void Output::turnOff() {}

69
src/Settings.cpp Normal file
View file

@ -0,0 +1,69 @@
#include "Settings.h"
#include "Gate.h"
#include "hardware/flash.h"
#include "hardware/sync.h"
#include "pico/multicore.h"
#include <string.h>
#define FLASH_TARGET_OFFSET (2048 * 1024 - FLASH_SECTOR_SIZE)
DeviceSettings globalSettings;
void save() {
const uint32_t WRITE_SIZE = (sizeof(DeviceSettings) + 255) & ~255;
static uint8_t __attribute__((aligned(4))) write_buf[2048];
uint32_t copy_size =
sizeof(DeviceSettings) > 2048 ? 2048 : sizeof(DeviceSettings);
memset(write_buf, 0, sizeof(write_buf));
memcpy(write_buf, &globalSettings, copy_size);
multicore_lockout_start_blocking();
uint32_t ints = save_and_disable_interrupts();
flash_range_erase(FLASH_TARGET_OFFSET, FLASH_SECTOR_SIZE);
flash_range_program(FLASH_TARGET_OFFSET, write_buf, WRITE_SIZE);
restore_interrupts(ints);
multicore_lockout_end_blocking();
}
void load_default() {
memset(&globalSettings.slots, 0, sizeof(globalSettings.slots));
globalSettings.magic = 0x434C4F4B;
globalSettings.version = 1;
for (int i = 0; i < MAX_OUTPUTS; i++) {
globalSettings.configs[i].type = TYPE_GATE;
GateSettings *s = (GateSettings *)globalSettings.configs[i].data;
s->modifierSelectionIndex = 8;
s->divideMode = 0;
s->modifier = 0;
s->width = 50;
s->p = 100;
s->level = 100;
s->shape = 0;
BPM = 60;
PLAY = true;
}
}
bool load() {
const uint8_t *flash_target_contents =
(const uint8_t *)(XIP_BASE + FLASH_TARGET_OFFSET);
DeviceSettings *stored = (DeviceSettings *)flash_target_contents;
if (stored->magic == 0x434C4F4B) {
memcpy(&globalSettings, stored, sizeof(DeviceSettings));
return false;
} else {
load_default();
return true;
}
}

View file

@ -1,96 +1,219 @@
#include <stdio.h>
#include "Settings.h"
#include "hardware/structs/rosc.h"
#include "pico/multicore.h"
#include "pico/stdlib.h"
#include "pico/time.h"
#include <cstdint>
#include <cstdio>
#include <cstring>
#include <hardware/gpio.h>
#include <stdio.h>
#include "globals.h"
#include "DisplayHandler.h"
#include "EncoderHandler.h"
#include "Gate.h"
#include "Mod.h"
#include "Settings.h"
#include "globals.h"
#include "hardware/pwm.h"
static constexpr uint8_t OUT_1_PIN = 0;
static constexpr uint8_t OUT_2_PIN = 2;
static constexpr uint8_t OUT_3_PIN = 4;
static constexpr uint8_t OUT_4_PIN = 6;
static constexpr uint8_t OUT_5_PIN = 8;
static constexpr uint8_t OUT_6_PIN = 10;
static constexpr uint8_t OUT_7_PIN = 12;
static constexpr uint8_t OUT_8_PIN = 14;
static constexpr uint8_t SCREEN_SCL_PIN = 18;
static constexpr uint8_t SCREEN_SDA_PIN = 19;
static constexpr uint8_t ENCODER_CLK_PIN = 20;
static constexpr uint8_t ENCODER_DT_PIN = 21;
static constexpr uint8_t ENCODER_SW_PIN = 22;
volatile uint8_t PLAY = 1;
volatile uint8_t BPM = 100;
static constexpr uint32_t MINUTE_US = 60000000;
static constexpr uint8_t PPQN = 96;
// Time based operations
struct repeating_timer bpm_timer = {0};
volatile uint8_t BPM = 60;
volatile bool PLAY = true;
volatile uint32_t period_us = 0;
volatile uint32_t MASTER_TICK;
volatile bool RUN = false;
const uint16_t PPQNOPTS[] = {1, 2, 4, 24, 48};
volatile uint8_t EXTPPQNIdx = 0;
struct repeating_timer bpm_timer;
ModMatrix matrix;
volatile bool beatToggle = false;
// Initialize Outputs
Gate out1(OUT_1_PIN, 0, 0, 1);
Gate out2(OUT_2_PIN, 1, 2, 3);
Gate out3(OUT_3_PIN, 2, 4, 5);
Gate out4(OUT_4_PIN, 3, 6, 7);
Gate out5(OUT_5_PIN, 4, 8, 9);
Gate out6(OUT_6_PIN, 5, 10, 11);
Gate out7(OUT_7_PIN, 6, 12, 13);
Gate out8(OUT_8_PIN, 7, 14, 15);
Gate out1(OUT_1_PIN);
Gate out2(OUT_2_PIN);
Gate out3(OUT_3_PIN);
Gate out4(OUT_4_PIN);
Gate out5(OUT_5_PIN);
Gate out6(OUT_6_PIN);
Gate out7(OUT_7_PIN);
Gate out8(OUT_8_PIN);
static Gate *outputs[] = {&out1, &out2, &out3, &out4,
&out5, &out6, &out7, &out8};
// Initialize Handlers
static DisplayHandler display_handler(outputs);
static EncoderHandler encoder_handler(&display_handler);
bool timer_callback(struct repeating_timer *t) {
if (PLAY == 1) {
beatToggle = true;
MASTER_TICK += 1;
}
return true;
}
void init_timer(uint32_t period_us) {
cancel_repeating_timer(&bpm_timer);
add_repeating_timer_us(-(int64_t)period_us, timer_callback, NULL, &bpm_timer);
}
void update_period() {
period_us = (uint32_t)(MINUTE_US / (uint32_t)BPM / PPQN);
init_timer(period_us);
}
int main() {
stdio_init_all();
srand(rosc_hw->randombit);
gpio_init(out1.pin);
gpio_init(out2.pin);
gpio_init(out3.pin);
gpio_init(out4.pin);
gpio_init(out5.pin);
gpio_init(out6.pin);
gpio_init(out7.pin);
gpio_init(out8.pin);
gpio_set_dir(out1.pin, GPIO_OUT);
gpio_set_dir(out2.pin, GPIO_OUT);
gpio_set_dir(out3.pin, GPIO_OUT);
gpio_set_dir(out4.pin, GPIO_OUT);
gpio_set_dir(out5.pin, GPIO_OUT);
gpio_set_dir(out6.pin, GPIO_OUT);
gpio_set_dir(out7.pin, GPIO_OUT);
gpio_set_dir(out8.pin, GPIO_OUT);
void update_BPM(bool up) {
if (up) {
BPM++;
} else {
BPM--;
}
update_period();
for (auto g : outputs) {
g->setWidth(g->width);
}
}
void core1_entry() {
multicore_fifo_pop_blocking();
multicore_lockout_victim_init();
char buffer[32];
while (true) {
display_handler.render();
}
}
void full_save() {
for (int i = 0; i < 8; i++) {
outputs[i]->pack(globalSettings.configs[i]);
}
globalSettings.bpm = BPM;
globalSettings.play = PLAY;
globalSettings.run = RUN;
globalSettings.ppqnidx = EXTPPQNIdx;
memcpy(globalSettings.slots, matrix.slots, sizeof(ModSlot) * 16);
save();
}
void setup_outs() {
for (auto g : outputs) {
gpio_init(g->pin);
gpio_set_dir(g->pin, GPIO_OUT);
gpio_set_function(g->pin, GPIO_FUNC_PWM);
uint slice_num = pwm_gpio_to_slice_num(g->pin);
pwm_set_wrap(slice_num, 1023);
pwm_set_clkdiv(slice_num, 1.0f);
pwm_set_gpio_level(g->pin, 0);
pwm_set_enabled(slice_num, true);
g->setLen(period_us);
g->setupPatches();
}
}
void handle_outs() {
matrix.process(outputs, 8);
for (Gate *g : outputs) {
g->turnOn();
g->update();
}
}
void gpio_callback(uint gpio, uint32_t events) {
if (gpio == IN_RUN_PIN) {
if (RUN) {
if (events & GPIO_IRQ_EDGE_RISE) {
PLAY = true;
} else if (events & GPIO_IRQ_EDGE_FALL) {
PLAY = false;
}
}
}
if (gpio == ENCODER_SW_PIN) {
uint64_t now = to_us_since_boot(get_absolute_time());
static uint64_t last_sw_time = 0;
if (now - last_sw_time > 200000) { // 200ms debounce
display_handler.handleClick();
last_sw_time = now;
}
}
}
void setup_ins() {
// SETUP RUN
gpio_init(IN_RUN_PIN);
gpio_set_dir(IN_RUN_PIN, GPIO_IN);
gpio_pull_down(IN_RUN_PIN);
gpio_set_irq_enabled_with_callback(IN_RUN_PIN, GPIO_IRQ_EDGE_RISE | GPIO_IRQ_EDGE_FALL, true, &gpio_callback);
// SETUP CLOCK
// SETUP CV INS
}
int main() {
stdio_init_all();
sleep_ms(200);
bool loaded_defaults = load();
display_handler.setup();
encoder_handler.setup();
setup_outs();
if (!loaded_defaults) {
for (int i = 0; i < 16; i++) {
matrix.slots[i] = globalSettings.slots[i];
}
BPM = globalSettings.bpm;
PLAY = globalSettings.play;
RUN = globalSettings.run;
EXTPPQNIdx = globalSettings.ppqnidx;
}
for (int i = 0; i < 8; i++) {
outputs[i]->unpack(globalSettings.configs[i]);
}
multicore_launch_core1(core1_entry);
multicore_fifo_push_blocking(1);
update_period();
srand(rosc_hw->randombit);
bool lastPlayState = false;
setup_ins();
if (RUN) {
PLAY = false;
}
while (true) {
encoder_handler.update();
if (PLAY) {
handle_outs();
} else {
for (Gate *g : outputs) {
g->turnOff();
}
}
lastPlayState = PLAY;
}
}