First rp2040 code port

This commit is contained in:
Christoffer Martinsson 2023-07-31 09:20:22 +02:00
parent 1c539dc8c9
commit f9ff1c0b41
10 changed files with 1116 additions and 0 deletions

2
.gitignore vendored
View File

@ -1,2 +1,4 @@
firmware/.cache/clangd/index firmware/.cache/clangd/index
firmware/compile_commands.json firmware/compile_commands.json
rp2040/target
rp2040/Cargo.lock

42
rp2040/.cargo/config Normal file
View File

@ -0,0 +1,42 @@
#
# Cargo Configuration for the https://github.com/rp-rs/rp-hal.git repository.
#
# Copyright (c) The RP-RS Developers, 2021
#
# You might want to make a similar file in your own repository if you are
# writing programs for Raspberry Silicon microcontrollers.
#
# This file is MIT or Apache-2.0 as per the repository README.md file
#
[build]
# Set the default target to match the Cortex-M0+ in the RP2040
target = "thumbv6m-none-eabi"
# Target specific options
[target.thumbv6m-none-eabi]
# Pass some extra options to rustc, some of which get passed on to the linker.
#
# * linker argument --nmagic turns off page alignment of sections (which saves
# flash space)
# * linker argument -Tlink.x tells the linker to use link.x as the linker
# script. This is usually provided by the cortex-m-rt crate, and by default
# the version in that crate will include a file called `memory.x` which
# describes the particular memory layout for your specific chip.
# * inline-threshold=5 makes the compiler more aggressive and inlining functions
# * no-vectorize-loops turns off the loop vectorizer (seeing as the M0+ doesn't
# have SIMD)
rustflags = [
"-C", "link-arg=--nmagic",
"-C", "link-arg=-Tlink.x",
"-C", "inline-threshold=5",
"-C", "no-vectorize-loops",
]
# This runner will make a UF2 file and then copy it to a mounted RP2040 in USB
# Bootloader mode:
runner = "elf2uf2-rs -d"
# This runner will find a supported SWD debug probe and flash your RP2040 over
# SWD:
# runner = "probe-run --chip RP2040"

58
rp2040/Cargo.toml Normal file
View File

@ -0,0 +1,58 @@
[package]
name = "rp2040"
version = "0.1.0"
edition = "2021"
[dependencies]
cortex-m = "0.7.2"
waveshare-rp2040-zero = "0.6.0"
rp2040-boot2 = { version = "0.2.0", optional = true }
rp2040-hal = { version = "0.8.0" }
cortex-m-rt = { version = "0.7", optional = true }
panic-halt= "0.2.0"
embedded-hal ="0.2.5"
log = { version = "0.4", optional = true }
fugit = "0.3.5"
nb = "1.0.0"
smart-leds = "0.3.0"
smart-leds-trait = "0.2.1"
ws2812-pio = "0.6.0"
usbd-human-interface-device = "0.4.2"
usb-device = "0.2"
packed_struct = { version = "0.10", default-features = false }
pio = "0.2.0"
defmt = { version = "0.3", optional = true }
[features]
# This is the set of features we enable by default
default = ["boot2", "rt", "critical-section-impl", "rom-func-cache"]
# critical section that is safe for multicore use
critical-section-impl = ["rp2040-hal/critical-section-impl"]
# 2nd stage bootloaders for rp2040
boot2 = ["rp2040-boot2"]
# Minimal startup / runtime for Cortex-M microcontrollers
rt = ["cortex-m-rt","rp2040-hal/rt"]
# This enables a fix for USB errata 5: USB device fails to exit RESET state on busy USB bus.
# Only required for RP2040 B0 and RP2040 B1, but it doesn't hurt to enable it
rp2040-e5 = ["rp2040-hal/rp2040-e5"]
# Memoize(cache) ROM function pointers on first use to improve performance
rom-func-cache = ["rp2040-hal/rom-func-cache"]
# Disable automatic mapping of language features (like floating point math) to ROM functions
disable-intrinsics = ["rp2040-hal/disable-intrinsics"]
# This enables ROM functions for f64 math that were not present in the earliest RP2040s
rom-v2-intrinsics = ["rp2040-hal/rom-v2-intrinsics"]
defmt = ["dep:defmt", "usb-device/defmt"]
[[bin]]
name = "rp2040"
test = false
bench = false

15
rp2040/memory.x Normal file
View File

@ -0,0 +1,15 @@
MEMORY {
BOOT2 : ORIGIN = 0x10000000, LENGTH = 0x100
FLASH : ORIGIN = 0x10000100, LENGTH = 2048K - 0x100
RAM : ORIGIN = 0x20000000, LENGTH = 256K
}
EXTERN(BOOT2_FIRMWARE)
SECTIONS {
/* ### Boot loader */
.boot2 ORIGIN(BOOT2) :
{
KEEP(*(.boot2));
} > BOOT2
} INSERT BEFORE .text;

12
rp2040/pico-load Executable file
View File

@ -0,0 +1,12 @@
#!/bin/bash
sudo umount /mnt/usb
while [ ! -f /mnt/usb/INFO_UF2.TXT ]; do
sudo mount /dev/sda1 /mnt/usb -o umask=000
sleep 1
done
set -e
# cargo build --release --example waveshare_rp2040_zero_neopixel_rainbow
cargo run --release
# elf2uf2-rs $1
# cp $1.uf2 /mnt/usb
sudo umount /mnt/usb

View File

@ -0,0 +1,98 @@
//! Project: CMtec CMDR Keyboard 42
//! Date: 2023-07-01
//! Author: Christoffer Martinsson
//! Email: cm@cmtec.se
//! License: Please refer to LICENSE in root directory
use core::convert::Infallible;
use cortex_m::delay::Delay;
use embedded_hal::digital::v2::*;
/// Button matrix driver
///
/// # Example
/// ```
/// let button_matrix: ButtonMatrix<4, 6, 48> = ButtonMatrix::new(row_pins, col_pins, 5);
/// ```
pub struct ButtonMatrix<'a, const R: usize, const C: usize, const N: usize> {
rows: &'a [&'a dyn InputPin<Error = Infallible>; R],
cols: &'a mut [&'a mut dyn OutputPin<Error = Infallible>; C],
pressed: [bool; N],
debounce: u8,
debounce_counter: [u8; N],
}
impl<'a, const R: usize, const C: usize, const N: usize> ButtonMatrix<'a, R, C, N> {
/// Creates a new button matrix.
///
/// # Arguments
///
/// * `rows` - An array of references to the row pins.
/// * `cols` - An array of references to the column pins.
/// * `debounce` - The debounce time in number of scans.
pub fn new(
rows: &'a [&'a dyn InputPin<Error = Infallible>; R],
cols: &'a mut [&'a mut dyn OutputPin<Error = Infallible>; C],
debounce: u8,
) -> Self {
Self {
rows,
cols,
pressed: [false; N],
debounce,
debounce_counter: [0; N],
}
}
/// Initializes the button matrix.
/// This should be called once before scanning the matrix.
pub fn init_pins(&mut self) {
for col in self.cols.iter_mut() {
col.set_high().unwrap();
}
}
/// Scans the button matrix and updates the pressed state of each button.
/// This should be called at regular intervals.
/// Allow at least 5 times the delay compared to the needed button latency.
///
/// # Arguments
///
/// * `delay` - A mutable reference to a delay object.
pub fn scan_matrix(&mut self, delay: &mut Delay) {
for col_index in 0..self.cols.len() {
self.cols[col_index].set_low().unwrap();
delay.delay_us(10);
self.process_column(col_index);
self.cols[col_index].set_high().unwrap();
delay.delay_us(10);
}
}
/// Processes a column of the button matrix.
///
/// # Arguments
///
/// * `col_index` - The index of the column to process.
fn process_column(&mut self, col_index: usize) {
for row_index in 0..self.rows.len() {
let button_index: usize = col_index + (row_index * C);
let current_state = self.rows[row_index].is_low().unwrap();
if current_state == self.pressed[button_index] {
self.debounce_counter[button_index] = 0;
continue;
}
self.debounce_counter[button_index] += 1;
if self.debounce_counter[button_index] >= self.debounce {
self.pressed[button_index] = current_state;
}
}
}
/// Returns an array of booleans indicating whether each button is pressed.
pub fn buttons_pressed(&mut self) -> [bool; N] {
self.pressed
}
}

189
rp2040/src/layout.rs Normal file
View File

@ -0,0 +1,189 @@
//! Project: CMtec CMDR Keyboard 42
//! Date: 2023-07-01
//! Author: Christoffer Martinsson
//! Email: cm@cmtec.se
//! License: Please refer to LICENSE in root directory
use crate::NUMBER_OF_KEYS;
#[derive(Debug, PartialEq, Copy, Clone)]
pub enum ButtonType {
B1 = 0,
B2 = 1,
B3 = 2,
B4 = 3,
B5 = 4,
B6 = 5,
B7 = 6,
B8 = 7,
B9 = 8,
B10 = 9,
B11 = 10,
B12 = 11,
B13 = 12,
B14 = 13,
B15 = 14,
B16 = 15,
B17 = 16,
B18 = 17,
B19 = 18,
B20 = 19,
FnL = 20,
FnR = 21,
ModeL = 22,
ModeR = 23,
Hat1U = 24,
Hat1L = 25,
Hat1R = 26,
Hat1D = 27,
Hat2U = 28,
Hat2L = 29,
Hat2R = 30,
Hat2D = 31,
Hat3U = 32,
Hat3L = 33,
Hat3R = 34,
Hat3D = 35,
Hat4U = 36,
Hat4L = 37,
Hat4R = 38,
Hat4D = 39,
NotConnected = 40,
}
// Button index map:
// --------------------------------------------------------------
// | 0 | 1 | | 2 | 3 | (4)
// --------------------------------------------------------------
// | | 5 | 6 | 7 | | 12 | 11 | 10 | |
// | | (9) (14)
// | | 8 | | 13 | |
// | X1/Y1 X2/Y2 |
// | | 16 | | 21 | |
// | | 17 | 15 | 18 || 22 | 20 | 23 | |
// | | 19 | | 24 | |
// --------------------------------------------------------------
//
/// Button map to HID key (three Function layers)
pub const MAP: [[ButtonType; NUMBER_OF_KEYS]; 4] = [
[
// Function layer 0
// HID Key // Button Index
// -----------------------------------------
ButtonType::FnL, // 0
ButtonType::B1, // 1
ButtonType::B6, // 2
ButtonType::FnR, // 3
ButtonType::NotConnected, // 4
ButtonType::B2, // 5
ButtonType::B3, // 6
ButtonType::ModeL, // 7
ButtonType::B4, // 8
ButtonType::NotConnected, // 9
ButtonType::B7, // 10
ButtonType::B8, // 11
ButtonType::ModeR, // 12
ButtonType::B9, // 13
ButtonType::NotConnected, // 14
ButtonType::B5, // 15
ButtonType::Hat1U, // 16
ButtonType::Hat1L, // 17
ButtonType::Hat1R, // 18
ButtonType::Hat1D, // 19
ButtonType::B10, // 20
ButtonType::Hat2U, // 21
ButtonType::Hat2L, // 22
ButtonType::Hat2R, // 23
ButtonType::Hat2D, // 24
],
[
// Function layer left
// HID Key // Button Index
// -----------------------------------------
ButtonType::FnL, // 0
ButtonType::B11, // 1
ButtonType::B6, // 2
ButtonType::FnR, // 3
ButtonType::NotConnected, // 4
ButtonType::B12, // 5
ButtonType::B13, // 6
ButtonType::ModeL, // 7
ButtonType::B14, // 8
ButtonType::NotConnected, // 9
ButtonType::B7, // 10
ButtonType::B8, // 11
ButtonType::ModeR, // 12
ButtonType::B9, // 13
ButtonType::NotConnected, // 14
ButtonType::B15, // 15
ButtonType::Hat1U, // 16
ButtonType::Hat1L, // 17
ButtonType::Hat1R, // 18
ButtonType::Hat1D, // 19
ButtonType::B10, // 20
ButtonType::Hat2U, // 21
ButtonType::Hat2L, // 22
ButtonType::Hat2R, // 23
ButtonType::Hat2D, // 24
],
[
// Function layer right
// HID Key // Button Index
// -----------------------------------------
ButtonType::FnL, // 0
ButtonType::B1, // 1
ButtonType::B16, // 2
ButtonType::FnR, // 3
ButtonType::NotConnected, // 4
ButtonType::B2, // 5
ButtonType::B3, // 6
ButtonType::ModeL, // 7
ButtonType::B4, // 8
ButtonType::NotConnected, // 9
ButtonType::B17, // 10
ButtonType::B18, // 11
ButtonType::ModeR, // 12
ButtonType::B19, // 13
ButtonType::NotConnected, // 14
ButtonType::B5, // 15
ButtonType::Hat3U, // 16
ButtonType::Hat3L, // 17
ButtonType::Hat3R, // 18
ButtonType::Hat3D, // 19
ButtonType::B20, // 20
ButtonType::Hat2U, // 21
ButtonType::Hat2L, // 22
ButtonType::Hat2R, // 23
ButtonType::Hat2D, // 24
],
[
// Function layer left + right
// HID Key // Button Index
// -----------------------------------------
ButtonType::FnL, // 0
ButtonType::B11, // 1
ButtonType::B16, // 2
ButtonType::FnR, // 3
ButtonType::NotConnected, // 4
ButtonType::B12, // 5
ButtonType::B13, // 6
ButtonType::ModeL, // 7
ButtonType::B14, // 8
ButtonType::NotConnected, // 9
ButtonType::B17, // 10
ButtonType::B18, // 11
ButtonType::ModeR, // 12
ButtonType::B19, // 13
ButtonType::NotConnected, // 14
ButtonType::B15, // 15
ButtonType::Hat3U, // 16
ButtonType::Hat3L, // 17
ButtonType::Hat3R, // 18
ButtonType::Hat3D, // 19
ButtonType::B20, // 20
ButtonType::Hat4U, // 21
ButtonType::Hat4L, // 22
ButtonType::Hat4R, // 23
ButtonType::Hat4D, // 24
],
];

364
rp2040/src/main.rs Normal file
View File

@ -0,0 +1,364 @@
//! Project: CMtec CMDR Keyboard 42
//! Date: 2023-07-01
//! Author: Christoffer Martinsson
//! Email: cm@cmtec.se
//! License: Please refer to LICENSE in root directory
#![no_std]
#![no_main]
mod button_matrix;
// mod fmt;
mod layout;
mod status_led;
mod usb_joystick_device;
use button_matrix::ButtonMatrix;
use core::convert::Infallible;
use cortex_m::delay::Delay;
use embedded_hal::digital::v2::*;
use embedded_hal::timer::CountDown;
use fugit::ExtU32;
use panic_halt as _;
use rp2040_hal::{
gpio::{Function, FunctionConfig, PinId, ValidPinMode},
pio::StateMachineIndex,
};
use status_led::{StatusMode, Ws2812StatusLed};
use usb_device::class_prelude::*;
use usb_device::prelude::*;
use usb_joystick_device::{JoystickConfig, JoystickReport};
use usbd_human_interface_device::prelude::*;
use waveshare_rp2040_zero::entry;
use waveshare_rp2040_zero::{
hal::{
clocks::{init_clocks_and_plls, Clock},
pac,
pio::PIOExt,
timer::Timer,
watchdog::Watchdog,
Sio,
},
Pins, XOSC_CRYSTAL_FREQ,
};
// Public constants
pub const KEY_ROWS: usize = 5;
pub const KEY_COLS: usize = 5;
pub const NUMBER_OF_KEYS: usize = KEY_ROWS * KEY_COLS;
// Public types
#[derive(Copy, Clone, Default)]
pub struct KeyboardButton {
pub pressed: bool,
pub previous_pressed: bool,
pub fn_mode: u8,
}
#[entry]
fn main() -> ! {
// Grab our singleton objects
let mut pac = pac::Peripherals::take().unwrap();
// Set up the watchdog driver - needed by the clock setup code
let mut watchdog = Watchdog::new(pac.WATCHDOG);
// Configure clocks and PLLs
let clocks = init_clocks_and_plls(
XOSC_CRYSTAL_FREQ,
pac.XOSC,
pac.CLOCKS,
pac.PLL_SYS,
pac.PLL_USB,
&mut pac.RESETS,
&mut watchdog,
)
.ok()
.unwrap();
let core = pac::CorePeripherals::take().unwrap();
// The single-cycle I/O block controls our GPIO pins
let sio = Sio::new(pac.SIO);
// Set the pins to their default state
let pins = Pins::new(
pac.IO_BANK0,
pac.PADS_BANK0,
sio.gpio_bank0,
&mut pac.RESETS,
);
// Setting up array with pins connected to button rows
let button_matrix_row_pins: &[&dyn InputPin<Error = Infallible>; KEY_ROWS] = &[
&pins.gp9.into_pull_up_input(),
&pins.gp10.into_pull_up_input(),
&pins.gp11.into_pull_up_input(),
&pins.gp12.into_pull_up_input(),
&pins.gp13.into_pull_up_input(),
];
// Setting up array with pins connected to button columns
let button_matrix_col_pins: &mut [&mut dyn OutputPin<Error = Infallible>; KEY_COLS] = &mut [
&mut pins.gp4.into_push_pull_output(),
&mut pins.gp5.into_push_pull_output(),
&mut pins.gp6.into_push_pull_output(),
&mut pins.gp7.into_push_pull_output(),
&mut pins.gp8.into_push_pull_output(),
];
// Create button matrix object that scans all the PCB buttons
let mut button_matrix: ButtonMatrix<KEY_ROWS, KEY_COLS, NUMBER_OF_KEYS> =
ButtonMatrix::new(button_matrix_row_pins, button_matrix_col_pins, 5);
// Configure USB
let usb_bus = UsbBusAllocator::new(waveshare_rp2040_zero::hal::usb::UsbBus::new(
pac.USBCTRL_REGS,
pac.USBCTRL_DPRAM,
clocks.usb_clock,
true,
&mut pac.RESETS,
));
let mut joystick = UsbHidClassBuilder::new()
.add_device(JoystickConfig::default())
.build(&usb_bus);
let mut usb_dev = UsbDeviceBuilder::new(&usb_bus, UsbVidPid(0x1209, 0x0002))
.manufacturer("CMtec")
.product("CMDR Joystick")
.serial_number("0001")
.build();
// Create status LED
let (mut pio, sm0, _, _, _) = pac.PIO0.split(&mut pac.RESETS);
let mut status_led = Ws2812StatusLed::new(
pins.neopixel.into_mode(),
&mut pio,
sm0,
clocks.peripheral_clock.freq(),
);
// Create keyboard button array
let mut buttons: [KeyboardButton; NUMBER_OF_KEYS] = [KeyboardButton::default(); NUMBER_OF_KEYS];
// Create timers/delays
let timer = Timer::new(pac.TIMER, &mut pac.RESETS);
let mut delay = Delay::new(core.SYST, clocks.system_clock.freq().to_Hz());
let mut usb_hid_report_count_down = timer.count_down();
usb_hid_report_count_down.start(10.millis());
let mut usb_tick_count_down = timer.count_down();
usb_tick_count_down.start(1.millis());
let mut status_led_count_down = timer.count_down();
status_led_count_down.start(250.millis());
// Create variables to track caps lock and fn mode
let mut fn_mode: u8;
// Initialize button matrix
button_matrix.init_pins();
// Scan matrix to get initial state
for _ in 0..10 {
button_matrix.scan_matrix(&mut delay);
}
// Check if first key is pressed while power on. If yes then enter bootloader
if button_matrix.buttons_pressed()[0] {
status_led.update(StatusMode::Bootloader);
let gpio_activity_pin_mask: u32 = 0;
let disable_interface_mask: u32 = 0;
rp2040_hal::rom_data::reset_to_usb_boot(gpio_activity_pin_mask, disable_interface_mask);
}
status_led.update(StatusMode::Normal);
loop {
// if status_led_count_down.wait().is_ok() {
// update_status_led(&mut status_led, &caps_lock_active, &gui_lock_state);
// }
if usb_hid_report_count_down.wait().is_ok() {
let pressed_keys = button_matrix.buttons_pressed();
fn_mode = get_fn_mode(pressed_keys);
for (index, key) in pressed_keys.iter().enumerate() {
buttons[index].pressed = *key;
}
match joystick
.device()
.write_report(&get_joy_report(&mut buttons, fn_mode))
{
Err(UsbHidError::WouldBlock) => {}
Err(UsbHidError::SerializationError) => {
status_led.update(StatusMode::Bootloader);
}
Err(UsbHidError::UsbError(UsbError::BufferOverflow)) => {
status_led.update(StatusMode::Bootloader);
}
Ok(_) => {}
Err(e) => {
status_led.update(StatusMode::Error);
core::panic!("Failed to write joystick report: {:?}", e)
}
};
}
if usb_tick_count_down.wait().is_ok() {
button_matrix.scan_matrix(&mut delay);
}
if usb_dev.poll(&mut [&mut joystick]) {}
}
}
/// Update status LED colour based on function layer and capslock
///
/// Normal = green (NORMAL)
/// GUI lock = blue (GUI LOCK)
/// Capslock active = flashing red (WARNING)
/// Error = steady red (ERROR)
///
/// # Arguments
/// * `status_led` - Reference to status LED
/// * `caps_lock_active` - Is capslock active
fn update_status_led<P, SM, I>(
status_led: &mut Ws2812StatusLed<P, SM, I>,
caps_lock_active: &bool,
gui_lock_state: &u8,
) where
P: PIOExt + FunctionConfig,
I: PinId,
Function<P>: ValidPinMode<I>,
SM: StateMachineIndex,
{
if *caps_lock_active {
status_led.update(StatusMode::Warning);
} else if *gui_lock_state != 0 {
status_led.update(StatusMode::Activity);
} else {
status_led.update(StatusMode::Normal);
}
}
/// Get current Fn mode (0, 1, 2 or 3)
/// layout::FN_BUTTONS contains the button types
///
/// # Arguments
///
/// * `pressed_keys` - Array of pressed keys
fn get_fn_mode(pressed_keys: [bool; NUMBER_OF_KEYS]) -> u8 {
// Check how many Fn keys are pressed
let mut fn_mode: u8 = 0;
let mut fn_l_active: bool = false;
let mut fn_r_active: bool = false;
for (index, key) in pressed_keys.iter().enumerate() {
if *key && layout::MAP[0][index] == layout::ButtonType::FnL {
fn_l_active = true;
}
if *key && layout::MAP[0][index] == layout::ButtonType::FnR {
fn_r_active = true;
}
}
if fn_l_active && fn_r_active {
fn_mode = 3;
} else if fn_l_active {
fn_mode = 2;
} else if fn_r_active {
fn_mode = 1;
}
fn_mode
}
/// Generate keyboard report based on pressed keys and Fn mode (0, 1 or 2)
/// layout::MAP contains the keycodes for each key in each Fn mode
///
/// # Arguments
///
/// * `matrix_keys` - Array of pressed keys
/// * `fn_mode` - Current function layer
fn get_joy_report(
matrix_keys: &mut [KeyboardButton; NUMBER_OF_KEYS],
fn_mode: u8,
) -> JoystickReport {
let mut x: u16 = 0x03ff;
let mut y: u16 = 0x03ff;
let mut z: u16 = 0x03ff;
let mut rx: u16 = 0x03ff;
let mut ry: u16 = 0x03ff;
let mut rz: u16 = 0x03ff;
let mut buttons: u32 = 0;
let mut hat1: u8 = 0xf;
let mut hat2: u8 = 0xf;
let mut hat3: u8 = 0xf;
let mut hat4: u8 = 0xf;
// Filter report based on Fn mode and pressed keys
for (index, key) in matrix_keys.iter_mut().enumerate() {
// Set fn mode for the pressed button
if key.pressed != key.previous_pressed && key.pressed {
key.fn_mode = fn_mode;
}
key.previous_pressed = key.pressed;
// Skip key if defined as NoEventIndicated
if layout::MAP[key.fn_mode as usize][index] == layout::ButtonType::NotConnected {
continue;
}
// Update button state
if key.pressed
&& layout::MAP[fn_mode as usize][index] as usize <= layout::ButtonType::B20 as usize
{
buttons |= 1 << layout::MAP[fn_mode as usize][index] as usize;
}
// Update hat state
if key.pressed
&& layout::MAP[fn_mode as usize][index] as usize >= layout::ButtonType::Hat1U as usize
&& layout::MAP[fn_mode as usize][index] as usize <= layout::ButtonType::Hat4D as usize
{
match layout::MAP[fn_mode as usize][index] {
layout::ButtonType::Hat1U => hat1 = 0,
layout::ButtonType::Hat1R => hat1 = 2,
layout::ButtonType::Hat1D => hat1 = 4,
layout::ButtonType::Hat1L => hat1 = 6,
layout::ButtonType::Hat2U => hat2 = 0,
layout::ButtonType::Hat2R => hat2 = 2,
layout::ButtonType::Hat2D => hat2 = 4,
layout::ButtonType::Hat2L => hat2 = 6,
layout::ButtonType::Hat3U => hat3 = 0,
layout::ButtonType::Hat3R => hat3 = 2,
layout::ButtonType::Hat3D => hat3 = 4,
layout::ButtonType::Hat3L => hat3 = 6,
layout::ButtonType::Hat4U => hat4 = 0,
layout::ButtonType::Hat4R => hat4 = 2,
layout::ButtonType::Hat4D => hat4 = 4,
layout::ButtonType::Hat4L => hat4 = 6,
_ => {}
}
}
}
JoystickReport {
x,
y,
z,
rx,
ry,
rz,
hat1,
hat2,
hat3,
hat4,
buttons,
}
}

130
rp2040/src/status_led.rs Normal file
View File

@ -0,0 +1,130 @@
//! Project: CMtec CMDR Keyboard 42
//! Date: 2023-07-01
//! Author: Christoffer Martinsson
//! Email: cm@cmtec.se
//! License: Please refer to LICENSE in root directory
use rp2040_hal::{
gpio::{Function, FunctionConfig, Pin, PinId, ValidPinMode},
pio::{PIOExt, StateMachineIndex, UninitStateMachine, PIO},
};
use smart_leds::{SmartLedsWrite, RGB8};
use ws2812_pio::Ws2812Direct;
/// Status LED modes
///
/// * OFF = Syatem offline
/// * NORMAL = All system Ok
/// * ACTIVITY = System activity
/// * OTHER = Other activity
/// * WARNING = Warning
/// * ERROR = Error
/// * BOOTLOADER = Bootloader active
#[allow(dead_code)]
#[derive(PartialEq, Eq, Copy, Clone)]
pub enum StatusMode {
Off = 0,
Normal = 1,
Activity = 2,
Other = 3,
Warning = 4,
Error = 5,
Bootloader = 6,
}
#[warn(dead_code)]
/// Status LED driver
/// This driver uses the PIO state machine to drive a WS2812 LED
///
/// # Example
///
/// ```
/// let mut status_led = Ws2812StatusLed::new(
/// pins.neopixel.into_mode(),
/// &mut pio,
/// sm0,
/// clocks.peripheral_clock.freq(),
/// );
/// ```
pub struct Ws2812StatusLed<P, SM, I>
where
I: PinId,
P: PIOExt + FunctionConfig,
Function<P>: ValidPinMode<I>,
SM: StateMachineIndex,
{
ws2812_direct: Ws2812Direct<P, SM, I>,
state: bool,
}
impl<P, SM, I> Ws2812StatusLed<P, SM, I>
where
I: PinId,
P: PIOExt + FunctionConfig,
Function<P>: ValidPinMode<I>,
SM: StateMachineIndex,
{
/// Creates a new instance of this driver.
///
/// # Arguments
///
/// * `pin` - PIO pin
/// * `pio` - PIO instance
/// * `sm` - PIO state machine
/// * `clock_freq` - PIO clock frequency
pub fn new(
pin: Pin<I, Function<P>>,
pio: &mut PIO<P>,
sm: UninitStateMachine<(P, SM)>,
clock_freq: fugit::HertzU32,
) -> Self {
// prepare the PIO program
let ws2812_direct = Ws2812Direct::new(pin, pio, sm, clock_freq);
let state = false;
Self {
ws2812_direct,
state,
}
}
/// Update status LED
/// Depending on the mode, the LED will be set to a different colour
///
/// * OFF = off
/// * NORMAL = green
/// * ACTIVITY = blue
/// * OTHER = orange
/// * WARNING = red (flashing)
/// * ERROR = red
/// * BOOTLOADER = purple
///
/// Make sure to call this function regularly to keep the LED flashing
pub fn update(&mut self, mode: StatusMode) {
let colors: [RGB8; 7] = [
(0, 0, 0).into(), // Off
(10, 7, 0).into(), // Green
(10, 4, 10).into(), // Blue
(5, 10, 0).into(), // Orange
(2, 20, 0).into(), // Red
(2, 20, 0).into(), // Red
(0, 10, 10).into(), // Purple
];
if mode == StatusMode::Warning && !self.state {
self.ws2812_direct
.write([colors[mode as usize]].iter().copied())
.unwrap();
self.state = true;
} else if mode == StatusMode::Warning || mode == StatusMode::Off {
self.ws2812_direct
.write([colors[0]].iter().copied())
.unwrap();
self.state = false;
} else {
self.ws2812_direct
.write([colors[mode as usize]].iter().copied())
.unwrap();
self.state = true;
}
}
}

View File

@ -0,0 +1,206 @@
//!HID joystick
use core::default::Default;
use fugit::ExtU32;
use usb_device::bus::UsbBus;
use usb_device::class_prelude::UsbBusAllocator;
use usbd_human_interface_device::usb_class::prelude::*;
// Fetched from https://github.com/embassy-rs/embassy/blob/e3efda2249640e0b4881289aa609c96a26a7479a/embassy-hal-common/src/fmt.rs
#[cfg(feature = "defmt")]
macro_rules! unwrap {
($($x:tt)*) => {
::defmt::unwrap!($($x)*)
};
}
#[cfg(not(feature = "defmt"))]
macro_rules! unwrap {
($arg:expr) => {
match $crate::usb_joystick_device::Try::into_result($arg) {
::core::result::Result::Ok(t) => t,
::core::result::Result::Err(e) => {
::core::panic!("unwrap of `{}` failed: {:?}", ::core::stringify!($arg), e);
}
}
};
($arg:expr, $($msg:expr),+ $(,)? ) => {
match $crate::usb_joystick_device::Try::into_result($arg) {
::core::result::Result::Ok(t) => t,
::core::result::Result::Err(e) => {
::core::panic!("unwrap of `{}` failed: {}: {:?}", ::core::stringify!($arg), ::core::format_args!($($msg,)*), e);
}
}
}
}
#[derive(Debug, Copy, Clone, Eq, PartialEq)]
pub struct NoneError;
pub trait Try {
type Ok;
type Error;
fn into_result(self) -> Result<Self::Ok, Self::Error>;
}
impl<T> Try for Option<T> {
type Ok = T;
type Error = NoneError;
#[inline]
fn into_result(self) -> Result<T, NoneError> {
self.ok_or(NoneError)
}
}
impl<T, E> Try for Result<T, E> {
type Ok = T;
type Error = E;
#[inline]
fn into_result(self) -> Self {
self
}
}
// Based on example device from https://github.com/dlkj/usbd-human-interface-device/blob/main/src/device/joystick.rs
// Updated to 6pc 12bit axis, 20pc buttons and 4pc hat switches
#[rustfmt::skip]
pub const JOYSTICK_DESCRIPTOR: &[u8] = &[
0x05, 0x01, // Usage Page (Generic Desktop)
0x09, 0x04, // Usage (Joystick)
0xa1, 0x01, // Collection (Application)
0x09, 0x01, // Usage Page (Pointer)
0xa1, 0x00, // Collection (Physical)
0x09, 0x30, // Usage (X)
0x09, 0x31, // Usage (Y)
0x09, 0x32, // Usage (Z)
0x09, 0x33, // Usage (RX)
0x09, 0x34, // Usage (RY)
0x09, 0x35, // Usage (RZ)
0x15, 0x00, // Logical Minimum (0)
0x26, 0xFF, 0x0F, // Logical Maximum (4095)
0x75, 0x0C, // Report Size (12)
0x95, 0x06, // Report count (6)
0x81, 0x02, // Input (Data, Variable, Absolute)
0xc0, // End Collection
0x05, 0x09, // Usage Page (Button)
0x19, 0x01, // Usage Minimum (1)
0x29, 0x10, // Usage Maximum (16)
0x15, 0x00, // Logical Minimum (0)
0x25, 0x01, // Logical Maximum (1)
0x75, 0x01, // Report Size (1)
0x95, 0x14, // Report Count (20)
0x81, 0x02, // Input (Data, Variable, Absolute)
0x75, 0x01, // Report Size (1) PADDING
0x95, 0x04, // Report Count (4) PADDING
0x81, 0x03, // Input (Const, Variable, Absolute) PADDING
0x15, 0x00, // Logical Minimum (0)
0x25, 0x07, // Logical Maximum (7)
0x35, 0x00, // Physical Minimum (0)
0x46, 0x3B, 0x01, // Physical Maximum (315)
0x75, 0x04, // Report Size (4)
0x95, 0x04, // Report Count (4)
0x65, 0x14, // Unit (20)
0x05, 0x01, // Usage Page (Generic Desktop)
0x09, 0x39, // Usage (Hat switch)
0x09, 0x39, // Usage (Hat switch)
0x09, 0x39, // Usage (Hat switch)
0x09, 0x39, // Usage (Hat switch)
0x81, 0x42, // Input (variable,absolute,null_state)
0xc0, // End Collection
];
#[derive(Clone, Copy, Debug, Eq, PartialEq, Default)]
pub struct JoystickReport {
pub x: u16, // 12bit
pub y: u16, // 12bit
pub z: u16, // 12bit
pub rx: u16, // 12bit
pub ry: u16, // 12bit
pub rz: u16, // 12bit
pub buttons: u32, // 20bit
pub hat1: u8, // 4bit
pub hat2: u8, // 4bit
pub hat3: u8, // 4bit
pub hat4: u8, // 4bit
}
pub struct Joystick<'a, B: UsbBus> {
interface: Interface<'a, B, InBytes16, OutNone, ReportSingle>,
}
impl<'a, B: UsbBus> Joystick<'a, B> {
pub fn write_report(&mut self, report: &JoystickReport) -> Result<(), UsbHidError> {
let mut data: [u8; 14] = [0; 14];
// Did not make the packed struct work, so doing it manually
data[0] = report.x as u8;
data[1] = ((report.x >> 8) as u8) | ((report.y << 4) as u8);
data[2] = (report.y >> 4) as u8;
data[3] = report.z as u8;
data[4] = ((report.z >> 8) as u8) | ((report.rx << 4) as u8);
data[5] = (report.rx >> 4) as u8;
data[6] = report.ry as u8;
data[7] = ((report.ry >> 8) as u8) | ((report.rz << 4) as u8);
data[8] = (report.rz >> 4) as u8;
data[9] = report.buttons as u8;
data[10] = (report.buttons >> 8) as u8;
data[11] = (report.buttons >> 16) as u8;
data[12] = (report.hat1) | (report.hat2 << 4);
data[13] = (report.hat3) | (report.hat4 << 4);
self.interface
.write_report(&data)
.map(|_| ())
.map_err(UsbHidError::from)
}
}
impl<'a, B: UsbBus> DeviceClass<'a> for Joystick<'a, B> {
type I = Interface<'a, B, InBytes16, OutNone, ReportSingle>;
fn interface(&mut self) -> &mut Self::I {
&mut self.interface
}
fn reset(&mut self) {}
fn tick(&mut self) -> Result<(), UsbHidError> {
Ok(())
}
}
pub struct JoystickConfig<'a> {
interface: InterfaceConfig<'a, InBytes16, OutNone, ReportSingle>,
}
impl<'a> Default for JoystickConfig<'a> {
#[must_use]
fn default() -> Self {
Self::new(
unwrap!(unwrap!(InterfaceBuilder::new(JOYSTICK_DESCRIPTOR))
.boot_device(InterfaceProtocol::None)
.description("Joystick")
.in_endpoint(10.millis()))
.without_out_endpoint()
.build(),
)
}
}
impl<'a> JoystickConfig<'a> {
#[must_use]
pub fn new(interface: InterfaceConfig<'a, InBytes16, OutNone, ReportSingle>) -> Self {
Self { interface }
}
}
impl<'a, B: UsbBus + 'a> UsbAllocatable<'a, B> for JoystickConfig<'a> {
type Allocated = Joystick<'a, B>;
fn allocate(self, usb_alloc: &'a UsbBusAllocator<B>) -> Self::Allocated {
Self::Allocated {
interface: Interface::new(usb_alloc, self.interface),
}
}
}