4 Commits

6 changed files with 504 additions and 36 deletions

343
src/README.md Normal file
View File

@ -0,0 +1,343 @@
# libGravity API Reference
This document provides API documentation for `libGravity`, a library for building custom scripts for the Sitka Instruments Gravity module.
## `Gravity` Class
The `Gravity` class is the main hardware abstraction wrapper for the module. It provides a central point of access to all of the module's hardware components like the display, clock, inputs, and outputs.
A global instance of this class, `gravity`, is created for you to use in your scripts.
```cpp
// Global instance
extern Gravity gravity;
```
### Public Methods
#### `void Init()`
Initializes the Arduino and all the Gravity hardware components. This should be called once in your `setup()` function.
#### `void Process()`
Performs a polling check for state changes on all inputs and outputs. This should be called repeatedly in your main `loop()` function to ensure all components are responsive.
### Public Properties
* `U8G2_SSD1306_128X64_NONAME_1_HW_I2C display`
* OLED display object from the `U8g2lib` library. Use this to draw to the screen.
* `Clock clock`
* The main clock source wrapper. See the [Clock Class](https://www.google.com/search?q=%23clock-class) documentation for details.
* `DigitalOutput outputs[OUTPUT_COUNT]`
* An array of `DigitalOutput` objects, where `OUTPUT_COUNT` is 6. Each element corresponds to one of the six gate/trigger outputs.
* `DigitalOutput pulse`
* A `DigitalOutput` object for the MIDI Expander module's pulse output.
* `Encoder encoder`
* The rotary encoder with a built-in push button. See the [Encoder Class](https://www.google.com/search?q=%23encoder-class) documentation for details.
* `Button shift_button`
* A `Button` object for the 'Shift' button.
* `Button play_button`
* A `Button` object for the 'Play' button.
* `AnalogInput cv1`
* An `AnalogInput` object for the CV1 input jack.
* `AnalogInput cv2`
* An `AnalogInput` object for the CV2 input jack.
## `AnalogInput` Class
This class handles reading and processing the analog CV inputs. It includes features for calibration, offsetting, and attenuation.
### Public Methods
#### `void Init(uint8_t pin)`
Initializes the analog input on a specific pin.
* **Parameters:**
* `pin`: The GPIO pin for the analog input.
#### `void Process()`
Reads the raw value from the ADC, applies calibration, offset, and attenuation/inversion. This must be called regularly in the main loop.
#### `void AdjustCalibrationLow(int amount)`
Adjusts the low calibration point to fine-tune the input mapping.
* **Parameters:**
* `amount`: The amount to add to the current low calibration value.
#### `void AdjustCalibrationHigh(int amount)`
Adjusts the high calibration point to fine-tune the input mapping.
* **Parameters:**
* `amount`: The amount to add to the current high calibration value.
#### `void SetOffset(float percent)`
Sets a DC offset for the input signal.
* **Parameters:**
* `percent`: A percentage (e.g., `0.5` for 50%) to shift the signal.
#### `void SetAttenuation(float percent)`
Sets the attenuation (scaling) of the input signal. A negative percentage will also invert the signal.
* **Parameters:**
* `percent`: The attenuation level, typically from `0.0` to `1.0`.
#### `int16_t Read()`
Gets the current processed value of the analog input.
* **Returns:** The read value, scaled to a range of +/-512.
#### `float Voltage()`
Gets the analog read value as a voltage.
* **Returns:** A `float` representing the calculated voltage (-5.0V to +5.0V).
## `Button` Class
A wrapper class for handling digital inputs like push buttons, including debouncing and long-press detection.
### Enums
#### `enum ButtonChange`
Constants representing a change in the button's state.
* `CHANGE_UNCHANGED`
* `CHANGE_PRESSED`
* `CHANGE_RELEASED` (a normal, short press)
* `CHANGE_RELEASED_LONG` (a long press)
### Public Methods
#### `void Init(uint8_t pin)`
Initializes the button on a specific GPIO pin.
* **Parameters:**
* `pin`: The GPIO pin for the button.
#### `void AttachPressHandler(void (*f)())`
Attaches a callback function to be executed on a short button press.
* **Parameters:**
* `f`: The function to call.
#### `void AttachLongPressHandler(void (*f)())`
Attaches a callback function to be executed on a long button press.
* **Parameters:**
* `f`: The function to call.
#### `void Process()`
Reads the button's state and handles debouncing and press detection. Call this repeatedly in the main loop.
#### `ButtonChange Change()`
Gets the last state change of the button.
* **Returns:** A `ButtonChange` enum value indicating the last detected change.
#### `bool On()`
Checks the current physical state of the button.
* **Returns:** `true` if the button is currently being held down, `false` otherwise.
## `Clock` Class
A wrapper for all clock and timing functions, supporting internal, external, and MIDI clock sources.
### Enums
#### `enum Source`
Defines the possible clock sources.
* `SOURCE_INTERNAL`
* `SOURCE_EXTERNAL_PPQN_24` (24 pulses per quarter note)
* `SOURCE_EXTERNAL_PPQN_4` (4 pulses per quarter note)
* `SOURCE_EXTERNAL_MIDI`
#### `enum Pulse`
Defines the possible pulse-per-quarter-note rates for the pulse output.
* `PULSE_NONE`
* `PULSE_PPQN_1`
* `PULSE_PPQN_4`
* `PULSE_PPQN_24`
### Public Methods
#### `void Init()`
Initializes the clock, sets up MIDI serial, and sets default values.
#### `void AttachExtHandler(void (*callback)())`
Attaches a user-defined callback to the external clock input. This is triggered by a rising edge on the external clock pin or by an incoming MIDI clock message.
* **Parameters:**
* `callback`: The function to call on an external clock event.
#### `void AttachIntHandler(void (*callback)(uint32_t))`
Sets a callback function that is triggered at the high-resolution internal clock rate (PPQN\_96). This is the main internal timing callback.
* **Parameters:**
* `callback`: The function to call on every internal clock tick. It receives the tick count as a `uint32_t` parameter.
#### `void SetSource(Source source)`
Sets the clock's driving source.
* **Parameters:**
* `source`: The new clock source from the `Source` enum.
#### `bool ExternalSource()`
Checks if the clock source is external.
* **Returns:** `true` if the source is external (PPQN or MIDI).
#### `bool InternalSource()`
Checks if the clock source is internal.
* **Returns:** `true` if the source is the internal master clock.
#### `int Tempo()`
Gets the current tempo.
* **Returns:** The current tempo in beats per minute (BPM).
#### `void SetTempo(int tempo)`
Sets the clock tempo when in internal mode.
* **Parameters:**
* `tempo`: The new tempo in BPM.
#### `void Tick()`
Manually triggers a clock tick. This should be called from your external clock handler to drive the internal timing when in an external clock mode.
#### `void Start()`
Starts the clock.
#### `void Stop()`
Stops (pauses) the clock.
#### `void Reset()`
Resets all clock counters to zero.
#### `bool IsPaused()`
Checks if the clock is currently paused.
* **Returns:** `true` if the clock is stopped.
## `DigitalOutput` Class
This class is used to control the digital gate/trigger outputs.
### Public Methods
#### `void Init(uint8_t cv_pin)`
Initializes a digital output on a specific pin.
* **Parameters:**
* `cv_pin`: The GPIO pin for the CV/Gate output.
#### `void SetTriggerDuration(uint8_t duration_ms)`
Sets the duration for triggers. When `Trigger()` is called, the output will remain high for this duration.
* **Parameters:**
* `duration_ms`: The trigger duration in milliseconds.
#### `void Update(uint8_t state)`
Sets the output state directly.
* **Parameters:**
* `state`: `HIGH` or `LOW`.
#### `void High()`
Sets the output to HIGH (approx. 5V).
#### `void Low()`
Sets the output to LOW (0V).
#### `void Trigger()`
Begins a trigger. The output goes HIGH and will automatically be set LOW after the configured trigger duration has elapsed (handled by `Process()`).
#### `void Process()`
Handles the timing for triggers. If an output was triggered, this method checks if the duration has elapsed and sets the output LOW if necessary. Call this in the main loop.
#### `bool On()`
Returns the current on/off state of the output.
* **Returns:** `true` if the output is currently HIGH.
## `Encoder` Class
Handles all interaction with the rotary encoder, including rotation, button presses, and rotation while pressed.
**Header:** `encoder_dir.h`
### Public Methods
#### `void SetReverseDirection(bool reversed)`
Sets the direction of the encoder.
* **Parameters:**
* `reversed`: Set to `true` to reverse the direction of rotation.
#### `void AttachPressHandler(void (*f)())`
Attaches a callback for a simple press-and-release of the encoder button.
* **Parameters:**
* `f`: The function to call on a button press.
#### `void AttachRotateHandler(void (*f)(int val))`
Attaches a callback for when the encoder is rotated (while the button is not pressed).
* **Parameters:**
* `f`: The callback function. It receives an `int` representing the change in position (can be positive or negative).
#### `void AttachPressRotateHandler(void (*f)(int val))`
Attaches a callback for when the encoder is rotated while the button is being held down.
* **Parameters:**
* `f`: The callback function. It receives an `int` representing the change in position.
#### `void Process()`
Processes encoder and button events. This method must be called repeatedly in the main loop to check for state changes and dispatch the appropriate callbacks.

View File

@ -13,19 +13,23 @@
const int MAX_INPUT = (1 << 10) - 1; // Max 10 bit analog read resolution.
// estimated default calibration value
// Estimated default calibration value
// TODO: This should be set by metadata via calibration.
const int CALIBRATED_LOW = -566;
const int CALIBRATED_HIGH = 512;
/**
* @brief Class for interacting with analog inputs (CV).
*/
class AnalogInput {
public:
AnalogInput() {}
~AnalogInput() {}
/**
* Initializes a analog input object.
* @brief Initializes an analog input object.
*
* @param pin gpio pin for the analog input.
* @param pin The GPIO pin for the analog input.
*/
void Init(uint8_t pin) {
pinMode(pin, INPUT);
@ -33,8 +37,11 @@ class AnalogInput {
}
/**
* Read the value of the analog input and set instance state.
* @brief Reads and processes the analog input.
*
* This method reads the raw value from the ADC, applies the current
* calibration, offset, and attenuation/inversion settings. It should be
* called regularly in the main loop to update the input's state.
*/
void Process() {
old_read_ = read_;
@ -44,14 +51,38 @@ class AnalogInput {
if (inverted_) read_ = -read_;
}
// Set calibration values.
/**
* @brief Adjusts the low calibration point.
*
* This is used to fine-tune the mapping of the raw analog input to the output range.
*
* @param amount The amount to add to the current low calibration value.
*/
void AdjustCalibrationLow(int amount) { low_ += amount; }
/**
* @brief Adjusts the high calibration point.
*
* This is used to fine-tune the mapping of the raw analog input to the output range.
*
* @param amount The amount to add to the current high calibration value.
*/
void AdjustCalibrationHigh(int amount) { high_ += amount; }
/**
* @brief Sets a DC offset for the input.
*
* @param percent A percentage (e.g., 0.5 for 50%) to shift the signal.
*/
void SetOffset(float percent) { offset_ = -(percent)*512; }
/**
* @brief Sets the attenuation (scaling) of the input signal.
*
* This scales the input signal. A negative percentage will also invert the signal.
*
* @param percent The attenuation level, typically from 0.0 to 1.0.
*/
void SetAttenuation(float percent) {
low_ = abs(percent) * CALIBRATED_LOW;
high_ = abs(percent) * CALIBRATED_HIGH;
@ -59,18 +90,16 @@ class AnalogInput {
}
/**
* Get the current value of the analog input within a range of +/-512.
*
* @return read value within a range of +/-512.
* @brief Get the current processed value of the analog input.
*
* @return The read value within a range of +/-512.
*/
inline int16_t Read() { return read_; }
/**
* Return the analog read value as voltage.
*
* @return A float representing the voltage (-5.0 to +5.0).
* @brief Return the analog read value as a voltage.
*
* @return A float representing the calculated voltage (-5.0 to +5.0).
*/
inline float Voltage() { return ((read_ / 512.0) * 5.0); }
@ -85,4 +114,4 @@ class AnalogInput {
bool inverted_ = false;
};
#endif
#endif

View File

@ -4,7 +4,7 @@
* @brief Wrapper class for interacting with trigger / gate inputs.
* @version 0.1
* @date 2025-04-20
*
*
* @copyright MIT - (c) 2025 - Adam Wonak - adam.wonak@gmail.com
*
*/
@ -13,14 +13,14 @@
#include <Arduino.h>
const uint8_t DEBOUNCE_MS = 10;
const uint16_t LONG_PRESS_DURATION_MS = 750;
class Button {
protected:
typedef void (*CallbackFunction)(void);
public:
static const uint8_t DEBOUNCE_MS = 10;
static const uint16_t LONG_PRESS_DURATION_MS = 750;
// Enum constants for active change in button state.
enum ButtonChange {
CHANGE_UNCHANGED,
@ -84,7 +84,7 @@ class Button {
if (on_long_press_ != NULL) on_long_press_();
}
}
// Update variables for next loop
last_press_ = (pressed || released) ? millis() : last_press_;
old_read_ = read;

View File

@ -4,7 +4,7 @@
* @brief Wrapper Class for clock timing functions.
* @version 0.1
* @date 2025-05-04
*
*
* @copyright MIT - (c) 2025 - Adam Wonak - adam.wonak@gmail.com
*
*/
@ -27,6 +27,9 @@ typedef void (*ExtCallback)(void);
static ExtCallback extUserCallback = nullptr;
static void serialEventNoop(uint8_t msg, uint8_t status) {}
/**
* @brief Wrapper Class for clock timing functions.
*/
class Clock {
public:
static constexpr int DEFAULT_TEMPO = 120;
@ -47,6 +50,9 @@ class Clock {
PULSE_LAST,
};
/**
* @brief Initializes the clock, MIDI serial, and sets default values.
*/
void Init() {
NeoSerial.begin(31250);
@ -64,18 +70,36 @@ class Clock {
uClock.start();
}
// Handle external clock tick and call user callback when receiving clock trigger (PPQN_4, PPQN_24, or MIDI).
/**
* @brief Attach a handler for external clock ticks.
*
* This function attaches a user-defined callback to the external clock input pin interrupt.
* It is also called for incoming MIDI clock events.
*
* @param callback Function to call on an external clock event.
*/
void AttachExtHandler(void (*callback)()) {
extUserCallback = callback;
attachInterrupt(digitalPinToInterrupt(EXT_PIN), callback, RISING);
}
// Internal PPQN96 callback for all clock timer operations.
/**
* @brief Attach a handler for the internal high-resolution clock.
*
* Sets a callback function that is triggered at the internal PPQN_96 rate. This is the
* main internal timing callback for all clock operations.
*
* @param callback Function to call on every internal clock tick. It receives the tick count as a parameter.
*/
void AttachIntHandler(void (*callback)(uint32_t)) {
uClock.setOnOutputPPQN(callback);
}
// Set the source of the clock mode.
/**
* @brief Set the source of the clock.
*
* @param source The new source for driving the clock. See the `Source` enum.
*/
void SetSource(Source source) {
bool was_playing = !IsPaused();
uClock.stop();
@ -107,47 +131,81 @@ class Clock {
}
}
// Return true if the current selected source is externl (PPQN_4, PPQN_24, or MIDI).
/**
* @brief Checks if the clock source is external.
*
* @return true if the current source is external (PPQN_4, PPQN_24, or MIDI).
* @return false if the source is internal.
*/
bool ExternalSource() {
return uClock.getClockMode() == uClock.EXTERNAL_CLOCK;
}
// Return true if the current selected source is the internal master clock.
/**
* @brief Checks if the clock source is internal.
*
* @return true if the current source is the internal master clock.
* @return false if the source is external.
*/
bool InternalSource() {
return uClock.getClockMode() == uClock.INTERNAL_CLOCK;
}
// Returns the current BPM tempo.
/**
* @brief Gets the current tempo.
*
* @return int The current tempo in beats per minute (BPM).
*/
int Tempo() {
return uClock.getTempo();
}
// Set the clock tempo to a int between 1 and 400.
/**
* @brief Set the clock tempo.
*
* @param tempo The new tempo in beats per minute (BPM).
*/
void SetTempo(int tempo) {
return uClock.setTempo(tempo);
}
// Record an external clock tick received to process external/internal syncronization.
/**
* @brief Manually trigger a clock tick.
*
* This should be called when in an external clock mode to register an incoming
* clock pulse and drive the internal timing.
*/
void Tick() {
uClock.clockMe();
}
// Start the internal clock.
/**
* @brief Starts the clock.
*/
void Start() {
uClock.start();
}
// Stop internal clock clock.
/**
* @brief Stops (pauses) the clock.
*/
void Stop() {
uClock.stop();
}
// Reset all clock counters to 0.
/**
* @brief Resets all clock counters to zero.
*/
void Reset() {
uClock.resetCounters();
}
// Returns true if the clock is not running.
/**
* @brief Checks if the clock is currently paused.
*
* @return true if the clock is stopped/paused.
* @return false if the clock is running.
*/
bool IsPaused() {
return uClock.clock_state == uClock.PAUSED;
}

View File

@ -13,10 +13,10 @@
#include <Arduino.h>
const byte DEFAULT_TRIGGER_DURATION_MS = 5;
class DigitalOutput {
public:
static const byte DEFAULT_TRIGGER_DURATION_MS = 5;
/**
* Initializes an CV Output paired object.
*

View File

@ -4,10 +4,11 @@
* @brief Class for interacting with encoders.
* @version 0.1
* @date 2025-04-19
*
*
* @copyright MIT - (c) 2025 - Adam Wonak - adam.wonak@gmail.com
*
*/
#ifndef ENCODER_DIR_H
#define ENCODER_DIR_H
@ -16,6 +17,9 @@
#include "button.h"
#include "peripherials.h"
/**
* @brief Class for interacting with a rotary encoder that has a push button.
*/
class Encoder {
protected:
typedef void (*CallbackFunction)(void);
@ -32,22 +36,57 @@ class Encoder {
}
~Encoder() {}
// Set to true if the encoder read direction should be reversed.
/**
* @brief Set the direction of the encoder.
*
* @param reversed Set to true to reverse the direction of rotation.
*/
void SetReverseDirection(bool reversed) {
reversed_ = reversed;
}
/**
* @brief Attach a handler for the encoder button press.
*
* This callback is triggered on a simple press and release of the button,
* without any rotation occurring during the press.
*
* @param f The callback function to execute when a button press.
*/
void AttachPressHandler(CallbackFunction f) {
on_press = f;
}
/**
* @brief Attach a handler for encoder rotation.
*
* This callback is triggered when the encoder is rotated while the button is not pressed.
*
* @param f The callback function to execute on rotation. It receives an integer
* representing the change in position (can be positive or negative).
*/
void AttachRotateHandler(RotateCallbackFunction f) {
on_rotate = f;
}
/**
* @brief Attach a handler for rotation while the button is pressed.
*
* This callback is triggered when the encoder is rotated while the button is being held down.
*
* @param f The callback function to execute. It receives an integer
* representing the change in position.
*/
void AttachPressRotateHandler(RotateCallbackFunction f) {
on_press_rotate = f;
}
/**
* @brief Processes encoder and button events.
*
* This method should be called repeatedly in the main loop to check for state
* changes (rotation, button presses) and dispatch the appropriate callbacks.
*/
void Process() {
// Get encoder position change amount.
int encoder_rotated = _rotate_change() != 0;
@ -91,7 +130,6 @@ class Encoder {
int position = encoder_.getPosition();
unsigned long ms = encoder_.getMillisBetweenRotations();
// Validation (TODO: add debounce check).
if (previous_pos_ == position) {
return 0;
}