Updated documentation and removed 42 in the name

This commit is contained in:
Christoffer Martinsson 2025-09-20 16:31:03 +02:00
parent 932d89e9ce
commit 9be79dd057
14 changed files with 170 additions and 23 deletions

View File

@ -1,13 +1,23 @@
# Assistant Configuration
This file contains configuration and commands for the Claude assistant working on the CMtec CMDR Joystick 25.
## Global Rules
- Rust emdedded
- Always describe what you thinking and your plan befor starting to change files.
- Make sure code have max 5 indentation levels
- Use classes, arrays, structs, etc for clean organization
- Use arrays, structs, etc for clean organization
- Make sure the codebase is manageable and easily readable
- Always check code (compile/check)
- Always fix compile warnings
- Do not try to deploy project to hardware
- Use "just" for check, test, flash etc
- Use file structure described in this file
## Firmware File Structure Blueprint (RP2040 / RP2350)
- `src/hardware.rs`**Required.** Centralize pin assignments, clock constants, peripheral aliases, timer intervals, and other board-specific configuration. Nothing outside this module hardcodes MCU pin numbers or magic frequencies.
- `src/board.rs`**Required.** Board bring-up; owns peripheral wiring (clocks, GPIO, comms, sensors, USB), exposes `Board`/`BoardParts` (or equivalent). Keep granular comments explaining each hardware init block.
- `src/main.rs`**Required.** Thin firmware entry; fetch initialized parts, load persisted configuration, configure timers, and run the primary control loop (USB/event poll, scheduling, report generation). Runtime orchestration only.
- Feature modules stay single-purpose (e.g., `inputs.rs`, `sensors.rs`, `storage.rs`, `status.rs`, `usb_report.rs`, `usb_device.rs`). Each should include unit tests with short intent comments capturing edge cases and data packing, runnable in host mode.
- Utility crates (`mapping.rs`, `calibration.rs`, etc.) should avoid cross-module side effects—prefer explicit data passed through `BoardParts`/state structs.
- Comments document why a block exists or which hardware behaviour it mirrors; avoid repeating obvious code but provide enough context for re-use across RP-series projects.

View File

@ -10,8 +10,8 @@ test:
build-uf2:
cd rp2040 && cargo build --release --target thumbv6m-none-eabi
cd rp2040 && cargo objcopy --release --target thumbv6m-none-eabi -- -O binary target/thumbv6m-none-eabi/release/cmdr-keyboard-42.bin
cd rp2040 && python3 uf2conv.py target/thumbv6m-none-eabi/release/cmdr-keyboard-42.bin --base 0x10000000 --family 0xe48bff56 --convert --output target/firmware.uf2
cd rp2040 && cargo objcopy --release --target thumbv6m-none-eabi -- -O binary target/thumbv6m-none-eabi/release/cmdr-keyboard.bin
cd rp2040 && python3 uf2conv.py target/thumbv6m-none-eabi/release/cmdr-keyboard.bin --base 0x10000000 --family 0xe48bff56 --convert --output target/firmware.uf2
clean:
cargo clean --manifest-path rp2040/Cargo.toml

View File

@ -1,4 +1,4 @@
# CMDR keyboard 42 (swedish layout)
# CMDR Keyboard (swedish layout)
_This HW(PCB) was original made for use with the TeensyLC module and is reused by patching it to fit the rp2040-zero module_

2
rp2040/Cargo.lock generated
View File

@ -54,7 +54,7 @@ source = "registry+https://github.com/rust-lang/crates.io-index"
checksum = "1fd0f2584146f6f2ef48085050886acf353beff7305ebd1ae69500e27c67f64b"
[[package]]
name = "cmdr-keyboard-42"
name = "cmdr-keyboard"
version = "0.2.0"
dependencies = [
"cortex-m",

View File

@ -1,5 +1,5 @@
[package]
name = "cmdr-keyboard-42"
name = "cmdr-keyboard"
version = "0.2.0"
edition = "2024"
@ -37,7 +37,7 @@ opt-level = 3
overflow-checks = false
[[bin]]
name = "cmdr-keyboard-42"
name = "cmdr-keyboard"
test = false
bench = false
path = "src/main.rs"

View File

@ -1,3 +1,11 @@
//! Board bring-up and peripheral wiring for the CMDR Keyboard firmware.
//!
//! This module owns the RP2040 peripheral initialisation lifecycle so that the
//! rest of the firmware can rely on already-configured clocks, GPIO, timers,
//! USB, and LED control. Nothing outside this module should directly touch raw
//! PAC peripherals; callers interact with the strongly typed `BoardParts`
//! returned after initialisation.
use crate::{hardware, ButtonMatrix, MatrixPins, StatusLed};
use cortex_m::delay::Delay;
use cortex_m::interrupt;
@ -22,6 +30,7 @@ pub type KeyboardMatrix = ButtonMatrix<
pub type KeyboardStatusLed = StatusLed<pac::PIO0, rp2040_hal::pio::SM0, hardware::StatusLedPin>;
/// Aggregates the peripherals required to run the keyboard firmware.
pub struct Board {
pub button_matrix: KeyboardMatrix,
pub status_led: KeyboardStatusLed,
@ -30,6 +39,7 @@ pub struct Board {
usb_bus: &'static UsbBusAllocator<rp2040_hal::usb::UsbBus>,
}
/// Components returned to the application after initialization.
pub struct BoardParts {
pub button_matrix: KeyboardMatrix,
pub status_led: KeyboardStatusLed,
@ -40,10 +50,12 @@ pub struct BoardParts {
impl Board {
pub fn new() -> Self {
// Acquire RP2040 peripheral handles before board bring-up.
let mut pac = pac::Peripherals::take().unwrap();
let core = pac::CorePeripherals::take().unwrap();
let mut watchdog = Watchdog::new(pac.WATCHDOG);
// Bring up the primary system and USB clocks using the external crystal.
let clocks = init_clocks_and_plls(
hardware::XTAL_FREQ_HZ,
pac.XOSC,
@ -57,6 +69,7 @@ impl Board {
.unwrap();
let sio = Sio::new(pac.SIO);
// Split the GPIO bank into the strongly typed board pins.
let pins = Pins::new(
pac.IO_BANK0,
pac.PADS_BANK0,
@ -67,6 +80,7 @@ impl Board {
let (rows, cols, status_pin) = hardware::split_board_pins(pins);
let matrix_pins = MatrixPins::new(rows, cols);
// Create the debounced button matrix scanner with firmware thresholds.
let mut button_matrix = ButtonMatrix::new(
matrix_pins,
hardware::MATRIX_DEBOUNCE_SCANS_PRESS,
@ -77,6 +91,7 @@ impl Board {
let (mut pio, sm0, _, _, _) = pac.PIO0.split(&mut pac.RESETS);
let status_led_pin = status_pin;
// Configure the WS2812 status LED using a dedicated PIO state machine.
let status_led = StatusLed::new(
status_led_pin,
&mut pio,
@ -84,9 +99,11 @@ impl Board {
clocks.peripheral_clock.freq(),
);
// Prepare shared timer peripherals and a blocking delay helper.
let timer = Timer::new(pac.TIMER, &mut pac.RESETS, &clocks);
let delay = Delay::new(core.SYST, clocks.system_clock.freq().to_Hz());
// Allocate the global USB bus for the HID device class.
let usb_bus = usb_allocator(
pac.USBCTRL_REGS,
pac.USBCTRL_DPRAM,
@ -120,6 +137,7 @@ fn usb_allocator(
usb_clock: rp2040_hal::clocks::UsbClock,
resets: &mut pac::RESETS,
) -> &'static UsbBusAllocator<rp2040_hal::usb::UsbBus> {
// Lazily create and share the USB bus allocator between HID classes.
static USB_BUS: static_cell::StaticCell<UsbBusAllocator<rp2040_hal::usb::UsbBus>> =
static_cell::StaticCell::new();

View File

@ -61,6 +61,7 @@ mod tests {
#[test]
fn chord_requires_all_modifier_keys_and_two_fn() {
// Confirm the bootloader chord only fires when both Shifts, Ctrl, and two Fn keys are held.
let mut pressed = [false; NUMBER_OF_KEYS];
for (index, key) in layout::MAP[0].iter().enumerate() {
match key {

View File

@ -1,4 +1,4 @@
//! Button matrix scanner for CMDR Keyboard 42.
//! Button matrix scanner for CMDR Keyboard.
//!
//! The scanner owns a concrete set of matrix pins and produces a debounced
//! boolean state for each key.
@ -19,6 +19,7 @@ pub trait MatrixPinAccess<const ROWS: usize, const COLS: usize> {
type RowPin = Pin<DynPinId, FunctionSioInput, PullUp>;
type ColPin = Pin<DynPinId, FunctionSioOutput, PullNone>;
/// Strongly typed bundle of row and column pins used during matrix scanning.
pub struct MatrixPins<const ROWS: usize, const COLS: usize> {
rows: [RowPin; ROWS],
cols: [ColPin; COLS],
@ -32,20 +33,24 @@ impl<const ROWS: usize, const COLS: usize> MatrixPins<ROWS, COLS> {
impl<const ROWS: usize, const COLS: usize> MatrixPinAccess<ROWS, COLS> for MatrixPins<ROWS, COLS> {
fn init_columns(&mut self) {
// Default every column high so rows can be strobed individually.
for column in self.cols.iter_mut() {
column.set_high().ok();
}
}
fn set_column_low(&mut self, column: usize) {
// Pull the active column low before sampling its rows.
self.cols[column].set_low().ok();
}
fn set_column_high(&mut self, column: usize) {
// Release the column after sampling to avoid ghosting.
self.cols[column].set_high().ok();
}
fn read_row(&mut self, row: usize) -> bool {
// Treat a low level as a pressed switch; default to false on IO errors.
self.rows[row].is_low().unwrap_or(false)
}
}
@ -202,6 +207,7 @@ mod tests {
Rc<Cell<bool>>,
Rc<Cell<bool>>,
) {
// Provide a matrix instance backed by mock row/column signals for testing.
let row_state = Rc::new(Cell::new(false));
let column_state = Rc::new(Cell::new(false));
let pins = MockMatrixPins::new(row_state.clone(), column_state.clone());
@ -211,6 +217,7 @@ mod tests {
#[test]
fn init_sets_columns_high() {
// Initialisation should drive the column line to its idle high level.
let (mut matrix, _row, column) = fixture();
assert!(!column.get());
matrix.init_pins();
@ -219,6 +226,7 @@ mod tests {
#[test]
fn debounce_respects_threshold() {
// Debounce counters must reach the threshold before toggling key state.
let (mut matrix, row, _column) = fixture();
let mut states = matrix.buttons_pressed();
assert!(!states[0]);
@ -248,4 +256,41 @@ mod tests {
states = matrix.buttons_pressed();
assert!(!states[0]);
}
#[test]
fn min_press_gap_blocks_fast_retrigger() {
// Verify that a second press faster than the configured gap is ignored until enough scans pass.
let (mut matrix, row, _column) = fixture();
matrix.set_scan_counter(1);
row.set(true);
for _ in 0..5 {
matrix.bump_scan_counter();
matrix.process_column(0);
}
assert!(matrix.buttons_pressed()[0]);
row.set(false);
for _ in 0..5 {
matrix.bump_scan_counter();
matrix.process_column(0);
}
assert!(!matrix.buttons_pressed()[0]);
row.set(true);
for _ in 0..5 {
matrix.bump_scan_counter();
matrix.process_column(0);
}
assert!(!matrix.buttons_pressed()[0]);
for _ in 0..200 {
matrix.bump_scan_counter();
}
for _ in 0..5 {
matrix.bump_scan_counter();
matrix.process_column(0);
}
assert!(matrix.buttons_pressed()[0]);
}
}

View File

@ -1,4 +1,4 @@
//! Hardware configuration and timing constants for the CMDR Keyboard 42.
//! Hardware configuration and timing constants for the CMDR Keyboard.
use rp2040_hal::gpio::{self, DynPinId, FunctionPio0, FunctionSioInput, FunctionSioOutput, Pin, PullNone, PullUp};
use rp2040_hal::gpio::Pins;
@ -28,7 +28,7 @@ pub mod usb {
pub const VID: u16 = 0x1209;
pub const PID: u16 = 0x0001;
pub const MANUFACTURER: &str = "CMtec";
pub const PRODUCT: &str = "CMDR Keyboard 42";
pub const PRODUCT: &str = "CMDR Keyboard";
pub const SERIAL_NUMBER: &str = "0001";
}
@ -106,11 +106,13 @@ mod tests {
#[test]
fn number_of_keys_matches_rows_and_cols() {
// Sanity-check that the declared key count matches the matrix geometry.
assert_eq!(NUMBER_OF_KEYS, KEY_ROWS * KEY_COLS);
}
#[test]
fn usb_metadata_is_consistent() {
// Ensure the device exposes meaningful USB identification strings and IDs.
assert_ne!(usb::VID, 0);
assert_ne!(usb::PID, 0);
assert!(!usb::MANUFACTURER.is_empty());

View File

@ -5,6 +5,7 @@ use crate::layout;
use crate::status::StatusSummary;
use usbd_human_interface_device::page::Keyboard;
/// Captures per-key state transitions and the function layer active when it was pressed.
#[derive(Copy, Clone, Default, Debug, PartialEq, Eq)]
pub struct KeyboardButton {
pub pressed: bool,
@ -12,6 +13,7 @@ pub struct KeyboardButton {
pub fn_mode: u8,
}
/// Discrete states for the sticky modifier state machine.
#[derive(Copy, Clone, PartialEq, Eq, Debug)]
pub enum StickyState {
Inactive,
@ -29,6 +31,7 @@ impl StickyState {
}
}
/// Manages keyboard-wide state, layer selection, and HID report composition.
pub struct KeyboardState {
buttons: [KeyboardButton; NUMBER_OF_KEYS],
sticky_state: StickyState,
@ -39,6 +42,7 @@ pub struct KeyboardState {
impl KeyboardState {
pub fn new() -> Self {
// Initialise button, sticky, and host communication state.
Self {
buttons: [KeyboardButton::default(); NUMBER_OF_KEYS],
sticky_state: StickyState::Inactive,
@ -52,6 +56,7 @@ impl KeyboardState {
&mut self,
pressed_keys: KeyMatrix,
) -> KeyReport {
// Update each button from the latest scan and build the keyboard report.
let fn_mode = Self::fn_mode(&pressed_keys);
for (index, pressed) in pressed_keys.iter().enumerate() {
@ -62,30 +67,37 @@ impl KeyboardState {
}
pub fn update_caps_lock(&mut self, active: bool) {
// Track the host LED state to drive the status indicator.
self.caps_lock_active = active;
}
pub fn caps_lock_active(&self) -> bool {
// Report whether the Caps Lock LED is currently active.
self.caps_lock_active
}
pub fn mark_started(&mut self) {
// Note that the HID interface has successfully exchanged reports.
self.started = true;
}
pub fn mark_stopped(&mut self) {
// Reset the flag when USB communication fails.
self.started = false;
}
pub fn started(&self) -> bool {
// Expose whether USB activity has been observed.
self.started
}
pub fn sticky_state(&self) -> StickyState {
// Current state of the sticky modifier toggle.
self.sticky_state
}
fn toggle_sticky_state(&mut self) {
// Advance through inactive → armed → latched lifecycle and clear when toggled off.
self.sticky_state = match self.sticky_state {
StickyState::Inactive => StickyState::Armed,
StickyState::Armed | StickyState::Latched => {
@ -102,6 +114,7 @@ impl KeyboardState {
usb_suspended: bool,
idle_mode: bool,
) -> StatusSummary {
// Produce a condensed summary consumed by the status LED driver.
StatusSummary::new(
self.caps_lock_active,
matches!(self.sticky_state, StickyState::Armed),
@ -114,6 +127,7 @@ impl KeyboardState {
}
fn build_report(&mut self, fn_mode: u8) -> KeyReport {
// Translate layer-aware button state into the NKRO HID report payload.
let mut report = [Keyboard::NoEventIndicated; NUMBER_OF_KEYS];
let mut sticky_toggle_requested = false;
@ -165,6 +179,7 @@ impl KeyboardState {
}
fn fn_mode(pressed_keys: &KeyMatrix) -> u8 {
// Count the active FN buttons and clamp to the highest supported layer.
let active_fn_keys = layout::FN_BUTTONS
.iter()
.filter(|key_index| pressed_keys[**key_index as usize])
@ -186,6 +201,7 @@ mod tests {
#[test]
fn fn_mode_caps_at_two() {
// Ensure the layer helper never exceeds the maximum FN layer value.
let mut pressed = [false; NUMBER_OF_KEYS];
pressed[layout::FN_BUTTONS[0] as usize] = true;
pressed[layout::FN_BUTTONS[1] as usize] = true;
@ -196,6 +212,7 @@ mod tests {
#[test]
fn sticky_button_transitions_between_states() {
// Sticky button chord should arm, latch on next key, and clear when pressed again.
let mut state = KeyboardState::new();
let mut pressed = [false; NUMBER_OF_KEYS];
@ -225,6 +242,7 @@ mod tests {
#[test]
fn status_summary_reflects_keyboard_state() {
// Status summary must mirror the internal keyboard and USB flags.
let mut state = KeyboardState::new();
state.update_caps_lock(true);
state.mark_started();
@ -236,4 +254,31 @@ mod tests {
assert!(!summary.sticky_armed);
assert!(!summary.sticky_latched);
}
#[test]
fn sticky_key_is_exposed_in_reports_after_latch() {
// Ensure the latched sticky modifier key stays in the HID report stream until cleared.
let mut state = KeyboardState::new();
let mut pressed = [false; NUMBER_OF_KEYS];
pressed[layout::FN_BUTTONS[0] as usize] = true;
pressed[layout::FN_BUTTONS[1] as usize] = true;
pressed[layout::STICKY_BUTTON[0] as usize] = true;
state.process_scan(pressed);
let mut pressed = [false; NUMBER_OF_KEYS];
pressed[layout::FN_BUTTONS[0] as usize] = true;
pressed[layout::FN_BUTTONS[1] as usize] = true;
pressed[0] = true;
let report = state.process_scan(pressed);
assert_eq!(state.sticky_state(), StickyState::Latched);
assert_eq!(report[0], layout::MAP[2][0]);
assert_eq!(report[46], layout::MAP[2][0]);
let pressed = [false; NUMBER_OF_KEYS];
let report = state.process_scan(pressed);
assert_eq!(report[46], layout::MAP[2][0]);
}
}

View File

@ -1,4 +1,4 @@
//! Project: CMtec CMDR Keyboard 42
//! Project: CMtec CMDR Keyboard
//! Date: 2025-03-09
//! Author: Christoffer Martinsson
//! Email: cm@cmtec.se
@ -212,6 +212,7 @@ mod tests {
#[test]
fn layer_map_dimensions_match() {
// Validate each layer exposes exactly one mapping per physical key index.
for layer in MAP.iter() {
assert_eq!(layer.len(), NUMBER_OF_KEYS);
}
@ -219,6 +220,7 @@ mod tests {
#[test]
fn fn_buttons_are_unique() {
// Ensure every Fn button index is distinct so layer counting stays reliable.
assert_ne!(FN_BUTTONS[0], FN_BUTTONS[1]);
assert_ne!(FN_BUTTONS[0], FN_BUTTONS[2]);
}

View File

@ -1,6 +1,6 @@
#![cfg_attr(not(feature = "std"), no_std)]
//! CMDR Keyboard 42 firmware library for RP2040.
//! CMDR Keyboard firmware library for RP2040.
//!
//! This crate mirrors the structure used by earlier CMDR firmware so the
//! keyboard shares the same modular layout for hardware details, status
@ -29,6 +29,7 @@ pub type KeyMatrix = [bool; NUMBER_OF_KEYS];
pub type KeyReport = [usbd_human_interface_device::page::Keyboard; NUMBER_OF_KEYS];
#[cfg(feature = "std")]
// Host-mode tests require these linker symbols even though they are never touched.
#[unsafe(no_mangle)]
static mut __bi_entries_start: u8 = 0;

View File

@ -1,4 +1,4 @@
//! Project: CMtec CMDR Keyboard 42
//! Project: CMtec CMDR Keyboard
//! Date: 2025-03-09
//! Author: Christoffer Martinsson
//! Email: cm@cmtec.se
@ -7,8 +7,8 @@
#![no_std]
#![no_main]
use cmdr_keyboard_42::hardware::{self, timers};
use cmdr_keyboard_42::{Board, BoardParts, KeyboardState, StatusMode, bootloader, KeyReport};
use cmdr_keyboard::hardware::{self, timers};
use cmdr_keyboard::{Board, BoardParts, KeyboardState, StatusMode, bootloader, KeyReport};
use embedded_hal_0_2::timer::CountDown;
use fugit::ExtU32;
use panic_halt as _;
@ -20,6 +20,7 @@ use usbd_human_interface_device::page::Keyboard;
use usbd_human_interface_device::prelude::UsbHidError;
use usbd_human_interface_device::prelude::*;
// The boot2 image must live in the dedicated ROM section, which requires these attributes.
#[unsafe(link_section = ".boot2")]
#[unsafe(no_mangle)]
#[used]
@ -33,6 +34,7 @@ fn handle_usb_state_changes(
last_activity_ms: &mut u32,
status_time_ms: u32,
) {
// Track suspend/resume transitions and refresh idle timers when USB wakes.
let current_suspended = usb_dev.state() == UsbDeviceState::Suspend;
let was_suspended = *usb_suspended;
@ -52,6 +54,7 @@ fn handle_usb_state_changes(
#[rp2040_hal::entry]
fn main() -> ! {
// Bring up the board peripherals and split them into reusable parts.
let BoardParts {
mut button_matrix,
mut status_led,
@ -60,6 +63,7 @@ fn main() -> ! {
usb_bus,
} = Board::new().into_parts();
// Build the HID keyboard class on the shared USB bus allocator.
let mut keyboard = UsbHidClassBuilder::new()
.add_device(NKROBootKeyboardConfig::default())
.build(usb_bus);
@ -82,6 +86,7 @@ fn main() -> ! {
bootloader::enter(&mut status_led);
}
// Timers driving periodic USB polls and status LED updates.
let mut usb_tick = timer.count_down();
usb_tick.start(timers::USB_TICK_INTERVAL_US.micros());
@ -93,9 +98,11 @@ fn main() -> ! {
let mut usb_suspended = false;
let mut wake_on_input = false;
let mut last_activity_ms: u32 = 0;
let mut suspended_scan_divider: u8 = 0;
loop {
if status_tick.wait().is_ok() {
// Update the status LED summary on its cadence.
status_time_ms = status_time_ms.saturating_add(timers::STATUS_LED_INTERVAL_MS);
let idle_elapsed = status_time_ms.saturating_sub(last_activity_ms);
let idle_mode = usb_initialized && idle_elapsed >= timers::IDLE_TIMEOUT_MS;
@ -111,15 +118,18 @@ fn main() -> ! {
);
}
let should_scan = !usb_suspended || {
static mut SUSPENDED_SCAN_COUNTER: u8 = 0;
unsafe {
SUSPENDED_SCAN_COUNTER = (SUSPENDED_SCAN_COUNTER + 1) % 20;
SUSPENDED_SCAN_COUNTER == 0
}
// When suspended, thin out scans to reduce power but keep responsiveness.
const SUSPENDED_SCAN_PERIOD: u8 = 20;
let should_scan = if !usb_suspended {
suspended_scan_divider = 0;
true
} else {
suspended_scan_divider = (suspended_scan_divider + 1) % SUSPENDED_SCAN_PERIOD;
suspended_scan_divider == 0
};
if usb_tick.wait().is_ok() && should_scan {
// Scan the key matrix, handle bootloader chord, and produce a report.
button_matrix.scan_matrix(&mut delay);
let pressed_keys = button_matrix.buttons_pressed();
@ -151,6 +161,7 @@ fn main() -> ! {
let keyboard_report = keyboard_state.process_scan(pressed_keys);
if !usb_suspended {
// Try to send the generated report to the host.
match keyboard.device().write_report(keyboard_report) {
Err(UsbHidError::WouldBlock) | Err(UsbHidError::Duplicate) => {}
Ok(_) => {
@ -173,6 +184,7 @@ fn main() -> ! {
}
if usb_dev.poll(&mut [&mut keyboard]) {
// Consume OUT reports (e.g., LED indicators) and track host activity.
match keyboard.device().read_report() {
Err(UsbError::WouldBlock) => {}
Err(_) => {

View File

@ -58,6 +58,7 @@ impl StatusSummary {
}
}
/// Minimal wrapper around the WS2812 PIO driver that tracks display state.
pub struct StatusLed<P, SM, I>
where
I: AnyPin<Function = P::PinFunction>,
@ -81,6 +82,7 @@ where
sm: UninitStateMachine<(P, SM)>,
clock_freq: fugit::HertzU32,
) -> Self {
// Initialise the WS2812 driver and default the LED to off.
let mut led = Self {
ws2812_direct: Ws2812Direct::new(pin, pio, sm, clock_freq),
current_mode: StatusMode::Off,
@ -91,6 +93,7 @@ where
}
pub fn update(&mut self, mode: StatusMode) {
// Immediately switch to a new mode without animation state.
self.current_mode = mode;
self.mode_started_at = None;
let color = mode_color(mode, 0);
@ -98,6 +101,7 @@ where
}
pub fn apply_summary(&mut self, summary: StatusSummary, current_time_ms: u32) {
// Convert the status summary into a mode, track elapsed time, and update the LED.
let mode = summary_to_mode(summary);
let elapsed = if self.current_mode != mode {
self.current_mode = mode;
@ -113,11 +117,13 @@ where
}
fn write_color(&mut self, color: RGB8) {
// Push a single RGB frame to the WS2812 LED, ignoring transient failures.
let _ = self.ws2812_direct.write([color].iter().copied());
}
}
fn summary_to_mode(summary: StatusSummary) -> StatusMode {
// Collapse the summary flags into a base LED mode.
if summary.usb_suspended {
StatusMode::Suspended
} else if !summary.usb_initialized {
@ -132,6 +138,7 @@ fn summary_to_mode(summary: StatusSummary) -> StatusMode {
}
fn highlight_color(summary: StatusSummary) -> Option<RGB8> {
// Overlay higher-priority highlight colours for sticky and caps-lock states.
if summary.sticky_latched {
Some(COLOR_PURPLE)
} else if summary.sticky_armed {
@ -144,6 +151,7 @@ fn highlight_color(summary: StatusSummary) -> Option<RGB8> {
}
fn mode_color(mode: StatusMode, elapsed_ms: u32) -> RGB8 {
// Determine the base colour or animation effect for the current mode.
match mode {
StatusMode::Off => COLOR_OFF,
StatusMode::Active => COLOR_GREEN,
@ -155,6 +163,7 @@ fn mode_color(mode: StatusMode, elapsed_ms: u32) -> RGB8 {
}
fn blink(color: RGB8, elapsed_ms: u32, period_ms: u32) -> RGB8 {
// Toggle between the provided colour and off at the requested period.
if period_ms == 0 {
return color;
}
@ -163,6 +172,7 @@ fn blink(color: RGB8, elapsed_ms: u32, period_ms: u32) -> RGB8 {
}
fn breathe(color: RGB8, elapsed_ms: u32, period_ms: u32) -> RGB8 {
// Apply a breathing effect by scaling brightness over the period.
if period_ms == 0 {
return color;
}
@ -180,6 +190,7 @@ fn breathe(color: RGB8, elapsed_ms: u32, period_ms: u32) -> RGB8 {
}
fn scale_color(color: RGB8, factor: u8) -> RGB8 {
// Linearly scale each colour component by the provided brightness factor.
RGB8 {
r: (u16::from(color.r) * u16::from(factor) / 255) as u8,
g: (u16::from(color.g) * u16::from(factor) / 255) as u8,