This commit is contained in:
weebrobot
2025-06-26 13:34:31 -06:00
parent 7ac52dde74
commit b2149e4454
59 changed files with 21437 additions and 161 deletions

3
.gitmodules vendored
View File

@@ -37,3 +37,6 @@
[submodule "Firmware/ESP32/components/libfixmath/libfixmath"]
path = Firmware/ESP32/components/libfixmath/libfixmath
url = https://github.com/PetteriAimonen/libfixmath.git
[submodule "Firmware/pico/external/lwip"]
path = Firmware/pico/external/lwip
url = https://github.com/lwip-tcpip/lwip.git

View File

@@ -6,7 +6,7 @@
"cortex-debug.objdumpPath": "/usr/bin/arm-none-eabi-objdump",
"cortex-debug.nmPath": "/usr/bin/arm-none-eabi-nm",
"cmake.configureArgs": [
"-DOGXMINI_BOARD=PI_PICO_W",
"-DOGXMINI_BOARD=DEVKIT",
],
"files.associations": {
"device_private.h": "c",
@@ -95,7 +95,18 @@
"master.h": "c",
"i2c_slave.h": "c",
"callbacks.h": "c",
"gpio.h": "c"
"gpio.h": "c",
"sync.h": "c",
"lwip_nosys.h": "c",
"lwip_freertos.h": "c",
"dhserver.h": "c",
"debug.h": "c",
"httpd.h": "c",
"etharp.h": "c",
"unique_id.h": "c",
"net_device.h": "c",
"ethernet.h": "c",
"rndis_def.h": "c"
},
"idf.port": "/dev/ttyUSB0",
}

View File

@@ -22,10 +22,16 @@ include(${CMAKE_CURRENT_LIST_DIR}/boards/${OGXMINI_BOARD}.cmake)
include(${CMAKE_CURRENT_LIST_DIR}/pico_sdk_import.cmake)
include($ENV{PICO_SDK_PATH}/pico_sdk_init.cmake)
set(PICO_PIO_USB_PATH ${EXTERNAL_DIR}/Pico-PIO-USB)
set(PICO_TINYUSB_PATH ${EXTERNAL_DIR}/tinyusb)
set(BLUEPAD32_PATH ${EXTERNAL_DIR}/bluepad32)
set(PICO_BTSTACK_PATH ${EXTERNAL_DIR}/bluepad32/external/btstack)
set(PICO_PIO_USB_PATH ${EXTERNAL_DIR}/Pico-PIO-USB)
set(PICO_TINYUSB_PATH ${EXTERNAL_DIR}/tinyusb)
set(BLUEPAD32_PATH ${EXTERNAL_DIR}/bluepad32)
set(PICO_BTSTACK_PATH ${EXTERNAL_DIR}/bluepad32/external/btstack)
set(LWIP_DIR ${EXTERNAL_DIR}/lwip)
set(LWIP_INCLUDE_DIRS
${LWIP_DIR}/src/include
${SRC}/webserver/lwip
)
project(${FW_NAME} C CXX ASM)
@@ -35,6 +41,8 @@ add_subdirectory(${EXTERNAL_DIR}/pico_usb)
add_subdirectory(${EXTERNAL_DIR}/libxsm3)
add_subdirectory(${EXTERNAL_DIR}/g726)
add_subdirectory(${EXTERNAL_DIR}/libfixmath libfixmath)
add_subdirectory(${EXTERNAL_DIR}/fatfs)
include(${LWIP_DIR}/src/Filelists.cmake)
add_executable(${FW_NAME}
${SRC}/main_standard.c
@@ -51,6 +59,8 @@ add_executable(${FW_NAME}
${SRC}/settings/settings.cpp
${SRC}/sdcard/sdcard.c
${SRC}/sdcard/sd_spi.c
${SRC}/sdcard/fatfs_io.c
${SRC}/led/led.cpp
${SRC}/led/neopixel/WS2812.cpp
@@ -69,6 +79,8 @@ add_executable(${FW_NAME}
${SRC}/usb/device/drivers/psclassic.c
${SRC}/usb/device/drivers/uart_bridge.c
${SRC}/usb/device/drivers/webapp.c
${SRC}/usb/device/drivers/net.c
${SRC}/usb/device/drivers/rndis/rndis.c
${SRC}/usb/host/host.c
${SRC}/usb/host/drivers/xboxog_gp.c
@@ -95,11 +107,19 @@ add_executable(${FW_NAME}
${SRC}/four_channel/master.c
${SRC}/four_channel/slave.c
${SRC}/webserver/webserver.c
${SRC}/webserver/lwip/sys.c
${SRC}/webserver/networking/dhserver.c
${SRC}/webserver/networking/dnserver.c
# ${SRC}/webserver/networking/rndis_reports.c
)
target_include_directories(${FW_NAME}
PRIVATE
${SRC}
${SRC}/webserver/networking/
${LWIP_INCLUDE_DIRS}
)
target_link_libraries(${FW_NAME}
@@ -108,6 +128,8 @@ target_link_libraries(${FW_NAME}
pico_multicore
pico_rand
pico_i2c_slave
# pico_lwip
# pico_lwip_arch
hardware_pio
hardware_sync
hardware_gpio
@@ -120,9 +142,13 @@ target_link_libraries(${FW_NAME}
libxsm3
g726
libfixmath
fatfs
tinyusb_board
tinyusb_host
tinyusb_pico_pio_usb
lwipcore
lwipallapps
)
target_compile_definitions(${FW_NAME}

View File

@@ -26,6 +26,13 @@ set(ESP32_SPI_PIN_MISO 12)
set(ESP32_SPI_PIN_CS 13)
set(ESP32_SPI_PIN_IRQ 7)
set(SD_CARD_ENABLED 1)
set(SD_CARD_SPI_NUM 0)
set(SD_CARD_SPI_PIN_SCK 2)
set(SD_CARD_SPI_PIN_MOSI 3)
set(SD_CARD_SPI_PIN_MISO 4)
set(SD_CARD_SPI_PIN_CS 5)
set(OGXM_BOARD OGXM_BOARD_DEVKIT)
set(PICO_DEFAULT_UART 0)

View File

@@ -4,7 +4,7 @@ project(fatfs)
set(SRC_DIR ${CMAKE_CURRENT_LIST_DIR}/ff15a/source)
add_library(fatfs STATIC
${SRC_DIR}/diskio.c
# ${SRC_DIR}/diskio.c
${SRC_DIR}/ff.c
${SRC_DIR}/ffsystem.c
${SRC_DIR}/ffunicode.c

1
Firmware/pico/external/lwip vendored Submodule

View File

@@ -1,6 +1,6 @@
#pragma once
#define BUILD_DATETIME "2025-06-18 08:44:57"
#define BUILD_DATETIME "2025-06-26 13:30:51"
#define BUILD_VERSION "1.0.0a4"
#define VERIFY_BUILD_VERSION 0
#define OGXM_LOG_ENABLED 1
@@ -8,8 +8,8 @@
#define GAMEPADS_MAX 1
#define LED_ENABLED 0
#define LED_PIN
#define LED_ENABLED 1
#define LED_PIN 25
#define NEOPIXEL_ENABLED 0
#define NEOPIXEL_FORMAT_RGB 0
@@ -20,43 +20,43 @@
#define NEOPIXEL_VCC_ENABLED 0
#define NEOPIXEL_VCC_ENABLE_PIN
#define UART_BRIDGE_ENABLED 0
#define UART_BRIDGE_UART_NUM
#define UART_BRIDGE_PIN_TX
#define UART_BRIDGE_PIN_RX
#define UART_BRIDGE_PIN_BOOT
#define UART_BRIDGE_PIN_RESET
#define UART_BRIDGE_ENABLED 1
#define UART_BRIDGE_UART_NUM 1
#define UART_BRIDGE_PIN_TX 8
#define UART_BRIDGE_PIN_RX 9
#define UART_BRIDGE_PIN_BOOT 22
#define UART_BRIDGE_PIN_RESET 6
#define USBH_ENABLED 0
#define USBH_PIO_ENABLED 0
#define USBH_PIO_DP_PIN
#define USBH_ENABLED 1
#define USBH_PIO_ENABLED 1
#define USBH_PIO_DP_PIN 18
#define USBH_VCC_ENABLED 0
#define USBH_VCC_ENABLE_PIN
#define USBD_PIO_ENABLED 0
#define USBD_PIO_USB_DP_PIN
#define USBD_PIO_ENABLED 1
#define USBD_PIO_USB_DP_PIN 0
#define TS3USB221_ENABLED 0
#define TS3USB221_PIN_MUX_OE
#define TS3USB221_PIN_MUX_SEL
#define TS3USB221_ENABLED 1
#define TS3USB221_PIN_MUX_OE 20
#define TS3USB221_PIN_MUX_SEL 21
#define BLUETOOTH_ENABLED 1
#define BLUETOOTH_ENABLED 0
#define BLUETOOTH_HARDWARE_PICOW 0
#define BLUETOOTH_HARDWARE_ESP32_I2C 1
#define BLUETOOTH_HARDWARE_ESP32_SPI 2
#define BLUETOOTH_HARDWARE BLUETOOTH_HARDWARE_PICOW
#define BLUETOOTH_HARDWARE 0
#define ESP32_I2C_NUM
#define ESP32_I2C_PIN_SDA
#define ESP32_I2C_PIN_SCL
#define ESP32_I2C_PIN_IRQ
#define ESP32_SPI_NUM
#define ESP32_SPI_PIN_MOSI
#define ESP32_SPI_PIN_MISO
#define ESP32_SPI_PIN_SCK
#define ESP32_SPI_PIN_CS
#define ESP32_SPI_PIN_IRQ
#define ESP32_SPI_NUM 1
#define ESP32_SPI_PIN_MOSI 11
#define ESP32_SPI_PIN_MISO 12
#define ESP32_SPI_PIN_SCK 10
#define ESP32_SPI_PIN_CS 13
#define ESP32_SPI_PIN_IRQ 7
#define ESP32_RESET_PIN UART_BRIDGE_PIN_RESET
@@ -69,12 +69,12 @@
#define FOUR_CHANNEL_PIN_SLAVE_1
#define FOUR_CHANNEL_PIN_SLAVE_2
#define SD_CARD_ENABLED 0
#define SD_CARD_ENABLED 1
#define SD_CARD_SPI_NUM 0
#define SD_CARD_SPI_PIN_SCK 0
#define SD_CARD_SPI_PIN_MOSI 0
#define SD_CARD_SPI_PIN_MISO 0
#define SD_CARD_SPI_PIN_CS 0
#define SD_CARD_SPI_PIN_SCK 2
#define SD_CARD_SPI_PIN_MOSI 3
#define SD_CARD_SPI_PIN_MISO 4
#define SD_CARD_SPI_PIN_CS 5
#define OGXM_BOARD_STANDARD 1
#define OGXM_BOARD_BLUETOOTH 2
@@ -82,7 +82,7 @@
#define OGXM_BOARD_DEVKIT_ESP32 4
#define OGXM_BOARD_4CHANNEL 5
#define OGXM_BOARD_BLUETOOTH_USBH 6
#define OGXM_BOARD OGXM_BOARD_BLUETOOTH
#define OGXM_BOARD OGXM_BOARD_DEVKIT
#if (((OGXM_BOARD != OGXM_BOARD_DEVKIT) && (OGXM_BOARD != OGXM_BOARD_DEVKIT_ESP32)) \
&& USBH_PIO_ENABLED && USBD_PIO_ENABLED)

View File

@@ -41,12 +41,13 @@ void core1_entry(void) {
int main(void) {
set_sys_clock_khz(240000, true);
ogxm_log_init(true);
settings_init();
// settings_init();
// core1_entry();
// usbd_type_t device_type = settings_get_device_type();
usbd_type_t device_type = USBD_TYPE_XINPUT;
// usbd_type_t device_type = USBD_TYPE_XINPUT;
usbd_type_t device_type = USBD_TYPE_WEBAPP;
usb_device_config_t usbd_config = {
.multithread = true,
.count = 1,
@@ -60,22 +61,51 @@ int main(void) {
.audio_cb = usb_host_set_audio,
};
multicore_reset_core1();
multicore_launch_core1(core1_entry);
// multicore_reset_core1();
// multicore_launch_core1(core1_entry);
usb_device_configure(&usbd_config);
usb_device_connect();
check_pad_timer_set_enabled(true);
// check_pad_timer_set_enabled(true);
while (true) {
usb_device_task();
sleep_ms(1);
// sleep_ms(1);
if (check_pad_time()) {
check_pad_for_driver_change(0, device_type);
}
// if (check_pad_time()) {
// check_pad_for_driver_change(0, device_type);
// }
}
}
// #include "sdcard/sd_spi.h"
// int main(void) {
// set_sys_clock_khz(240000, true);
// ogxm_log_init(true);
// sd_error_t err = sd_spi_init();
// if (err != SD_ERR_OKAY) {
// ogxm_loge("SD card initialization failed: %d\n", err);
// return -1;
// }
// ogxm_logi("SD card initialized successfully\n");
// uint32_t block_count = 0;
// err = sd_spi_get_block_count(&block_count);
// if (err != SD_ERR_OKAY) {
// ogxm_loge("Failed to get block count: %d\n", err);
// return -1;
// }
// ogxm_logi("SD card block count: %u\n", block_count);
// while (true) {
// // usb_device_task();
// sleep_ms(1);
// // if (check_pad_time()) {
// // check_pad_for_driver_change(0, device_type);
// // }
// }
// }
#endif // (OGXM_BOARD == OGXM_BOARD_DEVKIT)

View File

@@ -2,6 +2,10 @@
#include "ring/ring_usb.h"
#ifdef __cplusplus
extern "C" {
#endif
typedef enum {
RING_BT_TYPE_NONE = 0,
RING_BT_TYPE_PAD,
@@ -17,4 +21,8 @@ typedef ring_usb_packet_t ring_bluetooth_packet_t;
#define ring_bluetooth_push ring_usb_push
#define ring_bluetooth_pop ring_usb_pop
#define ring_bluetooth_empty ring_usb_empty
#define ring_bluetooth_empty ring_usb_empty
#ifdef __cplusplus
}
#endif

View File

@@ -1 +1,52 @@
#include <stdint.h>
// #include <stdint.h>
// #include "ff.h"
// #include "diskio.h"
// #include "sdcard/sdcard.h"
// #define DEV_RAM 0 /* Example: Map Ramdisk to physical drive 0 */
// #define DEV_MMC 1 /* Example: Map MMC/SD card to physical drive 1 */
// #define DEV_USB 2 /* Example: Map USB MSD to physical drive 2 */
// DSTATUS disk_initialize(BYTE pdrv) {
// switch (pdrv) {
// case DEV_RAM:
// return STA_NODISK;
// case DEV_MMC:
// if (sdcard_init()) {
// return 0;
// }
// break;
// case DEV_USB:
// return STA_NODISK;
// }
// return STA_NOINIT;
// }
// DSTATUS disk_status(BYTE pdrv) {
// DSTATUS stat;
// int result;
// switch (pdrv) {
// case DEV_RAM :
// result = RAM_disk_status();
// // translate the reslut code here
// return stat;
// case DEV_MMC :
// result = MMC_disk_status();
// // translate the reslut code here
// return stat;
// case DEV_USB :
// result = USB_disk_status();
// // translate the reslut code here
// return stat;
// }
// return STA_NOINIT;
// }

View File

@@ -0,0 +1,389 @@
#include "board_config.h"
#if SD_CARD_ENABLED
#include <string.h>
#include <pico/stdlib.h>
#include <hardware/spi.h>
#include <hardware/gpio.h>
#include <pico/sync.h>
#include "sd_spi.h"
typedef enum {
CMDO_GO_IDLE_STATE = 0,
CMD2_ALL_SEND_CID = 2,
CMD3_SEND_RELATIVE_ADDR = 3,
CMD4_SET_DSR = 4,
// Reserved for DSIO, I/O cards
CMD7_SELECT_DESELECT_CARD = 7,
CMD8_SEND_IF_COND = 8,
CMD9_SEND_CSD = 9,
CMD10_SEND_CID = 10,
CMD11_VOLTAGE_SWITCH = 11,
CMD12_STOP_TRANSMISSION = 12,
CMD13_SEND_STATUS = 13,
CMD15_GO_INACTIVE_STATE = 15,
CMD16_SET_BLOCKLEN = 16,
CMD17_READ_SINGLE_BLOCK = 17,
CMD18_READ_MULTIPLE_BLOCK = 18,
CMD19_SEND_TUNING_BLOCK = 19,
CMD20_SPEED_CLASS_CONTROL = 20,
CMD22_ADDRESS_EXTENSION = 22,
CMD23_SET_BLOCK_COUNT = 23,
CMD24_WRITE_BLOCK = 24,
CMD25_WRITE_MULTIPLE_BLOCK = 25,
CMD27_PROGRAM_CSD = 27,
CMD28_SET_WRITE_PROT = 28,
CMD29_CLR_WRITE_PROT = 29,
CMD30_SEND_WRITE_PROT = 30,
CMD32_ERASE_WR_BLK_START = 32,
CMD33_ERASE_WR_BLK_END = 33,
CMD38_ERASE = 38,
CMD43_Q_MANAGEMENT = 43,
CMD44_Q_TASK_INFO_A = 44,
CMD45_Q_TASK_INFO_B = 45,
CMD46_Q_RD_TASK = 46,
CMD47_Q_WR_TASK = 47,
CMD48_READ_EXTR_SINGLE = 48,
CMD49_WRITE_EXTR_SINGLE = 49,
CMD55_APP_CMD = 55,
CMD56_GEN_CMD = 56,
CMD58_READ_EXTR_MULTI = 58,
CMD59_WRITE_EXTR_MULTI = 59,
// SDIO commands
} sd_cmd_t;
typedef enum {
ACMD6_SET_BUS_WIDTH = 6,
ACMD13_SD_STATUS = 13,
ACMD22_SEND_NUM_WR_BLOCKS = 22,
ACMD23_SET_WR_BLK_ERASE_COUNT = 23,
ACMD41_SD_SEND_OP_COND = 41,
ACMD42_SET_CLR_CARD_DETECT = 42,
ACMD51_SEND_SCR = 51,
} sd_acmd_t;
#define SPI_HW __CONCAT(spi, SD_CARD_SPI_NUM)
#define SPI_BAUDRATE (1000U*1000U) // 1 MHz
#define SD_SPI_ASSERT() gpio_put(SD_CARD_SPI_PIN_CS, 0)
#define SD_SPI_DEASSERT() gpio_put(SD_CARD_SPI_PIN_CS, 1)
typedef struct {
bool inited;
bool card_present;
} sd_spi_state_t;
static sd_spi_state_t sd_spi_state = {0};
static uint8_t sd_spi_xfer(uint8_t data) {
uint8_t rx;
spi_write_read_blocking(SPI_HW, &data, &rx, 1);
return rx;
}
static uint8_t sd_spi_send_cmd(uint8_t cmd, uint32_t arg, uint8_t crc) {
sd_spi_xfer(0xFF);
sd_spi_xfer(0x40 | cmd);
sd_spi_xfer(arg >> 24);
sd_spi_xfer(arg >> 16);
sd_spi_xfer(arg >> 8);
sd_spi_xfer(arg);
sd_spi_xfer(crc);
// Wait for response (response is not 0xFF)
for (int i = 0; i < 8; i++) {
uint8_t resp = sd_spi_xfer(0xFF);
if ((resp & 0x80) == 0) {
return resp;
}
}
return 0xFF; // Timeout
}
// static bool sd_card_preset(void) {
// SD_SPI_ASSERT();
// uint8_t resp = sd_spi_send_cmd(CMDO_GO_IDLE_STATE, 0, 0x95); // CMD0: GO_IDLE_STATE
// SD_SPI_DEASSERT();
// return (resp == 0x01);
// }
static bool sd_spi_wait_ready(void) {
uint8_t resp = 0;
for (int i = 0; i < 50000; i++) {
if ((resp = sd_spi_xfer(0xFF)) == 0xFF) {
break;
}
}
return (resp == 0xFF);
}
sd_error_t sd_spi_init(void) {
if (sd_spi_state.inited) {
return SD_ERR_OKAY;
}
spi_init(SPI_HW, SPI_BAUDRATE);
spi_set_format(SPI_HW, 8, SPI_CPOL_0, SPI_CPHA_0, SPI_MSB_FIRST);
gpio_set_function(SD_CARD_SPI_PIN_SCK, GPIO_FUNC_SPI);
gpio_set_function(SD_CARD_SPI_PIN_MOSI, GPIO_FUNC_SPI);
gpio_set_function(SD_CARD_SPI_PIN_MISO, GPIO_FUNC_SPI);
gpio_set_function(SD_CARD_SPI_PIN_CS, GPIO_FUNC_SIO);
gpio_set_dir(SD_CARD_SPI_PIN_CS, GPIO_OUT);
SD_SPI_DEASSERT();
// 80+ clock cycles with CS high
for (int i = 0; i < 10; i++) {
sd_spi_xfer(0xFF);
}
SD_SPI_ASSERT();
// CMD0: GO_IDLE_STATE
uint8_t resp = sd_spi_send_cmd(CMDO_GO_IDLE_STATE, 0, 0x95);
SD_SPI_DEASSERT();
if (resp != 0x01) {
sd_spi_state.card_present = false;
return SD_ERR_NO_DISK;
}
// CMD8: SEND_IF_COND (for SDHC/SDXC)
SD_SPI_ASSERT();
resp = sd_spi_send_cmd(CMD8_SEND_IF_COND, 0x1AA, 0x87);
uint8_t cmd8_resp[4];
for (int i = 0; i < 4; i++) {
cmd8_resp[i] = sd_spi_xfer(0xFF);
}
SD_SPI_DEASSERT();
bool sdhc = false;
if (resp == 0x01 && cmd8_resp[2] == 0x01 && cmd8_resp[3] == 0xAA) {
// Card supports SDHC/SDXC
// ACMD41 with HCS
for (int i = 0; i < 1000; i++) {
// CMD55
SD_SPI_ASSERT();
resp = sd_spi_send_cmd(CMD55_APP_CMD, 0, 0x65);
SD_SPI_DEASSERT();
// ACMD41
SD_SPI_ASSERT();
resp = sd_spi_send_cmd(ACMD41_SD_SEND_OP_COND, 0x40000000, 0x77);
SD_SPI_DEASSERT();
if (resp == 0x00) {
sdhc = true;
break;
}
sleep_ms(1);
}
} else {
// Standard capacity card: ACMD41 without HCS
for (int i = 0; i < 1000; i++) {
SD_SPI_ASSERT();
resp = sd_spi_send_cmd(CMD55_APP_CMD, 0, 0x65);
SD_SPI_DEASSERT();
SD_SPI_ASSERT();
resp = sd_spi_send_cmd(ACMD41_SD_SEND_OP_COND, 0, 0x77);
SD_SPI_DEASSERT();
if (resp == 0x00) {
break;
}
sleep_ms(1);
}
}
// Optionally: CMD58 to read OCR and confirm SDHC/SDXC
sd_spi_state.inited = true;
sd_spi_state.card_present = true;
return SD_ERR_OKAY;
}
sd_error_t sd_spi_inited(void) {
if (!sd_spi_state.inited) {
return SD_ERR_NO_INIT;
}
return sd_spi_state.card_present ? SD_ERR_OKAY : SD_ERR_NO_DISK;
}
sd_error_t sd_spi_deinit(void) {
if (!sd_spi_state.inited) {
return SD_ERR_NO_INIT;
}
spi_deinit(SPI_HW);
gpio_deinit(SD_CARD_SPI_PIN_CS);
gpio_deinit(SD_CARD_SPI_PIN_SCK);
gpio_deinit(SD_CARD_SPI_PIN_MOSI);
gpio_deinit(SD_CARD_SPI_PIN_MISO);
sd_spi_state.inited = false;
return SD_ERR_OKAY;
}
sd_error_t sd_spi_read_blocks(uint32_t block, uint8_t *buffer, uint32_t count) {
if (!buffer || (count == 0)) {
return SD_ERR_INVALID_ARG;
}
if (!sd_spi_state.inited) {
return SD_ERR_NO_INIT;
}
if (!sd_spi_state.card_present) {
return SD_ERR_NO_DISK;
}
for (uint32_t i = 0; i < count; i++) {
SD_SPI_ASSERT();
uint8_t resp = sd_spi_send_cmd(CMD17_READ_SINGLE_BLOCK, (block + i) * SD_BLOCK_SIZE, 0xFF); // CMD17: READ_SINGLE_BLOCK
if (resp != 0x00) {
SD_SPI_DEASSERT();
return SD_ERR_READ_WRITE;
}
int tries = 10000;
while (sd_spi_xfer(0xFF) != 0xFE && tries--) {
// Wait for the start token (0xFE)
}
if (tries <= 0) {
return SD_ERR_TIMEOUT;
}
for (uint32_t j = 0; j < SD_BLOCK_SIZE; j++) {
buffer[i * SD_BLOCK_SIZE + j] = sd_spi_xfer(0xFF);
}
sd_spi_xfer(0xFF);
sd_spi_xfer(0xFF);
SD_SPI_DEASSERT();
sd_spi_xfer(0xFF);
}
return SD_ERR_OKAY;
}
sd_error_t sd_spi_write_blocks(uint32_t block, const uint8_t *buffer, uint32_t count) {
if (!buffer || (count == 0)) {
return SD_ERR_INVALID_ARG;
}
if (!sd_spi_state.inited) {
return SD_ERR_NO_INIT;
}
if (!sd_spi_state.card_present) {
return SD_ERR_NO_DISK;
}
for (uint32_t i = 0; i < count; i++) {
SD_SPI_ASSERT();
uint8_t resp = sd_spi_send_cmd(CMD24_WRITE_BLOCK, (block + i) * SD_BLOCK_SIZE, 0x01); // CMD17: READ_SINGLE_BLOCK
if (resp != 0x00) {
SD_SPI_DEASSERT();
return SD_ERR_READ_WRITE;
}
sd_spi_xfer(0xFF); // Ncr
sd_spi_xfer(0xFE); // Data token
for (uint32_t j = 0; j < SD_BLOCK_SIZE; j++) {
sd_spi_xfer(buffer[i * SD_BLOCK_SIZE + j]);
}
sd_spi_xfer(0xFF); // CRC (not used, can be 0xFF)
sd_spi_xfer(0xFF); // CRC (not used, can be 0xFF)
uint8_t resp2 = sd_spi_xfer(0xFF); // Wait for data response
if ((resp2 & 0x1F) != 0x05) { // Check for data accepted response
SD_SPI_DEASSERT();
return SD_ERR_READ_WRITE;
}
if (!sd_spi_wait_ready()) {
SD_SPI_DEASSERT();
return SD_ERR_TIMEOUT;
}
SD_SPI_DEASSERT();
sd_spi_xfer(0xFF);
}
return SD_ERR_OKAY;
}
sd_error_t sd_spi_sync(void) {
if (!sd_spi_state.inited) {
return SD_ERR_NO_INIT;
}
if (!sd_spi_state.card_present) {
return SD_ERR_NO_DISK;
}
SD_SPI_ASSERT();
bool ready = sd_spi_wait_ready();
SD_SPI_DEASSERT();
return ready ? SD_ERR_OKAY : SD_ERR_TIMEOUT;
}
#include "log/log.h"
sd_error_t sd_spi_get_block_count(uint32_t* count) {
if (!count) {
return SD_ERR_INVALID_ARG;
}
if (!sd_spi_state.inited) {
return SD_ERR_NO_INIT;
}
if (!sd_spi_state.card_present) {
return SD_ERR_NO_DISK;
}
// Send CMD9 to get the CSD register
SD_SPI_ASSERT();
uint8_t resp = sd_spi_send_cmd(CMD9_SEND_CSD, 0, 0xFF); // CMD9: SEND_CSD
if (resp != 0x00) {
SD_SPI_DEASSERT();
ogxm_loge("Failed to read CSD register: %02X", resp);
return SD_ERR_READ_WRITE;
}
// *** Wait for data token (0xFE) ***
int tries = 10000;
uint8_t token;
do {
token = sd_spi_xfer(0xFF);
} while (token != 0xFE && --tries);
if (tries <= 0) {
SD_SPI_DEASSERT();
ogxm_loge("Timeout waiting for CSD token\n");
return SD_ERR_TIMEOUT;
}
// Read the CSD register (16 bytes)
uint8_t csd[16];
for (int i = 0; i < 16; i++) {
csd[i] = sd_spi_xfer(0xFF);
}
sd_spi_xfer(0xFF); // CRC (not used, can be 0xFF)
sd_spi_xfer(0xFF); // CRC (not used, can be 0xFF)
SD_SPI_DEASSERT();
uint8_t csd_structure = (csd[0] >> 6) & 0x3;
if (csd_structure == 1) {
// CSD version 2.0 (SDHC/SDXC)
uint32_t c_size = ((uint32_t)(csd[7] & 0x3F) << 16) |
((uint32_t)csd[8] << 8) |
csd[9];
*count = (c_size + 1) * 1024;
ogxm_logd("CSD structure: %u, C_SIZE: %u, Block count: %u\n", csd_structure, c_size, *count);
return SD_ERR_OKAY;
} else if (csd_structure == 0) {
// CSD version 1.0 (SDSC)
uint32_t c_size = ((uint32_t)(csd[6] & 0x03) << 10) |
((uint32_t)csd[7] << 2) |
((csd[8] & 0xC0) >> 6);
uint8_t c_size_mult = ((csd[9] & 0x03) << 1) | ((csd[10] & 0x80) >> 7);
uint8_t read_bl_len = csd[5] & 0x0F;
uint32_t block_len = 1UL << read_bl_len;
uint32_t mult = 1UL << (c_size_mult + 2);
uint32_t blocknr = (c_size + 1) * mult;
*count = (blocknr * block_len) / 512;
ogxm_logd("CSD structure: %u, C_SIZE: %u, C_SIZE_MULT: %u, READ_BL_LEN: %u, Block count: %u\n",
csd_structure, c_size, c_size_mult, read_bl_len, *count);
return SD_ERR_OKAY;
} else {
ogxm_loge("Unknown CSD structure: %u\n", csd_structure);
return SD_ERR_READ_WRITE;
}
}
#endif // SD_CARD_ENABLED

View File

@@ -0,0 +1,38 @@
#pragma once
#include "board_config.h"
#if SD_CARD_ENABLED
#include <stdint.h>
#ifdef __cplusplus
extern "C" {
#endif
/* Don't use directly, use methods in sdcard.h */
#define SD_BLOCK_SIZE 512U
typedef enum {
SD_ERR_OKAY = 0,
SD_ERR_NO_INIT,
SD_ERR_NO_DISK,
SD_ERR_TIMEOUT,
SD_ERR_INVALID_ARG,
SD_ERR_WRITE_PROTECTED,
SD_ERR_READ_WRITE,
} sd_error_t;
sd_error_t sd_spi_init(void);
sd_error_t sd_spi_inited(void);
sd_error_t sd_spi_deinit(void);
sd_error_t sd_spi_read_blocks(uint32_t block, uint8_t *buffer, uint32_t count);
sd_error_t sd_spi_write_blocks(uint32_t block, const uint8_t *buffer, uint32_t count);
sd_error_t sd_spi_sync(void);
sd_error_t sd_spi_get_block_count(uint32_t* count);
#ifdef __cplusplus
}
#endif
#endif // SD_CARD_ENABLED

View File

@@ -1,103 +1,315 @@
#include "sdcard/sdcard.h"
#include "board_config.h"
#if SD_CARD_ENABLED
#include <hardware/spi.h>
#include <hardware/gpio.h>
#include <pico/sync.h>
#include "log/log.h"
#include "sdcard/sd_spi.h"
#include "sdcard/sdcard.h"
// #ifndef SDCARD_SPI
// #define SDCARD_SPI 0
// #endif
#define KILOBYTE (1024U)
#define GIGABYTES(x) ((x) * KILOBYTE * KILOBYTE * KILOBYTE)
#define MEGABYTES(x) ((x) * KILOBYTE * KILOBYTE)
#define KILOBYTES(x) ((x) * KILOBYTE)
// #ifndef SDCARD_SPI_PIN_SCK
// #define SDCARD_SPI_PIN_SCK 2U
// #endif
#define MSC_MINIMUM_PARTITION_BLOCKS (MEGABYTES(32U) / SD_BLOCK_SIZE)
#define MSC_MAXIMUM_PARTITION_BLOCKS (GIGABYTES(4U) / SD_BLOCK_SIZE)
#define MSC_MAX_RATIO_DENOMINATOR 4U // 75%
#define MSC_MAX_RATIO_NUMERATOR 3U // 75%
// #ifndef SDCARD_SPI_PIN_MOSI
// #define SDCARD_SPI_PIN_MOSI 3U
// #endif
#define FATFS_MINIMUM_PARTITION_BLOCKS (MEGABYTES(32U) / SD_BLOCK_SIZE)
// #ifndef SDCARD_SPI_PIN_MISO
// #define SDCARD_SPI_PIN_MISO 4U
// #endif
typedef struct {
volatile bool inited;
mutex_t mutex;
uint32_t block_count;
struct {
uint32_t start_block;
uint32_t blocks;
} partitions[SD_PART_MAX];
} sdcard_state_t;
// #ifndef SDCARD_SPI_PIN_CS
// #define SDCARD_SPI_PIN_CS 5U
// #endif
static sdcard_state_t sdcard = {0};
#define SDCARD_SPI_BAUDRATE 1000U*1000U // 1 MHz
#define SDCARD_ERR 0xFFU
static spi_inst_t* spi = __CONCAT(spi, SDCARD_SPI_NUM);
static volatile bool spi_inited = false;
static bool connected = false;
static mutex_t sd_mutex;
static void sd_xfer_begin(void) {
if (!mutex_is_initialized(&sd_mutex)) {
mutex_init(&sd_mutex);
static inline void sdcard_lock(void) {
if (!mutex_is_initialized(&sdcard.mutex)) {
mutex_init(&sdcard.mutex);
}
mutex_enter_blocking(&sd_mutex);
gpio_put(SDCARD_SPI_PIN_CS, 0);
mutex_enter_blocking(&sdcard.mutex);
}
static void sdcard_xfer_complete(void) {
gpio_put(SDCARD_SPI_PIN_CS, 1);
if (mutex_is_initialized(&sd_mutex)) {
mutex_exit(&sd_mutex);
static inline void sdcard_unlock(void) {
mutex_exit(&sdcard.mutex);
}
/* Private unprotected */
static void sdcard_calculate_partition_sizes(sdcard_state_t* sd) {
sd->partitions[SD_PART_MSC].start_block = 0;
uint32_t msc_blocks =
(sd->block_count / MSC_MAX_RATIO_DENOMINATOR) * MSC_MAX_RATIO_NUMERATOR;
sd->partitions[SD_PART_MSC].blocks = msc_blocks;
if (sd->partitions[SD_PART_MSC].blocks < MSC_MINIMUM_PARTITION_BLOCKS) {
ogxm_logd("SD: MSC partition size too small, setting to minimum");
sd->partitions[SD_PART_MSC].blocks = MSC_MINIMUM_PARTITION_BLOCKS;
} else if (sd->partitions[SD_PART_MSC].blocks > MSC_MAXIMUM_PARTITION_BLOCKS) {
ogxm_logd("SD: MSC partition size too large, setting to maximum");
sd->partitions[SD_PART_MSC].blocks = MSC_MAXIMUM_PARTITION_BLOCKS;
}
sd->partitions[SD_PART_FATFS].start_block =
sd->partitions[SD_PART_MSC].start_block + sd->partitions[SD_PART_MSC].blocks;
sd->partitions[SD_PART_FATFS].blocks =
sd->block_count - sd->partitions[SD_PART_MSC].blocks;
if (sd->partitions[SD_PART_FATFS].blocks < FATFS_MINIMUM_PARTITION_BLOCKS) {
ogxm_logd("SD: FATFS partition size too small, setting to minimum");
sd->partitions[SD_PART_FATFS].blocks = FATFS_MINIMUM_PARTITION_BLOCKS;
}
}
static uint8_t sd_send_cmd(uint8_t cmd, uint32_t arg, uint8_t crc) {
uint8_t buf[6];
buf[0] = 0x40 | cmd;
buf[1] = arg >> 24;
buf[2] = arg >> 16;
buf[3] = arg >> 8;
buf[4] = arg;
buf[5] = crc;
// sdcard_spi_send(buf, 6);
// Wait for response (response is always MSB=0)
for (int i = 0; i < 8; ++i) {
// uint8_t resp = sdcard_spi_xfer(0xFF);
// if (!(resp & 0x80)) {
// return resp;
// }
}
return SDCARD_ERR;
static bool sdcard_format_disk(sdcard_state_t* sd) {
sdcard_calculate_partition_sizes(sd);
uint8_t mbr[SD_BLOCK_SIZE] = {0};
// Partition 1: Pico/FatFs
uint8_t *part1 = &mbr[446];
part1[0] = 0x00; // Not bootable
part1[4] = 0x0C; // FAT32 LBA
part1[8] = (uint8_t)(sd->partitions[SD_PART_FATFS].start_block & 0xFF);
part1[9] = (uint8_t)((sd->partitions[SD_PART_FATFS].start_block >> 8) & 0xFF);
part1[10] = (uint8_t)((sd->partitions[SD_PART_FATFS].start_block >> 16) & 0xFF);
part1[11] = (uint8_t)((sd->partitions[SD_PART_FATFS].start_block >> 24) & 0xFF);
part1[12] = (uint8_t)(sd->partitions[SD_PART_FATFS].blocks & 0xFF);
part1[13] = (uint8_t)((sd->partitions[SD_PART_FATFS].blocks >> 8) & 0xFF);
part1[14] = (uint8_t)((sd->partitions[SD_PART_FATFS].blocks >> 16) & 0xFF);
part1[15] = (uint8_t)((sd->partitions[SD_PART_FATFS].blocks >> 24) & 0xFF);
// Partition 2: USB MSC
uint8_t *part2 = &mbr[462];
part2[0] = 0x00; // Not bootable
part2[4] = 0x0C; // FAT32 LBA (or 0x83 for Linux, etc.)
part2[8] = (uint8_t)(sd->partitions[SD_PART_MSC].start_block & 0xFF);
part2[9] = (uint8_t)((sd->partitions[SD_PART_MSC].start_block >> 8) & 0xFF);
part2[10] = (uint8_t)((sd->partitions[SD_PART_MSC].start_block >> 16) & 0xFF);
part2[11] = (uint8_t)((sd->partitions[SD_PART_MSC].start_block >> 24) & 0xFF);
part2[12] = (uint8_t)(sd->partitions[SD_PART_MSC].blocks & 0xFF);
part2[13] = (uint8_t)((sd->partitions[SD_PART_MSC].blocks >> 8) & 0xFF);
part2[14] = (uint8_t)((sd->partitions[SD_PART_MSC].blocks >> 16) & 0xFF);
part2[15] = (uint8_t)((sd->partitions[SD_PART_MSC].blocks >> 24) & 0xFF);
mbr[510] = 0x55;
mbr[511] = 0xAA;
return ((sd_spi_write_blocks(0, mbr, 1) == SD_ERR_OKAY) &&
(sd_spi_sync() == SD_ERR_OKAY));
}
bool sd_init(void) {
if (spi_inited) {
return true;
}
mutex_init(&sd_mutex);
static bool sdcard_check_partitions(const uint8_t* mbr, sdcard_state_t* sd) {
// Partition 1 (FATFS)
const uint8_t *part1 = &mbr[446];
uint32_t part1_start = part1[8] | (part1[9] << 8) |
(part1[10] << 16) | (part1[11] << 24);
uint32_t part1_size = part1[12] | (part1[13] << 8) |
(part1[14] << 16) | (part1[15] << 24);
spi_init(spi, SDCARD_SPI_BAUDRATE);
spi_set_format(spi, 8, SPI_CPOL_0, SPI_CPHA_0, SPI_MSB_FIRST);
gpio_set_function(SDCARD_SPI_PIN_SCK, GPIO_FUNC_SPI);
gpio_set_function(SDCARD_SPI_PIN_MOSI, GPIO_FUNC_SPI);
gpio_set_function(SDCARD_SPI_PIN_MISO, GPIO_FUNC_SPI);
gpio_init(SDCARD_SPI_PIN_CS);
gpio_set_dir(SDCARD_SPI_PIN_CS, GPIO_OUT);
gpio_put(SDCARD_SPI_PIN_CS, 1);
spi_inited = true;
// Partition 2 (MSC)
const uint8_t *part2 = &mbr[462];
uint32_t part2_start = part2[8] | (part2[9] << 8) |
(part2[10] << 16) | (part2[11] << 24);
uint32_t part2_size = part2[12] | (part2[13] << 8) |
(part2[14] << 16) | (part2[15] << 24);
sdcard_state_t sd_cmp = {0};
sdcard_calculate_partition_sizes(&sd_cmp);
// Check if matches expected layout
if ((part1_start == sd_cmp.partitions[SD_PART_FATFS].start_block) &&
(part1_size == sd_cmp.partitions[SD_PART_FATFS].blocks) &&
(part2_start == sd_cmp.partitions[SD_PART_MSC].start_block) &&
(part2_size == sd_cmp.partitions[SD_PART_MSC].blocks)) {
return true; // Already partitioned as expected
}
return false;
}
static bool sdcard_init_all(sdcard_state_t* sd) {
uint8_t mbr[SD_BLOCK_SIZE] = {0};
sd_error_t err = sd_spi_read_blocks(0, mbr, 1);
if (err != SD_ERR_OKAY) {
ogxm_loge("Failed to read MBR, Error: %d", err);
return false;
}
if ((mbr[510] != 0x55) || (mbr[511] != 0xAA)) {
ogxm_logd("SD: No MBR found, formatting disk");
if (!sdcard_format_disk(sd)) {
ogxm_loge("SD: Failed to format disk");
return false;
}
} else {
ogxm_logd("SD: MBR found, checking partitions");
}
if (!sdcard_check_partitions(mbr, sd)) {
ogxm_logd("SD: Partitions do not match expected layout, formatting disk");
if (!sdcard_format_disk(sd)) {
ogxm_loge("SD: Failed to format disk");
return false;
}
} else {
ogxm_logd("SD: Partitions match expected layout");
}
sd->inited = true;
return true;
}
bool sd_present(void) {
if (!spi_inited) {
spi_inited = sd_init();
/* Public thread safe methods */
bool sdcard_init(void) {
sdcard_lock();
if (sdcard.inited) {
ogxm_logd("SD card already initialized");
sdcard_unlock();
return true;
}
sd_xfer_begin();
uint8_t response = 0;
int result = spi_read_blocking(spi, 0xFF, &response, 1);
sd_xfer_complete();
connected = ((result == 1) && (response == 0xFF));
return connected;
sd_error_t err = sd_spi_init();
if (err != SD_ERR_OKAY) {
ogxm_loge("SD: Failed to initialize SD SPI, Error: %d", err);
sdcard_unlock();
return false;
}
err = sd_spi_get_block_count(&sdcard.block_count);
if (err != SD_ERR_OKAY) {
ogxm_loge("SD: Failed to get block count, Error: %d", err);
sdcard_unlock();
return false;
}
if (sdcard.block_count < MSC_MINIMUM_PARTITION_BLOCKS) {
ogxm_loge("SD: Card too small for minimum partition size");
sdcard_unlock();
return false;
}
if (!sdcard_init_all(&sdcard)) {
sdcard_unlock();
return false;
}
ogxm_logi("SD: Initialized successfully, Block Count: %u", sdcard.block_count);
sdcard_unlock();
return true;
}
bool sdcard_inited(void) {
sdcard_lock();
if (!sdcard.inited) {
ogxm_loge("SD: Not initialized");
sdcard_unlock();
return false;
}
sdcard_unlock();
ogxm_logd("SD: Initialized");
return true;
}
void sdcard_deinit(void) {
sdcard_lock();
if (!sdcard.inited) {
ogxm_logd("SD card not initialized, nothing to deinitialize");
sdcard_unlock();
return;
}
sd_error_t err = sd_spi_deinit();
if (err != SD_ERR_OKAY) {
ogxm_loge("SD: Failed to deinitialize SD SPI, Error: %d", err);
} else {
ogxm_logi("SD card deinitialized successfully");
}
sdcard.inited = false;
sdcard_unlock();
}
bool sdcard_read_blocks(sd_partition_t partition, uint32_t block, uint8_t *buffer, uint32_t count) {
sdcard_lock();
if (!sdcard.inited || !buffer || (count == 0) ||
((uint8_t)partition >= SD_PART_MAX)) {
ogxm_loge("SD: Invalid arguments for read_blocks");
sdcard_unlock();
return false;
}
uint32_t start_block = sdcard.partitions[partition].start_block + block;
if ((start_block + count) >
(sdcard.partitions[partition].start_block + sdcard.partitions[partition].blocks)) {
ogxm_loge("SD: Read exceeds partition bounds");
sdcard_unlock();
return false;
}
sd_error_t err = sd_spi_read_blocks(start_block, buffer, count);
sdcard_unlock();
if (err != SD_ERR_OKAY) {
ogxm_loge("SD: Failed to read blocks, Error: %d", err);
return false;
}
return true;
}
bool sdcard_write_blocks(sd_partition_t partition, uint32_t block,
const uint8_t *buffer, uint32_t count) {
sdcard_lock();
if (!sdcard.inited || !buffer || (count == 0) ||
((uint8_t)partition >= SD_PART_MAX)) {
ogxm_loge("SD: Invalid arguments for write_blocks");
sdcard_unlock();
return false;
}
uint32_t start_block = sdcard.partitions[partition].start_block + block;
if ((start_block + count) >
(sdcard.partitions[partition].start_block + sdcard.partitions[partition].blocks)) {
ogxm_loge("SD: Write exceeds partition bounds");
sdcard_unlock();
return false;
}
sd_error_t err = sd_spi_write_blocks(start_block, buffer, count);
sdcard_unlock();
if (err != SD_ERR_OKAY) {
ogxm_loge("SD: Failed to write blocks, Error: %d", err);
return false;
}
return true;
}
bool sdcard_sync(void) {
sdcard_lock();
if (!sdcard.inited) {
ogxm_loge("SD: Invalid arguments for sync");
sdcard_unlock();
return false;
}
sd_error_t err = sd_spi_sync();
sdcard_unlock();
if (err != SD_ERR_OKAY) {
ogxm_loge("SD: Failed to sync, Error: %d", err);
return false;
}
return true;
}
bool sdcard_get_block_count(sd_partition_t partition, uint32_t* count) {
sdcard_lock();
if (!count || ((uint8_t)partition >= SD_PART_MAX)) {
ogxm_loge("SD: Invalid arguments for get_block_count");
sdcard_unlock();
return false;
}
if (!sdcard.inited) {
ogxm_loge("SD: Card not initialized");
sdcard_unlock();
return false;
}
*count = sdcard.partitions[partition].blocks;
sdcard_unlock();
return true;
}
#endif // SD_CARD_ENABLED

View File

@@ -5,25 +5,25 @@
#include <stdint.h>
#include <stdbool.h>
#include "sdcard/sd_spi.h"
#ifdef __cplusplus
extern "C" {
#endif
bool sd_init(void);
bool sd_present(void);
typedef enum {
SD_PART_MSC = 0,
SD_PART_FATFS,
SD_PART_MAX
} sd_partition_t;
/* MSC/Ogxbox Partition */
bool sd_msc_read_blocks(uint8_t* buffer, uint32_t lba, uint32_t count);
bool sd_msc_write_blocks(const uint8_t* buffer, uint32_t lba, uint32_t count);
uint32_t sd_msc_get_block_count(void);
/* Internal use partition */
bool sd_fatfs_read_blocks(uint8_t* buffer, uint32_t lba, uint32_t count);
bool sd_fatfs_write_blocks(const uint8_t* buffer, uint32_t lba, uint32_t count);
uint32_t sd_fatfs_get_block_count(void);
bool sdcard_init(void);
void sdcard_deinit(void);
bool sdcard_inited(void);
bool sdcard_read_blocks(sd_partition_t partition, uint32_t block, uint8_t *buffer, uint32_t count);
bool sdcard_write_blocks(sd_partition_t partition, uint32_t block, const uint8_t *buffer, uint32_t count);
bool sdcard_sync(void);
bool sdcard_get_block_count(sd_partition_t partition, uint32_t* count);
#ifdef __cplusplus
}

View File

@@ -93,7 +93,7 @@ typedef struct __attribute__((packed, aligned(4))) {
uint8_t a_lb; /* Analog button array byte offset */
uint8_t a_rb; /* Analog button array byte offset */
};
uint8_t analog[GAMEPAD_ANALOG_COUNT]; /* Raw array of analog button array byte offsets */
uint8_t analog[GAMEPAD_ANALOG_COUNT]; /* Raw analog button array byte offsets */
};
uint8_t reserved[2];

View File

@@ -0,0 +1,361 @@
#pragma once
#include <stdint.h>
#include "common/usb_def.h"
#include "common/usb_util.h"
#include "common/class/cdc_def.h"
#include "common/class/rndis_def.h"
#include "webserver/webserver.h"
#ifdef __cplusplus
extern "C" {
#endif
#define NET_EPSIZE_CTRL ((uint8_t)64)
#define NET_EPSIZE_COMM ((uint16_t)8)
#define NET_EPSIZE_DATA ((uint16_t)64)
#define NET_EPADDR_COMM_IN ((uint8_t)USB_EP_DIR_IN | 1U)
#define NET_EPADDR_DATA_IN ((uint8_t)USB_EP_DIR_IN | 2U)
#define NET_EPADDR_DATA_OUT ((uint8_t)USB_EP_DIR_OUT | 3U)
#define NET_MAC_STR_INDEX 4U
typedef enum {
NET_ITF_COMM = 0,
NET_ITF_DATA,
NET_ITF_TOTAL
} net_itf_t;
typedef enum {
NET_CONFIG_RNDIS = 1,
NET_CONFIG_ECM = 2,
NET_CONFIG_TOTAL = 2
} net_config_t;
static const usb_desc_device_t NET_DESC_DEVICE = {
.bLength = sizeof(usb_desc_device_t),
.bDescriptorType = USB_DTYPE_DEVICE,
.bcdUSB = 0x0200,
.bDeviceClass = USB_CLASS_MISC,
.bDeviceSubClass = USB_SUBCLASS_IAD,
.bDeviceProtocol = USB_PROTOCOL_IAD,
.bMaxPacketSize0 = NET_EPSIZE_CTRL,
.idVendor = 0xCafe,
.idProduct = 0x5678,
.bcdDevice = 0x0100,
.iManufacturer = 1,
.iProduct = 2,
.iSerialNumber = 3,
.bNumConfigurations = NET_CONFIG_TOTAL
};
static const usb_desc_string_t NET_DESC_STR_LANG_ID = USB_ARRAY_DESC(0x0409);
static const usb_desc_string_t NET_DESC_STR_VENDOR = USB_STRING_DESC("Wired Opposite");
static const usb_desc_string_t NET_DESC_STR_PRODUCT = USB_STRING_DESC("OGX-Mini WebUSB");
static const usb_desc_string_t* NET_DESC_STRING[] = {
&NET_DESC_STR_LANG_ID,
&NET_DESC_STR_VENDOR,
&NET_DESC_STR_PRODUCT,
};
typedef struct __attribute__((packed)) {
usb_desc_config_t config;
usb_desc_iad_t iad;
usb_desc_itf_t itf_comm;
usb_cdc_desc_header_t header;
usb_cdc_desc_call_mgmt_t call_mgmt;
usb_cdc_desc_acm_t acm;
usb_cdc_desc_union_t union_desc;
usb_desc_endpoint_t ep_notif;
usb_desc_itf_t itf_data;
usb_desc_endpoint_t ep_in;
usb_desc_endpoint_t ep_out;
} net_desc_config_rndis_t;
typedef struct __attribute__((packed)) {
usb_desc_config_t config;
usb_desc_iad_t iad;
usb_desc_itf_t itf_comm;
usb_cdc_desc_header_t header;
usb_cdc_desc_call_mgmt_t call_mgmt;
usb_cdc_desc_union_t union_desc;
usb_cdc_desc_ecm_func_t ecm_func;
usb_desc_endpoint_t ep_notif;
usb_desc_itf_t itf_data;
usb_desc_endpoint_t ep_in;
usb_desc_endpoint_t ep_out;
} net_desc_config_ecm_t;
// Frame 22182: 14 bytes on wire (112 bits), 14 bytes captured (112 bits) on interface usb, id 0
// USB Link Layer
// USB URB
// CONFIGURATION DESCRIPTOR
// bLength: 9
// bDescriptorType: 0x02 (CONFIGURATION)
// wTotalLength: 75
// bNumInterfaces: 2
// bConfigurationValue: 1
// iConfiguration: 0
// Configuration bmAttributes: 0x80 NOT SELF-POWERED NO REMOTE-WAKEUP
// bMaxPower: 50 (100mA)
// INTERFACE ASSOCIATION DESCRIPTOR
// bLength: 8
// bDescriptorType: 0x0b (INTERFACE ASSOCIATION)
// bFirstInterface: 0
// bInterfaceCount: 2
// bFunctionClass: Wireless Controller (0xe0)
// bFunctionSubClass: 0x01
// bFunctionProtocol: 0x03
// iFunction: 0
// INTERFACE DESCRIPTOR (0.0): class Wireless Controller
// bLength: 9
// bDescriptorType: 0x04 (INTERFACE)
// bInterfaceNumber: 0
// bAlternateSetting: 0
// bNumEndpoints: 1
// bInterfaceClass: Wireless Controller (0xe0)
// bInterfaceSubClass: 0x01
// bInterfaceProtocol: 0x03
// iInterface: 4
// UNKNOWN DESCRIPTOR
// bLength: 5
// bDescriptorType: 0x24 (unknown)
// UNKNOWN DESCRIPTOR
// bLength: 5
// bDescriptorType: 0x24 (unknown)
// UNKNOWN DESCRIPTOR
// bLength: 4
// bDescriptorType: 0x24 (unknown)
// UNKNOWN DESCRIPTOR
// bLength: 5
// bDescriptorType: 0x24 (unknown)
// ENDPOINT DESCRIPTOR
// bLength: 7
// bDescriptorType: 0x05 (ENDPOINT)
// bEndpointAddress: 0x81 IN Endpoint:1
// bmAttributes: 0x03
// wMaxPacketSize: 8
// bInterval: 1
// INTERFACE DESCRIPTOR (1.0): class CDC-Data
// bLength: 9
// bDescriptorType: 0x04 (INTERFACE)
// bInterfaceNumber: 1
// bAlternateSetting: 0
// bNumEndpoints: 2
// bInterfaceClass: CDC-Data (0x0a)
// bInterfaceSubClass: 0x00
// bInterfaceProtocol: No class specific protocol required (0x00)
// iInterface: 0
// ENDPOINT DESCRIPTOR
// bLength: 7
// bDescriptorType: 0x05 (ENDPOINT)
// bEndpointAddress: 0x82 IN Endpoint:2
// bmAttributes: 0x02
// wMaxPacketSize: 64
// bInterval: 0
// ENDPOINT DESCRIPTOR
// bLength: 7
// bDescriptorType: 0x05 (ENDPOINT)
// bEndpointAddress: 0x02 OUT Endpoint:2
// bmAttributes: 0x02
// wMaxPacketSize: 64
// bInterval: 0
static const net_desc_config_rndis_t NET_DESC_CONFIG_RNDIS = {
.config = {
.bLength = sizeof(usb_desc_config_t),
.bDescriptorType = USB_DTYPE_CONFIGURATION,
.wTotalLength = sizeof(net_desc_config_rndis_t),
.bNumInterfaces = NET_ITF_TOTAL,
.bConfigurationValue = NET_CONFIG_RNDIS,
.iConfiguration = 0,
.bmAttributes = USB_ATTR_RESERVED,
.bMaxPower = 100,
},
.iad = {
.bLength = sizeof(usb_desc_iad_t),
.bDescriptorType = USB_DTYPE_IAD,
.bFirstInterface = NET_ITF_COMM,
.bInterfaceCount = 2,
.bFunctionClass = USB_CLASS_RNDIS,
.bFunctionSubClass = USB_RNDIS_ITF_SUBCLASS,
.bFunctionProtocol = USB_RNDIS_ITF_PROTOCOL,
.iFunction = 0
},
.itf_comm = {
.bLength = sizeof(usb_desc_itf_t),
.bDescriptorType = USB_DTYPE_INTERFACE,
.bInterfaceNumber = NET_ITF_COMM,
.bAlternateSetting = 0,
.bNumEndpoints = 1,
.bInterfaceClass = USB_CLASS_RNDIS,
.bInterfaceSubClass = USB_RNDIS_ITF_SUBCLASS,
.bInterfaceProtocol = USB_RNDIS_ITF_PROTOCOL,
.iInterface = 0
},
.header = {
.bFunctionLength = sizeof(usb_cdc_desc_header_t),
.bDescriptorType = USB_DTYPE_CS_INTERFACE,
.bDescriptorSubType = USB_DTYPE_CDC_HEADER,
.bcdCDC = 0x0110
},
.call_mgmt = {
.bFunctionLength = sizeof(usb_cdc_desc_call_mgmt_t),
.bDescriptorType = USB_DTYPE_CS_INTERFACE,
.bDescriptorSubType = USB_DTYPE_CDC_CALL_MGMT,
.bmCapabilities = 0x00,
.bDataInterface = NET_ITF_DATA,
},
.acm = {
.bFunctionLength = sizeof(usb_cdc_desc_acm_t),
.bDescriptorType = USB_DTYPE_CS_INTERFACE,
.bDescriptorSubType = USB_DTYPE_CDC_ACM,
.bmCapabilities = 0,
},
.union_desc = {
.bFunctionLength = sizeof(usb_cdc_desc_union_t),
.bDescriptorType = USB_DTYPE_CS_INTERFACE,
.bDescriptorSubType = USB_DTYPE_CDC_UNION,
.bMasterInterface0 = NET_ITF_COMM,
.bSlaveInterface0 = NET_ITF_DATA,
},
.ep_notif = {
.bLength = sizeof(usb_desc_endpoint_t),
.bDescriptorType = USB_DTYPE_ENDPOINT,
.bEndpointAddress = NET_EPADDR_COMM_IN,
.bmAttributes = USB_EP_TYPE_INTERRUPT,
.wMaxPacketSize = NET_EPSIZE_COMM,
.bInterval = 9,
},
.itf_data = {
.bLength = sizeof(usb_desc_itf_t),
.bDescriptorType = USB_DTYPE_INTERFACE,
.bInterfaceNumber = NET_ITF_DATA,
.bAlternateSetting = 0,
.bNumEndpoints = 2,
.bInterfaceClass = USB_CLASS_CDC_DATA,
.bInterfaceSubClass = 0,
.bInterfaceProtocol = 0,
.iInterface = 0,
},
.ep_in = {
.bLength = sizeof(usb_desc_endpoint_t),
.bDescriptorType = USB_DTYPE_ENDPOINT,
.bEndpointAddress = NET_EPADDR_DATA_IN,
.bmAttributes = USB_EP_TYPE_BULK,
.wMaxPacketSize = NET_EPSIZE_DATA,
.bInterval = 0,
},
.ep_out = {
.bLength = sizeof(usb_desc_endpoint_t),
.bDescriptorType = USB_DTYPE_ENDPOINT,
.bEndpointAddress = NET_EPADDR_DATA_OUT,
.bmAttributes = USB_EP_TYPE_BULK,
.wMaxPacketSize = NET_EPSIZE_DATA,
.bInterval = 0,
},
};
static const net_desc_config_ecm_t NET_DESC_CONFIG_ECM = {
.config = {
.bLength = sizeof(usb_desc_config_t),
.bDescriptorType = USB_DTYPE_CONFIGURATION,
.wTotalLength = sizeof(net_desc_config_ecm_t),
.bNumInterfaces = NET_ITF_TOTAL,
.bConfigurationValue = NET_CONFIG_ECM,
.iConfiguration = 0,
.bmAttributes = USB_ATTR_RESERVED,
.bMaxPower = 100,
},
.iad = {
.bLength = sizeof(usb_desc_iad_t),
.bDescriptorType = USB_DTYPE_IAD,
.bFirstInterface = NET_ITF_COMM,
.bInterfaceCount = 2,
.bFunctionClass = USB_CLASS_CDC,
.bFunctionSubClass = USB_SUBCLASS_CDC_ETHERNET_CONTROL,
.bFunctionProtocol = 0,
.iFunction = 0,
},
.itf_comm = {
.bLength = sizeof(usb_desc_itf_t),
.bDescriptorType = USB_DTYPE_INTERFACE,
.bInterfaceNumber = NET_ITF_COMM,
.bAlternateSetting = 0,
.bNumEndpoints = 1,
.bInterfaceClass = USB_CLASS_CDC,
.bInterfaceSubClass = USB_SUBCLASS_CDC_ETHERNET_CONTROL,
.bInterfaceProtocol = 0,
.iInterface = 0,
},
.header = {
.bFunctionLength = sizeof(usb_cdc_desc_header_t),
.bDescriptorType = USB_DTYPE_CS_INTERFACE,
.bDescriptorSubType = USB_DTYPE_CDC_HEADER,
.bcdCDC = 0x0110,
},
.call_mgmt = {
.bFunctionLength = sizeof(usb_cdc_desc_call_mgmt_t),
.bDescriptorType = USB_DTYPE_CS_INTERFACE,
.bDescriptorSubType = USB_DTYPE_CDC_CALL_MGMT,
.bmCapabilities = 0x00,
.bDataInterface = NET_ITF_DATA,
},
.union_desc = {
.bFunctionLength = sizeof(usb_cdc_desc_union_t),
.bDescriptorType = USB_DTYPE_CS_INTERFACE,
.bDescriptorSubType = USB_DTYPE_CDC_UNION,
.bMasterInterface0 = NET_ITF_COMM,
.bSlaveInterface0 = NET_ITF_DATA,
},
.ecm_func = {
.bFunctionLength = sizeof(usb_cdc_desc_ecm_func_t),
.bDescriptorType = USB_DTYPE_CS_INTERFACE,
.bDescriptorSubType = USB_DTYPE_CDC_ETHERNET,
.iMACAddress = NET_MAC_STR_INDEX,
.bmEthernetStatistics = 0,
.wMaxSegmentSize = WEBSERVER_MTU,
.wNumberMCFilters = 0,
.bNumberPowerFilters = 0,
},
.ep_notif = {
.bLength = sizeof(usb_desc_endpoint_t),
.bDescriptorType = USB_DTYPE_ENDPOINT,
.bEndpointAddress = NET_EPADDR_COMM_IN,
.bmAttributes = USB_EP_TYPE_INTERRUPT,
.wMaxPacketSize = NET_EPSIZE_COMM,
.bInterval = 9,
},
.itf_data = {
.bLength = sizeof(usb_desc_itf_t),
.bDescriptorType = USB_DTYPE_INTERFACE,
.bInterfaceNumber = NET_ITF_DATA,
.bAlternateSetting = 0,
.bNumEndpoints = 2,
.bInterfaceClass = USB_CLASS_CDC_DATA,
.bInterfaceSubClass = 0,
.bInterfaceProtocol = 0,
.iInterface = 0,
},
.ep_in = {
.bLength = sizeof(usb_desc_endpoint_t),
.bDescriptorType = USB_DTYPE_ENDPOINT,
.bEndpointAddress = NET_EPADDR_DATA_IN,
.bmAttributes = USB_EP_TYPE_BULK,
.wMaxPacketSize = NET_EPSIZE_DATA,
.bInterval = 0,
},
.ep_out = {
.bLength = sizeof(usb_desc_endpoint_t),
.bDescriptorType = USB_DTYPE_ENDPOINT,
.bEndpointAddress = NET_EPADDR_DATA_OUT,
.bmAttributes = USB_EP_TYPE_BULK,
.wMaxPacketSize = NET_EPSIZE_DATA,
.bInterval = 0,
},
};
#ifdef __cplusplus
}
#endif

View File

@@ -55,7 +55,7 @@ static const usb_device_driver_t* USBD_DRIVERS[USBD_INT_TYPE_COUNT] = {
[USBD_INT_TYPE_PS3] = &USBD_DRIVER_PS3,
[USBD_INT_TYPE_PSCLASSIC] = &USBD_DRIVER_PSCLASSIC,
[USBD_INT_TYPE_SWITCH] = &USBD_DRIVER_SWITCH,
[USBD_INT_TYPE_WEBAPP] = &USBD_DRIVER_WEBAPP,
[USBD_INT_TYPE_WEBAPP] = &USBD_DRIVER_NET,//&USBD_DRIVER_WEBAPP,
[USBD_INT_TYPE_UART_BRIDGE] = &USBD_DRIVER_UART_BRIDGE,
[USBD_INT_TYPE_XBOXOG_HUB] = &USBD_DRIVER_XBOXOG_HUB,
[USBD_INT_TYPE_XBOXOG_XMU] = NULL,

View File

@@ -52,6 +52,7 @@ extern const usb_device_driver_t USBD_DRIVER_XBOXOG_HUB;
extern const usb_device_driver_t USBD_DRIVER_XBOXOG_XMU;
extern const usb_device_driver_t USBD_DRIVER_XBOXOG_XBLC;
extern const usb_device_driver_t USBD_DRIVER_WEBAPP;
extern const usb_device_driver_t USBD_DRIVER_NET;
void usb_device_rumble_cb(usbd_handle_t* handle, const gamepad_rumble_t* rumble);
void usb_device_audio_cb(usbd_handle_t* handle, const gamepad_pcm_out_t* pcm_out);

View File

@@ -2,6 +2,7 @@
#include "usbd/usbd.h"
#include "usb/device/device_private.h"
#if SD_CARD_ENABLED
// #if 0
#include <string.h>
#include "common/usb_util.h"
@@ -12,7 +13,7 @@
#include "usb/device/device.h"
#include "log/log.h"
#define MSC_BLOCK_SIZE 512U
#define MSC_BLOCK_SIZE SD_BLOCK_SIZE
#define TO_UINT32(p) ((uint32_t)((((uint8_t*)(p))[0] << 24) | (((uint8_t*)(p))[1] << 16) | (((uint8_t*)(p))[2] << 8) | ((uint8_t*)(p))[3]))
#define TO_UINT16(p) ((uint16_t)((((uint8_t*)(p))[0] << 8) | ((uint8_t*)(p))[1]))
@@ -20,6 +21,7 @@
#define SWAP32(x) ((uint32_t)(((x) >> 24) | (((x) & 0x00FF0000) >> 8) | (((x) & 0x0000FF00) << 8) | ((x) << 24)))
typedef struct {
usbd_handle_t* handle;
bool ready;
uint32_t block_count;
usb_msc_csw_t csw;
@@ -35,7 +37,7 @@ typedef struct {
uint8_t block_in[MSC_BLOCK_SIZE] __attribute__((aligned(4)));
uint8_t ep_out[MSC_EPSIZE_OUT] __attribute__((aligned(4)));
} msc_state_t;
_Static_assert(sizeof(msc_state_t) <= USBD_STATUS_BUF_SIZE, "XBOXOG GP state size exceeds buffer size");
// _Static_assert(sizeof(msc_state_t) <= USBD_STATUS_BUF_SIZE, "XBOXOG GP state size exceeds buffer size");
typedef struct __attribute__((packed)) {
uint8_t opcode; // 0x28 for READ(10), 0x2A for WRITE(10)
@@ -75,7 +77,7 @@ static const usb_msc_scsi_inquiry_data_t MSC_SCSI_INQUIRY_DATA = {
.product_rev = "1.00"
};
static msc_state_t* msc_state[USBD_DEVICES_MAX] = { NULL };
static msc_state_t msc_state = {0};
static void msc_init_cb(usbd_handle_t* handle) {
(void)handle;
@@ -111,7 +113,7 @@ static bool msc_get_desc_cb(usbd_handle_t* handle, const usb_ctrl_req_t* req) {
}
static bool msc_ctrl_xfer_cb(usbd_handle_t* handle, const usb_ctrl_req_t* req) {
msc_state_t* msc = msc_state[handle->port];
msc_state_t* msc = &msc_state;
switch (req->bmRequestType & (USB_REQ_TYPE_Msk | USB_REQ_RECIP_Msk)) {
case (USB_REQ_TYPE_CLASS | USB_REQ_RECIP_INTERFACE):
switch (req->bRequest) {
@@ -153,12 +155,12 @@ static bool msc_set_config_cb(usbd_handle_t* handle, uint8_t config) {
static void msc_configured_cb(usbd_handle_t* handle, uint8_t config) {
(void)config;
msc_state_t* msc = msc_state[handle->port];
msc_state_t* msc = &msc_state;
memset(msc, 0, sizeof(msc_state_t));
}
static bool msc_write_bulk_blocking(usbd_handle_t* handle, const uint8_t* data, uint16_t len) {
msc_state_t* msc = msc_state[handle->port];
msc_state_t* msc = &msc_state;
uint32_t remaining = len;
while (remaining > 0) {
uint16_t to_write = MIN(remaining, MSC_EPSIZE_IN);
@@ -176,18 +178,24 @@ static bool msc_write_bulk_blocking(usbd_handle_t* handle, const uint8_t* data,
}
static void handle_cbw_command(usbd_handle_t* handle, const usb_msc_cbw_t* cbw) {
msc_state_t* msc = msc_state[handle->port];
msc_state_t* msc = &msc_state;
bool error = false;
switch (cbw->command[0]) {
case USB_MSC_SCSI_CMD_INQUIRY:
error = !msc_write_bulk_blocking(handle, (const uint8_t*)&MSC_SCSI_INQUIRY_DATA,
sizeof(MSC_SCSI_INQUIRY_DATA));
sizeof(MSC_SCSI_INQUIRY_DATA));
break;
case USB_MSC_SCSI_CMD_TEST_UNIT_READY:
break;
case USB_MSC_SCSI_CMD_READ_CAPACITY_10:
{
uint32_t last_block = sd_msc_get_block_count() - 1;
uint32_t last_block = 0;
if (!sdcard_get_block_count(SD_PART_MSC, &last_block)) {
ogxm_loge("Failed to get block count for MSC partition\n");
error = true;
break;
}
last_block--; // Convert to last block index
uint8_t cap[8] __attribute__((aligned(4))) = {
(last_block >> 24) & 0xFF, (last_block >> 16) & 0xFF,
(last_block >> 8) & 0xFF, last_block & 0xFF,
@@ -202,7 +210,11 @@ static void handle_cbw_command(usbd_handle_t* handle, const usb_msc_cbw_t* cbw)
uint32_t lba = TO_UINT32(&cbw->command[2]);
uint16_t count = TO_UINT16(&cbw->command[7]);
for (uint16_t i = 0; i < count; i++) {
sd_msc_read_blocks(msc->block_in, lba + i, 1);
if (!sdcard_read_blocks(SD_PART_MSC, lba + i, msc->block_in, 1)) {
ogxm_loge("Failed to read block %u from MSC partition\n", lba + i);
error = true;
break;
}
if (!msc_write_bulk_blocking(handle, msc->block_in, MSC_BLOCK_SIZE)) {
error = true;
break;
@@ -239,7 +251,7 @@ static void handle_cbw_command(usbd_handle_t* handle, const usb_msc_cbw_t* cbw)
}
static void msc_ep_xfer_cb(usbd_handle_t* handle, uint8_t epaddr) {
msc_state_t* msc = msc_state[handle->port];
msc_state_t* msc = &msc_state;
if (epaddr == MSC_EPADDR_OUT) {
int32_t len = usbd_ep_read(handle, MSC_EPADDR_OUT,
msc->ep_out, MSC_EPSIZE_OUT);
@@ -257,7 +269,8 @@ static void msc_ep_xfer_cb(usbd_handle_t* handle, uint8_t epaddr) {
if (msc->out_idx >= MSC_BLOCK_SIZE) {
// We have a full block, process it
sd_msc_write_blocks(msc->block_out, msc->out_lba + msc->out_current_count, 1);
sdcard_write_blocks(SD_PART_MSC, msc->out_lba + msc->out_current_count,
msc->block_out, 1);
msc->out_current_count++;
msc->out_idx -= MSC_BLOCK_SIZE;
@@ -279,9 +292,17 @@ static void msc_ep_xfer_cb(usbd_handle_t* handle, uint8_t epaddr) {
}
static usbd_handle_t* msc_init(const usb_device_driver_cfg_t* cfg) {
if ((cfg == NULL) || (cfg->usb.status_buffer == NULL)) {
if (cfg == NULL) {
return NULL;
}
if (!sdcard_init()) {
ogxm_loge("Failed to initialize SD card for MSC driver\n");
return NULL;
}
if ((msc_state.handle != NULL) && (msc_state.handle->state != USBD_STATE_DISABLED)) {
ogxm_logd("MSC driver already initialized\n");
return msc_state.handle;
}
usbd_driver_t driver = {
.init_cb = msc_init_cb,
.deinit_cb = msc_deinit_cb,
@@ -291,17 +312,15 @@ static usbd_handle_t* msc_init(const usb_device_driver_cfg_t* cfg) {
.ctrl_xfer_cb = msc_ctrl_xfer_cb,
.ep_xfer_cb = msc_ep_xfer_cb,
};
usbd_handle_t* handle = usbd_init(cfg->usb.hw_type, &driver, MSC_EPSIZE_CTRL);
if (handle != NULL) {
msc_state[handle->port] = (msc_state_t*)cfg->usb.status_buffer;
}
return handle;
msc_state.handle = usbd_init(cfg->usb.hw_type, &driver, MSC_EPSIZE_CTRL);
return msc_state.handle;
}
#else // SD_CARD_ENABLED
static usbd_handle_t* msc_init(const usb_device_driver_cfg_t* cfg) {
(void)cfg;
ogxm_loge("MSC driver is disabled because SD_CARD_ENABLED is not set\n");
return NULL;
}

View File

@@ -0,0 +1,513 @@
#include <stdbool.h>
#include <string.h>
#include <pico/unique_id.h>
#include "usbd/usbd.h"
#include "common/class/cdc_def.h"
#include "common/class/rndis_def.h"
#include "lwip/init.h"
#include "lwip/timeouts.h"
#include "lwip/apps/httpd.h"
#include "log/log.h"
#include "gamepad/gamepad.h"
#include "settings/settings.h"
#include "usb/device/device.h"
#include "usb/descriptors/net.h"
#include "usb/device/device_private.h"
#include "usb/device/drivers/rndis/rndis.h"
#include "webserver/webserver.h"
typedef struct {
usb_ctrl_req_t header;
uint32_t downlink;
uint32_t uplink;
} ecm_notify_t;
typedef union {
uint8_t rndis[0x80];
ecm_notify_t ecm;
} net_notify_t;
typedef struct {
struct {
usbd_handle_t* handle;
net_config_t config;
uint8_t itf_alt_data;
uint16_t out_xfer_idx;
uint16_t rndis_next_len;
bool in_xfer_busy;
uint16_t in_xfer_idx;
uint16_t in_xfer_len;
} usb;
bool can_xmit;
net_notify_t notify;
} net_state_t;
_Static_assert(sizeof(net_state_t) <= USBD_STATUS_BUF_SIZE, "net_state_t size exceeds USBH_EPSIZE_MAX");
static const ecm_notify_t ECM_NOTIFY_NC = {
.header = {
.bmRequestType = 0xA1,
.bRequest = 0 /* NETWORK_CONNECTION aka NetworkConnection */,
.wValue = 1 /* Connected */,
.wLength = 0,
},
};
static const ecm_notify_t ECM_NOTIFY_CSC = {
.header = {
.bmRequestType = 0xA1,
.bRequest = 0x2A /* CONNECTION_SPEED_CHANGE aka ConnectionSpeedChange */,
.wLength = 8,
},
.downlink = 9728000,
.uplink = 9728000,
};
static net_state_t* net_state = NULL;
static uint8_t net_buf_out[WEBSERVER_MTU + sizeof(usb_rndis_msg_data_t)] __attribute__((aligned(4)));
static uint8_t net_buf_in[WEBSERVER_MTU + sizeof(usb_rndis_msg_data_t)] __attribute__((aligned(4)));
// static int32_t write_ep_bulk_blocking(usbd_handle_t* handle, uint8_t epaddr,
// const void* data, uint32_t len) {
// int32_t remain = len;
// while (remain > 0) {
// while (!usbd_ep_ready(handle, epaddr)) {
// usbd_task();
// }
// int32_t written = usbd_ep_write(handle, epaddr, data, remain);
// if (written < 0) {
// ogxm_loge("Failed to write to endpoint %02x: %d",
// epaddr, written);
// return -1;
// }
// remain -= written;
// data = (const uint8_t*)data + written;
// }
// return len;
// }
static bool handle_eth_frame_write(usbd_handle_t* handle) {
if (net_state->usb.in_xfer_idx == net_state->usb.in_xfer_len) {
ogxm_logv("NET: Transfer complete, %d bytes\n",
net_state->usb.in_xfer_len);
net_state->usb.in_xfer_busy = false;
net_state->usb.in_xfer_idx = 0;
net_state->usb.in_xfer_len = 0;
return true;
}
net_state->usb.in_xfer_busy = true;
int32_t written = usbd_ep_write(handle, NET_EPADDR_DATA_IN,
net_buf_in + net_state->usb.in_xfer_idx,
net_state->usb.in_xfer_len - net_state->usb.in_xfer_idx);
if (written < 0) {
ogxm_loge("Failed to write to endpoint %02x: %d",
NET_EPADDR_DATA_IN, written);
net_state->usb.in_xfer_busy = false;
net_state->usb.in_xfer_idx = 0;
net_state->usb.in_xfer_len = 0;
return false;
}
net_state->usb.in_xfer_idx += written;
return true;
}
static err_t netif_linkoutput_cb(struct netif *netif, struct pbuf *p) {
if ((net_state == NULL) || (net_state->usb.handle == NULL)) {
ogxm_loge("USB device handle is not initialized");
return ERR_IF;
}
if (!usbd_ep_ready(net_state->usb.handle, NET_EPADDR_DATA_IN) ||
net_state->usb.in_xfer_busy) {
ogxm_loge("Endpoint %02x is not ready for data transmission\n",
NET_EPADDR_DATA_IN);
return ERR_USE;
}
ogxm_logv("NET: Sending %d bytes on interface %d\n", p->tot_len, netif->num);
switch (net_state->usb.config) {
case NET_CONFIG_RNDIS:
{
usb_rndis_msg_data_t* hdr = (usb_rndis_msg_data_t*)net_buf_in;
hdr->MessageType = USB_RNDIS_PACKET_MSG;
hdr->MessageLength = sizeof(usb_rndis_msg_data_t) + p->tot_len;
hdr->DataOffset = sizeof(usb_rndis_msg_data_t) - offsetof(usb_rndis_msg_data_t, DataOffset);
hdr->DataLength = p->tot_len;
hdr->OOBDataOffset = 0;
hdr->OOBDataLength = 0;
hdr->NumOOBDataElements = 0;
hdr->PerPacketInfoOffset = 0;
hdr->PerPacketInfoLength = 0;
hdr->DeviceVcHandle = 0;
hdr->Reserved = 0;
if (pbuf_copy_partial(p, net_buf_in + sizeof(usb_rndis_msg_data_t),
p->tot_len, 0) != p->tot_len) {
ogxm_loge("NET: Failed to copy pbuf data to RNDIS buffer");
return ERR_IF;
}
net_state->usb.in_xfer_len = hdr->MessageLength;
if (!handle_eth_frame_write(net_state->usb.handle)) {
ogxm_loge("NET: Failed to write RNDIS data to endpoint %02x",
NET_EPADDR_DATA_IN);
return ERR_IF;
}
ogxm_logv_hex(net_buf_in + sizeof(usb_rndis_msg_data_t), 16, "NET: 16:");
}
break;
case NET_CONFIG_ECM:
{
const uint32_t len = p->tot_len;
if (pbuf_copy_partial(p, net_buf_in, p->tot_len, 0) != p->tot_len) {
ogxm_loge("NET: Failed to copy pbuf data to RNDIS buffer");
return ERR_IF;
}
net_state->usb.in_xfer_len = len;
handle_eth_frame_write(net_state->usb.handle);
}
break;
default:
ogxm_loge("NET: Unsupported NET configuration type: %d",
net_state->usb.config);
return ERR_IF;
}
ogxm_logd("NET: Frame send started\n");
return ERR_OK;
}
static void net_rumble_cb(uint8_t index, const gamepad_rumble_t* rumble) {
(void)index;
if ((net_state == NULL) || (net_state->usb.handle == NULL)) {
ogxm_loge("USB device handle is not initialized");
return;
}
usb_device_rumble_cb(net_state->usb.handle, rumble);
}
static void ecm_report(bool nc) {
net_state->notify.ecm = (nc) ? ECM_NOTIFY_NC : ECM_NOTIFY_CSC;
net_state->notify.ecm.header.wIndex = NET_ITF_COMM;
usbd_ep_write(net_state->usb.handle,
NET_EPADDR_COMM_IN,
&net_state->notify.ecm,
(nc) ? sizeof(net_state->notify.ecm.header)
: sizeof(net_state->notify.ecm));
}
static void net_rndis_notify(usbd_handle_t* handle, const usb_ctrl_req_t* req) {
static const uint8_t NDIS_REPORT[8] = { 0x01,0x00,0x00,0x00,0x00,0x00,0x00,0x00 };
usbd_ep_write(handle, NET_EPADDR_COMM_IN, NDIS_REPORT, sizeof(NDIS_REPORT));
}
// USBD NET Class driver
static void net_init_cb(usbd_handle_t* handle) {
(void)handle;
}
static void net_deinit_cb(usbd_handle_t* handle) {
(void)handle;
}
static bool net_get_desc_cb(usbd_handle_t* handle, const usb_ctrl_req_t* req) {
switch (USB_DESC_TYPE(req->wValue)) {
case USB_DTYPE_DEVICE:
return usbd_send_ctrl_resp(handle, &NET_DESC_DEVICE,
sizeof(NET_DESC_DEVICE), NULL);
case USB_DTYPE_CONFIGURATION:
ogxm_logd("NET: Configuration request for %d\n",
USB_DESC_INDEX(req->wValue) + 1);
if (USB_DESC_INDEX(req->wValue) == (NET_CONFIG_RNDIS - 1)) {
return usbd_send_ctrl_resp(handle, &NET_DESC_CONFIG_RNDIS,
sizeof(NET_DESC_CONFIG_RNDIS), NULL);
} else if (USB_DESC_INDEX(req->wValue) == (NET_CONFIG_ECM - 1)) {
return usbd_send_ctrl_resp(handle, &NET_DESC_CONFIG_ECM,
sizeof(NET_DESC_CONFIG_ECM), NULL);
}
break;
case USB_DTYPE_STRING:
{
uint8_t idx = USB_DESC_INDEX(req->wValue);
if (idx < ARRAY_SIZE(NET_DESC_STRING)) {
return usbd_send_ctrl_resp(handle, NET_DESC_STRING[idx],
NET_DESC_STRING[idx]->bLength, NULL);
} else if (idx == NET_DESC_DEVICE.iSerialNumber) {
const usb_desc_string_t* serial = usbd_get_desc_string_serial(handle);
return usbd_send_ctrl_resp(handle, serial,
serial->bLength, NULL);
} else if (idx == NET_MAC_STR_INDEX) {
uint8_t mac_addr[6] = {0};
webserver_get_mac_addr(mac_addr);
uint8_t mac_str[6 * 4 + 2] = {0};
usbd_hex_to_desc_string(mac_addr, sizeof(mac_addr),
mac_str, sizeof(mac_str));
return usbd_send_ctrl_resp(handle, mac_str,
sizeof(mac_str), NULL);
}
}
break;
default:
break;
}
return false;
}
static bool net_ctrl_xfer_cb(usbd_handle_t* handle, const usb_ctrl_req_t* req) {
// ogxm_logd("NET: Control request: %02x %02x %04x %04x %04x\n",
// req->bmRequestType, req->bRequest, req->wValue, req->wIndex, req->wLength);
switch (req->bmRequestType & (USB_REQ_TYPE_Msk | USB_REQ_RECIP_Msk)) {
case USB_REQ_TYPE_STANDARD | USB_REQ_RECIP_INTERFACE:
switch (req->bRequest) {
case USB_REQ_STD_GET_INTERFACE:
{
const uint8_t itf_num = (uint8_t)req->wIndex;
if (itf_num != NET_ITF_COMM &&
itf_num != NET_ITF_DATA) {
ogxm_loge("Invalid interface number: %d", itf_num);
return false;
}
return usbd_send_ctrl_resp(handle, &net_state->usb.itf_alt_data,
sizeof(net_state->usb.itf_alt_data), NULL);
}
break;
case USB_REQ_STD_SET_INTERFACE:
{
const uint8_t itf_num = (uint8_t)req->wIndex;
const uint8_t req_alt = (uint8_t)req->wValue;
// // Only valid for Data Interface with Alternate is either 0 or 1
// TU_VERIFY(_netd_itf.itf_num+1 == itf_num && req_alt < 2);
if (net_state->usb.config != NET_CONFIG_ECM) {
ogxm_loge("Invalid configuration for SET_INTERFACE: %d",
net_state->usb.config);
return false;
}
net_state->usb.itf_alt_data = req_alt;
if (net_state->usb.itf_alt_data != 0) {
net_state->can_xmit = true; // we are ready to transmit a packet
} else {
// TODO close the endpoint pair
// For now pretend that we did, this should have no harm since host won't try to
// communicate with the endpoints again
// _netd_itf.ep_in = _netd_itf.ep_out = 0
}
}
return true;
default:
break;
}
break;
case USB_REQ_TYPE_CLASS | USB_REQ_RECIP_INTERFACE:
switch (req->bRequest) {
case USB_REQ_CDC_GET_LINE_CODING:
case USB_REQ_CDC_SET_LINE_CODING:
case USB_REQ_CDC_SET_CONTROL_LINE_STATE:
return false;
default:
break;
}
switch (net_state->usb.config) {
case NET_CONFIG_RNDIS:
{
const usb_rndis_msg_generic_t* msg =
(const usb_rndis_msg_generic_t*)req->data;
switch (req->bRequest) {
case USB_REQ_RNDIS_SET_ENCAPSULATED_COMMAND:
{
int32_t ret = rndis_handle_msg(req->data,
net_state->notify.rndis,
sizeof(net_state->notify.rndis));
if (ret < 0) {
ogxm_loge("NET: Failed to handle RNDIS message: %d, type: %02X\n",
ret, msg->MessageType);
net_state->usb.rndis_next_len = 0;
return false;
} else if (ret > 0) {
ogxm_logd("NET: RNDIS message handled, response length: %d, type: %02X\n",
ret, msg->MessageType);
net_state->usb.rndis_next_len = ret;
net_rndis_notify(handle, req);
return true;
}
ogxm_logd("NET: RNDIS message handled, no response needed\n");
net_state->usb.rndis_next_len = 0;
return true;
}
case USB_REQ_RNDIS_GET_ENCAPSULATED_RESPONSE:
ogxm_logd("NET: RNDIS message complete, length: %d\n",
net_state->usb.rndis_next_len);
return usbd_send_ctrl_resp(handle,
net_state->notify.rndis,
net_state->usb.rndis_next_len, NULL);
default:
break;
}
}
case NET_CONFIG_ECM:
/* the only required CDC-ECM Management Element Request is SetEthernetPacketFilter */
if (USB_REQ_CDC_SET_ETHERNET_PACKET_FILTER == req->bRequest) {
usbd_send_ctrl_resp(handle, NULL, 0, NULL);
ecm_report(true);
return true;
}
break;
default:
break;
}
break;
default:
break;
}
ogxm_loge("NET: Unhandled control request: %02x %02x %04x %04x %04x",
req->bmRequestType, req->bRequest, req->wValue, req->wIndex, req->wLength);
return false;
}
static bool net_set_config_cb(usbd_handle_t* handle, uint8_t config) {
(void)config;
net_state->usb.config = config;
ogxm_logd("NET: Set configuration to %d, %s\n", config,
(config == NET_CONFIG_RNDIS) ? "RNDIS" :
(config == NET_CONFIG_ECM) ? "ECM" : "Unknown");
switch (net_state->usb.config) {
case NET_CONFIG_RNDIS:
return usbd_configure_all_eps(handle, &NET_DESC_CONFIG_RNDIS);
case NET_CONFIG_ECM:
return usbd_configure_all_eps(handle, &NET_DESC_CONFIG_ECM);
default:
ogxm_loge("NET: Invalid configuration selected: %d", config);
return false;
}
}
static void net_configured_cb(usbd_handle_t* handle, uint8_t config) {
(void)handle;
(void)config;
}
static void handle_rndis_ep_out(uint16_t len) {
usb_rndis_msg_data_t *msg = (usb_rndis_msg_data_t*)net_buf_out;
if ((net_state->usb.out_xfer_idx + len) < sizeof(usb_rndis_msg_data_t)) {
net_state->usb.out_xfer_idx += len;
return;
}
if (msg->MessageType != USB_RNDIS_PACKET_MSG) {
ogxm_loge("Unexpected RNDIS message type: %d", msg->MessageType);
net_state->usb.out_xfer_idx = 0;
return;
}
uint32_t data_offset = RNDIS_DATA_OFFSET(msg);
if ((net_state->usb.out_xfer_idx + len) < (data_offset + msg->DataLength)) {
net_state->usb.out_xfer_idx += len;
return;
}
net_state->usb.out_xfer_idx = 0;
webserver_set_frame(&net_buf_out[data_offset], msg->DataLength);
// ogxm_logv("NET: RNDIS OUT transfer complete, %d bytes\n",
// msg->DataLength);
}
static void handle_ecm_ep_out(uint16_t len) {
if (len < NET_EPSIZE_DATA) {
net_state->usb.out_xfer_idx += len;
webserver_set_frame(net_buf_out, net_state->usb.out_xfer_idx);
net_state->usb.out_xfer_idx = 0;
} else {
net_state->usb.out_xfer_idx += len;
}
}
static void net_ep_xfer_cb(usbd_handle_t* handle, uint8_t epaddr) {
switch (epaddr) {
case NET_EPADDR_DATA_OUT:
{
uint8_t* data_p = &net_buf_out[net_state->usb.out_xfer_idx];
int32_t len = usbd_ep_read(handle, epaddr,
data_p, NET_EPSIZE_DATA);
if (len < 0) {
ogxm_loge("NET: Failed to read from endpoint %02x: %d", epaddr, len);
net_state->usb.out_xfer_idx = 0;
return;
}
switch (net_state->usb.config) {
case NET_CONFIG_RNDIS:
handle_rndis_ep_out(len);
break;
case NET_CONFIG_ECM:
handle_ecm_ep_out(len);
break;
}
break;
}
case NET_EPADDR_DATA_IN:
if (net_state->usb.in_xfer_busy) {
handle_eth_frame_write(handle);
// if (net_state->usb.in_xfer_busy) {
// // ogxm_logv("NET: Data IN xfer progress: %d/%d bytes\n",
// // net_state->usb.in_xfer_idx, net_state->usb.in_xfer_len);
// }
}
default:
break;
}
}
// USBH driver callbacks
static usbd_handle_t* net_init(const usb_device_driver_cfg_t* cfg) {
if ((net_state != NULL) &&
(net_state->usb.handle != NULL) &&
(net_state->usb.handle->state != USBD_STATE_DISABLED)) {
return NULL;
}
usbd_driver_t driver = {
.init_cb = net_init_cb,
.deinit_cb = net_deinit_cb,
.get_desc_cb = net_get_desc_cb,
.set_config_cb = net_set_config_cb,
.configured_cb = net_configured_cb,
.ctrl_xfer_cb = net_ctrl_xfer_cb,
.ep_xfer_cb = net_ep_xfer_cb,
};
net_state = (net_state_t*)cfg->usb.status_buffer;
net_state->usb.handle = usbd_init(cfg->usb.hw_type, &driver, NET_EPSIZE_CTRL);
if (net_state->usb.handle != NULL) {
webserver_init(netif_linkoutput_cb, net_rumble_cb);
usbd_connect(cfg->usb.hw_type);
webserver_wait_ready(usbd_task);
webserver_start();
uint8_t mac_addr[6] = {0};
webserver_get_mac_addr(mac_addr);
rndis_init(WEBSERVER_MTU, mac_addr);
} else {
ogxm_loge("Failed to initialize USB device for net driver");
}
return net_state->usb.handle;
}
static void net_set_pad(usbd_handle_t* handle, const gamepad_pad_t* pad) {
// net_state_t* net = net_state[handle->port];
// memcpy(&net_state->report_in, pad, sizeof(gamepad_pad_t));
// webserver_set_pad(pad);
}
static void net_task(usbd_handle_t* handle) {
(void)handle;
webserver_task();
}
const usb_device_driver_t USBD_DRIVER_NET = {
.name = "Net",
.init = net_init,
.task = net_task,
.set_pad = net_set_pad,
.set_audio = NULL,
};

View File

@@ -0,0 +1,314 @@
#include <string.h>
#include "common/usb_def.h"
#include "common/class/rndis_def.h"
#include "log/log.h"
#include "usb/device/drivers/rndis/rndis.h"
#include "netif/ethernet.h"
#define RNDIS_LINK_SPEED 12000000 /* Link baudrate (12Mbit/s for USB-FS) */
#define RNDIS_VENDOR "Wired Opposite" /* NIC vendor name */
#define ENC_BUF_SIZE (OID_LIST_LENGTH * 4 + 32)
#define MAC_OPT NDIS_MAC_OPTION_COPY_LOOKAHEAD_DATA | \
NDIS_MAC_OPTION_RECEIVE_SERIALIZED | \
NDIS_MAC_OPTION_TRANSFERS_NOT_PEND | \
NDIS_MAC_OPTION_NO_LOOPBACK
typedef enum {
RNDIS_STATE_IDLE = 0,
RNDIS_STATE_INITIALIZED,
RNDIS_STATE_DATA_INITIALIZED
} rndis_state_t;
typedef struct {
rndis_state_t state;
uint16_t mtu;
uint8_t mac_addr[6];
uint32_t txok;
uint32_t rxok;
uint32_t txbad;
uint32_t rxbad;
uint32_t oid_packet_filter;
} rndis_t;
static const uint32_t OID_SUPPORT_LIST[] __attribute__((aligned(4))) = {
NDIS_OID_GEN_SUPPORTED_LIST,
NDIS_OID_GEN_HARDWARE_STATUS,
NDIS_OID_GEN_MEDIA_SUPPORTED,
NDIS_OID_GEN_MEDIA_IN_USE,
NDIS_OID_GEN_MAXIMUM_FRAME_SIZE,
NDIS_OID_GEN_LINK_SPEED,
NDIS_OID_GEN_TRANSMIT_BLOCK_SIZE,
NDIS_OID_GEN_RECEIVE_BLOCK_SIZE,
NDIS_OID_GEN_VENDOR_ID,
NDIS_OID_GEN_VENDOR_DESCRIPTION,
NDIS_OID_GEN_VENDOR_DRIVER_VERSION,
NDIS_OID_GEN_CURRENT_PACKET_FILTER,
NDIS_OID_GEN_MAXIMUM_TOTAL_SIZE,
NDIS_OID_GEN_PROTOCOL_OPTIONS,
NDIS_OID_GEN_MAC_OPTIONS,
NDIS_OID_GEN_MEDIA_CONNECT_STATUS,
NDIS_OID_GEN_MAXIMUM_SEND_PACKETS,
NDIS_OID_802_3_PERMANENT_ADDRESS,
NDIS_OID_802_3_CURRENT_ADDRESS,
NDIS_OID_802_3_MULTICAST_LIST,
NDIS_OID_802_3_MAXIMUM_LIST_SIZE,
NDIS_OID_802_3_MAC_OPTIONS
};
static const char *rndis_vendor = RNDIS_VENDOR;
static rndis_t rndis = {0};
// static void rndis_report(void) {
// uint8_t ndis_report[8] = { 0x01,0x00,0x00,0x00,0x00,0x00,0x00,0x00 };
// netd_report(ndis_report, sizeof(ndis_report));
// }
#define VENDOR_DRIVER_VERSION 0x00001000
static int32_t rndis_handle_query(const usb_rndis_msg_query_t* m,
usb_rndis_msg_query_cmplt_t* r) {
int status = USB_RNDIS_STATUS_SUCCESS;
uint32_t val = 0;
const uint8_t* data = (const uint8_t*)&val;
uint16_t size = sizeof(val);
switch (m->Oid) {
case NDIS_OID_GEN_SUPPORTED_LIST:
data = (const uint8_t*)OID_SUPPORT_LIST;
size = sizeof(OID_SUPPORT_LIST);
break;
case NDIS_OID_GEN_VENDOR_DRIVER_VERSION:
val = VENDOR_DRIVER_VERSION;
break;
case NDIS_OID_802_3_CURRENT_ADDRESS:
case NDIS_OID_802_3_PERMANENT_ADDRESS:
data = rndis.mac_addr;
size = sizeof(rndis.mac_addr);
break;
case NDIS_OID_GEN_MEDIA_SUPPORTED:
case NDIS_OID_GEN_MEDIA_IN_USE:
case NDIS_OID_GEN_PHYSICAL_MEDIUM:
val = NDIS_MEDIUM_802_3;
break;
case NDIS_OID_GEN_HARDWARE_STATUS:
val = 0; // NDIS_HARDWARE_STATUS_READY
break;
case NDIS_OID_GEN_LINK_SPEED:
val = RNDIS_LINK_SPEED / 100; // Convert to Kbps
break;
case NDIS_OID_GEN_VENDOR_ID:
val = 0x00FFFFFF; // Vendor ID placeholder
break;
case NDIS_OID_GEN_VENDOR_DESCRIPTION:
data = (const uint8_t*)rndis_vendor;
size = strlen(rndis_vendor) + 1;
break;
case NDIS_OID_GEN_CURRENT_PACKET_FILTER:
val = rndis.oid_packet_filter;
break;
case NDIS_OID_GEN_MAXIMUM_FRAME_SIZE:
val = rndis.mtu - SIZEOF_ETH_HDR;
break;
case NDIS_OID_GEN_MAXIMUM_TOTAL_SIZE:
case NDIS_OID_GEN_TRANSMIT_BLOCK_SIZE:
case NDIS_OID_GEN_RECEIVE_BLOCK_SIZE:
val = rndis.mtu;
break;
case NDIS_OID_GEN_MEDIA_CONNECT_STATUS:
val = NDIS_MEDIA_STATE_CONNECTED;
break;
case NDIS_OID_GEN_RNDIS_CONFIG_PARAMETER:
val = 0;
break;
case NDIS_OID_802_3_MAXIMUM_LIST_SIZE:
val = 1;
break;
case NDIS_OID_802_3_MULTICAST_LIST:
case NDIS_OID_802_3_MAC_OPTIONS:
status = USB_RNDIS_STATUS_NOT_SUPPORTED;
val = 0;
break;
case NDIS_OID_GEN_MAC_OPTIONS:
// val = MAC_OPT; // MAC options
// break;
case NDIS_OID_802_3_RCV_ERROR_ALIGNMENT:
case NDIS_OID_802_3_XMIT_ONE_COLLISION:
case NDIS_OID_802_3_XMIT_MORE_COLLISIONS:
val = 0;
break;
case NDIS_OID_GEN_XMIT_OK:
val = rndis.txok;
break;
case NDIS_OID_GEN_RCV_OK:
val = rndis.rxok;
break;
case NDIS_OID_GEN_RCV_ERROR:
val = rndis.rxbad;
break;
case NDIS_OID_GEN_XMIT_ERROR:
val = rndis.txbad;
break;
case NDIS_OID_GEN_RCV_NO_BUFFER:
val = 0; // No buffer errors
break;
default:
status = USB_RNDIS_STATUS_FAILURE;
val = 0;
break;
}
r->MessageType = USB_RNDIS_QUERY_CMPLT;
r->MessageLength = sizeof(usb_rndis_msg_query_cmplt_t) + size;
r->RequestId = m->RequestId;
r->InformationBufferLength = size;
r->InformationBufferOffset = 16;
r->Status = status;
memcpy(r + 1, data, size);
return r->MessageLength;
}
// #define INFBUF ((uint8_t *)&(m->RequestId) + m->InformationBufferOffset)
// static void rndis_handle_config_parm(const char *data, int keyoffset, int valoffset, int keylen, int vallen)
// {
// (void)data;
// (void)keyoffset;
// (void)valoffset;
// (void)keylen;
// (void)vallen;
// }
// static void rndis_packetFilter(uint32_t newfilter)
// {
// (void)newfilter;
// }
static int32_t rndis_handle_set_msg(const usb_rndis_msg_set_t* m, usb_rndis_msg_set_cmplt_t* r) {
r->MessageType = USB_RNDIS_SET_CMPLT;
r->MessageLength = sizeof(usb_rndis_msg_set_cmplt_t);
r->Status = USB_RNDIS_STATUS_SUCCESS;
r->RequestId = m->RequestId;
switch (m->Oid) {
case NDIS_OID_GEN_RNDIS_CONFIG_PARAMETER:
{
// usb_rndis_msg_config_param_t *p;
// char *ptr = (char *)m;
// ptr += sizeof(usb_rndis_msg_generic_t);
// ptr += m->InformationBufferOffset;
// p = (usb_rndis_msg_config_param_t *) ((void*) ptr);
// rndis_handle_config_parm(ptr, p->ParameterNameOffset, p->ParameterValueOffset, p->ParameterNameLength, p->ParameterValueLength);
}
break;
case NDIS_OID_GEN_CURRENT_PACKET_FILTER:
{
const uint8_t* data = (const uint8_t*)m->RequestId + m->InformationBufferOffset;
memcpy(&rndis.oid_packet_filter, data, sizeof(rndis.oid_packet_filter));
if (rndis.oid_packet_filter) {
// rndis_packetFilter(rndis.oid_packet_filter);
rndis.state = RNDIS_STATE_DATA_INITIALIZED;
} else {
rndis.state = RNDIS_STATE_INITIALIZED;
}
}
break;
case NDIS_OID_GEN_CURRENT_LOOKAHEAD:
break;
case NDIS_OID_GEN_PROTOCOL_OPTIONS:
break;
case NDIS_OID_802_3_MULTICAST_LIST:
break;
/* Power Management: fails */
case NDIS_OID_PNP_ADD_WAKE_UP_PATTERN:
case NDIS_OID_PNP_REMOVE_WAKE_UP_PATTERN:
case NDIS_OID_PNP_ENABLE_WAKE_UP:
default:
r->Status = USB_RNDIS_STATUS_FAILURE;
break;
}
return r->MessageLength;
}
int32_t rndis_handle_msg(const uint8_t* msg, uint8_t* resp_buf, uint16_t resp_buf_len) {
// if (resp_buf_len < (rndis.mtu + sizeof(usb_rndis_msg_data_t))) {
// ogxm_loge("RNDIS: Response buffer too small: %d < %d",
// resp_buf_len, rndis.mtu + sizeof(usb_rndis_msg_data_t));
// return -1;
// }
const usb_rndis_msg_generic_t* m =
(const usb_rndis_msg_generic_t*)msg;
switch (m->MessageType) {
case USB_RNDIS_INITIALIZE_MSG:
ogxm_logv("RNDIS: Initialize message received\n");
{
usb_rndis_msg_init_cmplt_t *r =
(usb_rndis_msg_init_cmplt_t *)resp_buf;
/* r->MessageID is same as before */
r->MessageType = USB_RNDIS_INITIALIZE_CMPLT;
r->MessageLength = sizeof(usb_rndis_msg_init_cmplt_t);
r->RequestId = m->RequestId;
r->MajorVersion = USB_RNDIS_MAJOR_VERSION;
r->MinorVersion = USB_RNDIS_MINOR_VERSION;
r->Status = USB_RNDIS_STATUS_SUCCESS;
r->DeviceFlags = USB_RNDIS_DF_CONNECTIONLESS;
r->Medium = USB_RNDIS_MEDIUM_802_3;
r->MaxPacketsPerTransfer = 1;
r->MaxTransferSize = rndis.mtu + sizeof(usb_rndis_msg_data_t);
r->PacketAlignmentFactor = 0;
r->AfListOffset = 0;
r->AfListSize = 0;
rndis.state = RNDIS_STATE_INITIALIZED;
return r->MessageLength;
}
case USB_RNDIS_QUERY_MSG:
ogxm_logv("RNDIS: Query message received\n");
return rndis_handle_query((const usb_rndis_msg_query_t*)msg,
(usb_rndis_msg_query_cmplt_t*)resp_buf);
case USB_RNDIS_SET_MSG:
ogxm_logv("RNDIS: Set message received\n");
return rndis_handle_set_msg((const usb_rndis_msg_set_t*)msg,
(usb_rndis_msg_set_cmplt_t*)resp_buf);
case USB_RNDIS_RESET_MSG:
ogxm_logv("RNDIS: Reset message received\n");
{
usb_rndis_msg_reset_cmplt_t *r =
(usb_rndis_msg_reset_cmplt_t *)resp_buf;
rndis.state = RNDIS_STATE_IDLE;
r->MessageType = USB_RNDIS_RESET_CMPLT;
r->MessageLength = sizeof(usb_rndis_msg_reset_cmplt_t);
r->Status = USB_RNDIS_STATUS_SUCCESS;
r->AddressingReset = 1; /* Make it look like we did something */
/* r->AddressingReset = 0; - Windows halts if set to 1 for some reason */
return r->MessageLength;
}
break;
case USB_RNDIS_KEEPALIVE_MSG:
ogxm_logv("RNDIS: Keepalive message received\n");
{
usb_rndis_msg_keepalive_cmplt_t* r =
(usb_rndis_msg_keepalive_cmplt_t*)resp_buf;
r->MessageType = USB_RNDIS_KEEPALIVE_CMPLT;
r->MessageLength = sizeof(usb_rndis_msg_keepalive_cmplt_t);
r->RequestId = m->RequestId;
r->Status = USB_RNDIS_STATUS_SUCCESS;
return r->MessageLength;
}
case USB_RNDIS_INITIALIZE_CMPLT:
case USB_RNDIS_QUERY_CMPLT:
case USB_RNDIS_SET_CMPLT:
case USB_RNDIS_RESET_CMPLT:
case USB_RNDIS_KEEPALIVE_CMPLT:
default:
break;
}
ogxm_loge("RNDIS: Unknown message type: %d\n", m->MessageType);
return -1;
}
void rndis_init(uint16_t mtu, uint8_t mac_address[6]) {
rndis.state = RNDIS_STATE_IDLE;
rndis.mtu = mtu;
memcpy(rndis.mac_addr, mac_address, sizeof(rndis.mac_addr));
}

View File

@@ -0,0 +1,22 @@
#pragma once
#include <stdint.h>
#include "common/class/rndis_def.h"
#ifdef __cplusplus
extern "C" {
#endif
#define RNDIS_DATA_OFFSET(msg) (((const usb_rndis_msg_data_t*)(msg))->DataOffset + \
offsetof(usb_rndis_msg_data_t, DataOffset))
void rndis_init(uint16_t mtu, uint8_t mac_address[6]);
// Resp buf len should be at least MTU + 44 bytes, returns size of response
int32_t rndis_handle_msg(const uint8_t* msg, uint8_t* resp_buf, uint16_t resp_buf_len);
// bool rndis_format_frame_in(struct pbuf* p, uint8_t* frame_buf);
#ifdef __cplusplus
}
#endif

View File

@@ -1,6 +1,7 @@
#include <string.h>
#include "common/usb_util.h"
#include "common/class/hid_def.h"
#include "log/log.h"
#include "usbd/usbd.h"
#include "gamepad/range.h"
#include "usb/descriptors/xboxog_gp.h"
@@ -45,6 +46,8 @@ static bool xboxog_gp_get_desc_cb(usbd_handle_t* handle, const usb_ctrl_req_t* r
static bool xboxog_gp_ctrl_xfer_cb(usbd_handle_t* handle, const usb_ctrl_req_t* req) {
xboxog_gp_state_t* xboxog = xboxog_gp_state[handle->port];
ogxm_logv("XBOXOG GP CTRL XFER: %02X %02X %04X %04X %04X\n",
req->bmRequestType, req->bRequest, req->wValue, req->wIndex, req->wLength);
switch (req->bmRequestType & (USB_REQ_TYPE_Msk | USB_REQ_RECIP_Msk)) {
case (USB_REQ_TYPE_CLASS | USB_REQ_RECIP_INTERFACE):
{
@@ -56,6 +59,7 @@ static bool xboxog_gp_ctrl_xfer_cb(usbd_handle_t* handle, const usb_ctrl_req_t*
return usbd_send_ctrl_resp(handle, &xboxog->report_in,
sizeof(xboxog->report_in), NULL);
case USB_REQ_HID_SET_REPORT:
ogxm_logv_hex(req->data, req->wLength, "XBOXOG GP SET REPORT DATA: ");
if (req->wLength >= 4) {
const xboxog_gp_report_out_t* report_out =
(const xboxog_gp_report_out_t*)req->data;
@@ -117,12 +121,13 @@ static void xboxog_gp_configured_cb(usbd_handle_t* handle, uint8_t config) {
static void xboxog_gp_ep_xfer_cb(usbd_handle_t* handle, uint8_t epaddr) {
if (epaddr == XBOXOG_GP_EPADDR_OUT) {
ogxm_logv("XBOXOG GP OUT EP transfer complete\n");
xboxog_gp_state_t* xboxog = xboxog_gp_state[handle->port];
int32_t len = usbd_ep_read(handle, epaddr, &xboxog->report_out,
sizeof(xboxog->report_out));
if ((len >= 4) && (xboxog->report_out.report_id == 0)) {
xboxog->gp_rumble.l = xboxog->report_out.rumble_l;
xboxog->gp_rumble.r = xboxog->report_out.rumble_r;
xboxog->gp_rumble.l = range_uint16_to_uint8(xboxog->report_out.rumble_l);
xboxog->gp_rumble.r = range_uint16_to_uint8(xboxog->report_out.rumble_r);
usb_device_rumble_cb(handle, &xboxog->gp_rumble);
}
}

View File

@@ -0,0 +1,77 @@
/*
* Copyright (c) 2001-2003 Swedish Institute of Computer Science.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. The name of the author may not be used to endorse or promote products
* derived from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR IMPLIED
* WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT
* SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,
* EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT
* OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING
* IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY
* OF SUCH DAMAGE.
*
* This file is part of the lwIP TCP/IP stack.
*
* Author: Adam Dunkels <adam@sics.se>
*
*/
#ifndef __CC_H__
#define __CC_H__
//#include "cpu.h"
typedef int sys_prot_t;
/* define compiler specific symbols */
#if defined (__ICCARM__)
#define PACK_STRUCT_BEGIN
#define PACK_STRUCT_STRUCT
#define PACK_STRUCT_END
#define PACK_STRUCT_FIELD(x) x
#define PACK_STRUCT_USE_INCLUDES
#elif defined (__CC_ARM)
#define PACK_STRUCT_BEGIN __packed
#define PACK_STRUCT_STRUCT
#define PACK_STRUCT_END
#define PACK_STRUCT_FIELD(x) x
#elif defined (__GNUC__)
#define PACK_STRUCT_BEGIN
#define PACK_STRUCT_STRUCT __attribute__ ((__packed__))
#define PACK_STRUCT_END
#define PACK_STRUCT_FIELD(x) x
#elif defined (__TASKING__)
#define PACK_STRUCT_BEGIN
#define PACK_STRUCT_STRUCT
#define PACK_STRUCT_END
#define PACK_STRUCT_FIELD(x) x
#endif
#ifndef LWIP_PLATFORM_ASSERT
#define LWIP_PLATFORM_ASSERT(x) do { if(!(x)) while(1); } while(0)
#endif
#endif /* __CC_H__ */

View File

@@ -0,0 +1,27 @@
<!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.01//EN"
"http://www.w3.org/TR/html4/strict.dtd"
>
<html lang="en">
<head>
<title>Welcome to your Pico</title>
</head>
<body>
<center>
<h1>Welcome to your Pico!</h1>
<!-- Image Map Generated by http://www.image-map.net/ -->
<img src="pico.png" usemap="#image-map">
<map name="image-map">
<area target="" alt="BOOTSEL" title="BOOTSEL" href="/reset_usb_boot" coords="319,97,11" shape="circle">
<area target="" alt="LED" title="LED" href="/toggle_led" coords="341,58,359,79" shape="rect">
</map>
<br><br>
You can click the LED and BOOTSEL button on the picture above.
</center>
</body>
</html>

Binary file not shown.

After

Width:  |  Height:  |  Size: 142 KiB

File diff suppressed because it is too large Load Diff

View File

@@ -0,0 +1,68 @@
/*
* Copyright (c) 2001-2003 Swedish Institute of Computer Science.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. The name of the author may not be used to endorse or promote products
* derived from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR IMPLIED
* WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT
* SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,
* EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT
* OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING
* IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY
* OF SUCH DAMAGE.
*
* This file is part of the lwIP TCP/IP stack.
*
* Author: Simon Goldschmidt
*
*/
#ifndef __LWIPOPTS_H__
#define __LWIPOPTS_H__
/* Prevent having to link sys_arch.c (we don't test the API layers in unit tests) */
#define NO_SYS 1
#define MEM_ALIGNMENT 4
#define LWIP_RAW 0
#define LWIP_NETCONN 0
#define LWIP_SOCKET 0
#define LWIP_DHCP 0
#define LWIP_ICMP 1
#define LWIP_UDP 1
#define LWIP_TCP 1
#define ETH_PAD_SIZE 0
#define LWIP_IP_ACCEPT_UDP_PORT(p) ((p) == PP_NTOHS(67))
#define TCP_MSS (1500 /*mtu*/ - 20 /*iphdr*/ - 20 /*tcphhr*/)
#define TCP_SND_BUF (2 * TCP_MSS)
#define ETHARP_SUPPORT_STATIC_ENTRIES 1
#define LWIP_HTTPD_CGI 1
#define LWIP_HTTPD_SSI 0
#define LWIP_HTTPD_CGI_SSI 0
#define LWIP_HTTPD_SSI_INCLUDE_TAG 0
#define LWIP_HTTPD_CUSTOM_FILES 1
#define LWIP_HTTPD_SUPPORT_POST 1
#define LWIP_HTTPD_SUPPORT_V09 0
#define LWIP_HTTPD_SUPPORT_11_KEEPALIVE 0 // Causes lockups with CGI requests
#define LWIP_HTTPD_ABORT_ON_CLOSE_MEM_ERROR 1
#define HTTPD_USE_CUSTOM_FSDATA 1
#define HTTPD_FSDATA_FILE "../../../../src/webserver/lwip/fsdata.c"
#define LWIP_SINGLE_NETIF 1
#endif /* __LWIPOPTS_H__ */

View File

@@ -0,0 +1,27 @@
#include <stdint.h>
#include <stdbool.h>
#include <pico/sync.h>
#include <pico/time.h>
#include "lwip/sys.h"
static mutex_t* get_lwip_mutex(void) {
static mutex_t mutex;
if (!mutex_is_initialized(&mutex)) {
mutex_init(&mutex);
}
return &mutex;
}
sys_prot_t sys_arch_protect(void) {
mutex_enter_blocking(get_lwip_mutex());
return 0;
}
void sys_arch_unprotect(sys_prot_t pval) {
(void)pval;
mutex_exit(get_lwip_mutex());
}
uint32_t sys_now(void) {
return to_ms_since_boot(get_absolute_time());
}

View File

@@ -0,0 +1,356 @@
/*
* The MIT License (MIT)
*
* Copyright (c) 2015 by Sergey Fetisov <fsenok@gmail.com>
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in all
* copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*/
#include "dhserver.h"
/* DHCP message type */
#define DHCP_DISCOVER 1
#define DHCP_OFFER 2
#define DHCP_REQUEST 3
#define DHCP_DECLINE 4
#define DHCP_ACK 5
#define DHCP_NAK 6
#define DHCP_RELEASE 7
#define DHCP_INFORM 8
/* DHCP options */
enum DHCP_OPTIONS
{
DHCP_PAD = 0,
DHCP_SUBNETMASK = 1,
DHCP_ROUTER = 3,
DHCP_DNSSERVER = 6,
DHCP_HOSTNAME = 12,
DHCP_DNSDOMAIN = 15,
DHCP_MTU = 26,
DHCP_BROADCAST = 28,
DHCP_PERFORMROUTERDISC = 31,
DHCP_STATICROUTE = 33,
DHCP_NISDOMAIN = 40,
DHCP_NISSERVER = 41,
DHCP_NTPSERVER = 42,
DHCP_VENDOR = 43,
DHCP_IPADDRESS = 50,
DHCP_LEASETIME = 51,
DHCP_OPTIONSOVERLOADED = 52,
DHCP_MESSAGETYPE = 53,
DHCP_SERVERID = 54,
DHCP_PARAMETERREQUESTLIST = 55,
DHCP_MESSAGE = 56,
DHCP_MAXMESSAGESIZE = 57,
DHCP_RENEWALTIME = 58,
DHCP_REBINDTIME = 59,
DHCP_CLASSID = 60,
DHCP_CLIENTID = 61,
DHCP_USERCLASS = 77, /* RFC 3004 */
DHCP_FQDN = 81,
DHCP_DNSSEARCH = 119, /* RFC 3397 */
DHCP_CSR = 121, /* RFC 3442 */
DHCP_MSCSR = 249, /* MS code for RFC 3442 */
DHCP_END = 255
};
typedef struct
{
uint8_t dp_op; /* packet opcode type */
uint8_t dp_htype; /* hardware addr type */
uint8_t dp_hlen; /* hardware addr length */
uint8_t dp_hops; /* gateway hops */
uint32_t dp_xid; /* transaction ID */
uint16_t dp_secs; /* seconds since boot began */
uint16_t dp_flags;
uint8_t dp_ciaddr[4]; /* client IP address */
uint8_t dp_yiaddr[4]; /* 'your' IP address */
uint8_t dp_siaddr[4]; /* server IP address */
uint8_t dp_giaddr[4]; /* gateway IP address */
uint8_t dp_chaddr[16]; /* client hardware address */
uint8_t dp_legacy[192];
uint8_t dp_magic[4];
uint8_t dp_options[275]; /* options area */
} DHCP_TYPE;
DHCP_TYPE dhcp_data;
static struct udp_pcb *pcb = NULL;
static const dhcp_config_t *config = NULL;
char magic_cookie[] = {0x63,0x82,0x53,0x63};
static ip4_addr_t get_ip(const uint8_t *pnt)
{
ip4_addr_t result;
memcpy(&result, pnt, sizeof(result));
return result;
}
static void set_ip(uint8_t *pnt, ip4_addr_t value)
{
memcpy(pnt, &value.addr, sizeof(value.addr));
}
static dhcp_entry_t *entry_by_ip(ip4_addr_t ip)
{
int i;
for (i = 0; i < config->num_entry; i++)
if (config->entries[i].addr.addr == ip.addr)
return &config->entries[i];
return NULL;
}
static dhcp_entry_t *entry_by_mac(uint8_t *mac)
{
int i;
for (i = 0; i < config->num_entry; i++)
if (memcmp(config->entries[i].mac, mac, 6) == 0)
return &config->entries[i];
return NULL;
}
static __inline bool is_vacant(dhcp_entry_t *entry)
{
return memcmp("\0\0\0\0\0", entry->mac, 6) == 0;
}
static dhcp_entry_t *vacant_address(void)
{
int i;
for (i = 0; i < config->num_entry; i++)
if (is_vacant(config->entries + i))
return config->entries + i;
return NULL;
}
static __inline void free_entry(dhcp_entry_t *entry)
{
memset(entry->mac, 0, 6);
}
uint8_t *find_dhcp_option(uint8_t *attrs, int size, uint8_t attr)
{
int i = 0;
while ((i + 1) < size)
{
int next = i + attrs[i + 1] + 2;
if (next > size) return NULL;
if (attrs[i] == attr)
return attrs + i;
i = next;
}
return NULL;
}
int fill_options(void *dest,
uint8_t msg_type,
const char *domain,
ip4_addr_t dns,
int lease_time,
ip4_addr_t serverid,
ip4_addr_t router,
ip4_addr_t subnet)
{
uint8_t *ptr = (uint8_t *)dest;
/* ACK message type */
*ptr++ = 53;
*ptr++ = 1;
*ptr++ = msg_type;
/* dhcp server identifier */
*ptr++ = DHCP_SERVERID;
*ptr++ = 4;
set_ip(ptr, serverid);
ptr += 4;
/* lease time */
*ptr++ = DHCP_LEASETIME;
*ptr++ = 4;
*ptr++ = (lease_time >> 24) & 0xFF;
*ptr++ = (lease_time >> 16) & 0xFF;
*ptr++ = (lease_time >> 8) & 0xFF;
*ptr++ = (lease_time >> 0) & 0xFF;
/* subnet mask */
*ptr++ = DHCP_SUBNETMASK;
*ptr++ = 4;
set_ip(ptr, subnet);
ptr += 4;
/* router */
if (router.addr != 0)
{
*ptr++ = DHCP_ROUTER;
*ptr++ = 4;
set_ip(ptr, router);
ptr += 4;
}
/* domain name */
if (domain != NULL)
{
int len = strlen(domain);
*ptr++ = DHCP_DNSDOMAIN;
*ptr++ = len;
memcpy(ptr, domain, len);
ptr += len;
}
/* domain name server (DNS) */
if (dns.addr != 0)
{
*ptr++ = DHCP_DNSSERVER;
*ptr++ = 4;
set_ip(ptr, dns);
ptr += 4;
}
/* end */
*ptr++ = DHCP_END;
return ptr - (uint8_t *)dest;
}
static void udp_recv_proc(void *arg, struct udp_pcb *upcb, struct pbuf *p, const ip_addr_t *addr, u16_t port)
{
uint8_t *ptr;
dhcp_entry_t *entry;
struct pbuf *pp;
struct netif *netif = netif_get_by_index(p->if_idx);
(void)arg;
(void)addr;
unsigned n = p->len;
if (n > sizeof(dhcp_data)) n = sizeof(dhcp_data);
memcpy(&dhcp_data, p->payload, n);
ptr = find_dhcp_option(dhcp_data.dp_options, sizeof(dhcp_data.dp_options), DHCP_MESSAGETYPE);
if (ptr == NULL)
{
pbuf_free(p);
return;
}
switch (ptr[2])
{
case DHCP_DISCOVER:
entry = entry_by_mac(dhcp_data.dp_chaddr);
if (entry == NULL) entry = vacant_address();
if (entry == NULL) break;
dhcp_data.dp_op = 2; /* reply */
dhcp_data.dp_secs = 0;
dhcp_data.dp_flags = 0;
set_ip(dhcp_data.dp_yiaddr, entry->addr);
memcpy(dhcp_data.dp_magic, magic_cookie, 4);
memset(dhcp_data.dp_options, 0, sizeof(dhcp_data.dp_options));
fill_options(dhcp_data.dp_options,
DHCP_OFFER,
config->domain,
config->dns,
entry->lease,
*netif_ip4_addr(netif),
config->router,
*netif_ip4_netmask(netif));
pp = pbuf_alloc(PBUF_TRANSPORT, sizeof(dhcp_data), PBUF_POOL);
if (pp == NULL) break;
memcpy(pp->payload, &dhcp_data, sizeof(dhcp_data));
udp_sendto(upcb, pp, IP_ADDR_BROADCAST, port);
pbuf_free(pp);
break;
case DHCP_REQUEST:
/* 1. find requested ipaddr in option list */
ptr = find_dhcp_option(dhcp_data.dp_options, sizeof(dhcp_data.dp_options), DHCP_IPADDRESS);
if (ptr == NULL) break;
if (ptr[1] != 4) break;
ptr += 2;
/* 2. does hw-address registered? */
entry = entry_by_mac(dhcp_data.dp_chaddr);
if (entry != NULL) free_entry(entry);
/* 3. find requested ipaddr */
entry = entry_by_ip(get_ip(ptr));
if (entry == NULL) break;
if (!is_vacant(entry)) break;
/* 4. fill struct fields */
memcpy(dhcp_data.dp_yiaddr, ptr, 4);
dhcp_data.dp_op = 2; /* reply */
dhcp_data.dp_secs = 0;
dhcp_data.dp_flags = 0;
memcpy(dhcp_data.dp_magic, magic_cookie, 4);
/* 5. fill options */
memset(dhcp_data.dp_options, 0, sizeof(dhcp_data.dp_options));
fill_options(dhcp_data.dp_options,
DHCP_ACK,
config->domain,
config->dns,
entry->lease,
*netif_ip4_addr(netif),
config->router,
*netif_ip4_netmask(netif));
/* 6. send ACK */
pp = pbuf_alloc(PBUF_TRANSPORT, sizeof(dhcp_data), PBUF_POOL);
if (pp == NULL) break;
memcpy(entry->mac, dhcp_data.dp_chaddr, 6);
memcpy(pp->payload, &dhcp_data, sizeof(dhcp_data));
udp_sendto(upcb, pp, IP_ADDR_BROADCAST, port);
pbuf_free(pp);
break;
default:
break;
}
pbuf_free(p);
}
err_t dhserv_init(const dhcp_config_t *c)
{
err_t err;
udp_init();
dhserv_free();
pcb = udp_new();
if (pcb == NULL)
return ERR_MEM;
err = udp_bind(pcb, IP_ADDR_ANY, c->port);
if (err != ERR_OK)
{
dhserv_free();
return err;
}
udp_recv(pcb, udp_recv_proc, NULL);
config = c;
return ERR_OK;
}
void dhserv_free(void)
{
if (pcb == NULL) return;
udp_remove(pcb);
pcb = NULL;
}

View File

@@ -0,0 +1,68 @@
/*
* The MIT License (MIT)
*
* Copyright (c) 2015 by Sergey Fetisov <fsenok@gmail.com>
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in all
* copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*/
/*
* version: 1.0 demo (7.02.2015)
* brief: tiny dhcp ipv4 server using lwip (pcb)
* ref: https://lists.gnu.org/archive/html/lwip-users/2012-12/msg00016.html
*/
#ifndef DHSERVER_H
#define DHSERVER_H
#include <stdint.h>
#include <stdbool.h>
#include <stdio.h>
#include <string.h>
#include "lwip/err.h"
#include "lwip/udp.h"
#include "netif/etharp.h"
typedef struct dhcp_entry
{
uint8_t mac[6];
ip4_addr_t addr;
uint32_t lease;
} dhcp_entry_t;
typedef struct dhcp_config
{
ip4_addr_t router;
uint16_t port;
ip4_addr_t dns;
const char *domain;
int num_entry;
dhcp_entry_t *entries;
} dhcp_config_t;
#ifdef __cplusplus
extern "C" {
#endif
err_t dhserv_init(const dhcp_config_t *c);
void dhserv_free(void);
#ifdef __cplusplus
}
#endif
#endif /* DHSERVER_H */

View File

@@ -0,0 +1,200 @@
/*
* The MIT License (MIT)
*
* Copyright (c) 2015 by Sergey Fetisov <fsenok@gmail.com>
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in all
* copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*/
/*
* version: 1.0 demo (7.02.2015)
* brief: tiny dns ipv4 server using lwip (pcb)
*/
#include "dnserver.h"
#define DNS_MAX_HOST_NAME_LEN 128
static struct udp_pcb *pcb = NULL;
dns_query_proc_t query_proc = NULL;
#pragma pack(push, 1)
typedef struct
{
#if BYTE_ORDER == LITTLE_ENDIAN
uint8_t rd: 1, /* Recursion Desired */
tc: 1, /* Truncation Flag */
aa: 1, /* Authoritative Answer Flag */
opcode: 4, /* Operation code */
qr: 1; /* Query/Response Flag */
uint8_t rcode: 4, /* Response Code */
z: 3, /* Zero */
ra: 1; /* Recursion Available */
#else
uint8_t qr: 1, /* Query/Response Flag */
opcode: 4, /* Operation code */
aa: 1, /* Authoritative Answer Flag */
tc: 1, /* Truncation Flag */
rd: 1; /* Recursion Desired */
uint8_t ra: 1, /* Recursion Available */
z: 3, /* Zero */
rcode: 4; /* Response Code */
#endif
} dns_header_flags_t;
typedef struct
{
uint16_t id;
dns_header_flags_t flags;
uint16_t n_record[4];
} dns_header_t;
typedef struct dns_answer
{
uint16_t name;
uint16_t type;
uint16_t Class;
uint32_t ttl;
uint16_t len;
uint32_t addr;
} dns_answer_t;
#pragma pack(pop)
typedef struct dns_query
{
char name[DNS_MAX_HOST_NAME_LEN];
uint16_t type;
uint16_t Class;
} dns_query_t;
static uint16_t get_uint16(const uint8_t *pnt)
{
uint16_t result;
memcpy(&result, pnt, sizeof(result));
return result;
}
static int parse_next_query(void *data, int size, dns_query_t *query)
{
int len;
int labels;
uint8_t *ptr;
len = 0;
labels = 0;
ptr = (uint8_t *)data;
while (true)
{
uint8_t lable_len;
if (size <= 0) return -1;
lable_len = *ptr++;
size--;
if (lable_len == 0) break;
if (labels > 0)
{
if (len == DNS_MAX_HOST_NAME_LEN) return -2;
query->name[len++] = '.';
}
if (lable_len > size) return -1;
if (len + lable_len >= DNS_MAX_HOST_NAME_LEN) return -2;
memcpy(&query->name[len], ptr, lable_len);
len += lable_len;
ptr += lable_len;
size -= lable_len;
labels++;
}
if (size < 4) return -1;
query->name[len] = 0;
query->type = get_uint16(ptr);
ptr += 2;
query->Class = get_uint16(ptr);
ptr += 2;
return ptr - (uint8_t *)data;
}
static void udp_recv_proc(void *arg, struct udp_pcb *upcb, struct pbuf *p, const ip_addr_t *addr, u16_t port)
{
int len;
dns_header_t *header;
static dns_query_t query;
struct pbuf *out;
ip4_addr_t host_addr;
dns_answer_t *answer;
(void)arg;
if (p->len <= sizeof(dns_header_t)) goto error;
header = (dns_header_t *)p->payload;
if (header->flags.qr != 0) goto error;
if (ntohs(header->n_record[0]) != 1) goto error;
len = parse_next_query(header + 1, p->len - sizeof(dns_header_t), &query);
if (len < 0) goto error;
if (!query_proc(query.name, &host_addr)) goto error;
len += sizeof(dns_header_t);
out = pbuf_alloc(PBUF_TRANSPORT, len + 16, PBUF_POOL);
if (out == NULL) goto error;
memcpy(out->payload, p->payload, len);
header = (dns_header_t *)out->payload;
header->flags.qr = 1;
header->n_record[1] = htons(1);
answer = (struct dns_answer *)((uint8_t *)out->payload + len);
answer->name = htons(0xC00C);
answer->type = htons(1);
answer->Class = htons(1);
answer->ttl = htonl(32);
answer->len = htons(4);
answer->addr = host_addr.addr;
udp_sendto(upcb, out, addr, port);
pbuf_free(out);
error:
pbuf_free(p);
}
err_t dnserv_init(const ip_addr_t *bind, uint16_t port, dns_query_proc_t qp)
{
err_t err;
udp_init();
dnserv_free();
pcb = udp_new();
if (pcb == NULL)
return ERR_MEM;
err = udp_bind(pcb, bind, port);
if (err != ERR_OK)
{
dnserv_free();
return err;
}
udp_recv(pcb, udp_recv_proc, NULL);
query_proc = qp;
return ERR_OK;
}
void dnserv_free(void)
{
if (pcb == NULL) return;
udp_remove(pcb);
pcb = NULL;
}

View File

@@ -0,0 +1,53 @@
/*
* The MIT License (MIT)
*
* Copyright (c) 2015 by Sergey Fetisov <fsenok@gmail.com>
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in all
* copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*/
/*
* version: 1.0 demo (7.02.2015)
* brief: tiny dns ipv4 server using lwip (pcb)
*/
#ifndef DNSERVER
#define DNSERVER
#include <stdint.h>
#include <stdbool.h>
#include <stdio.h>
#include <string.h>
#include "lwip/def.h"
#include "lwip/err.h"
#include "lwip/udp.h"
#include "netif/etharp.h"
typedef bool (*dns_query_proc_t)(const char *name, ip4_addr_t *addr);
#ifdef __cplusplus
extern "C" {
#endif
err_t dnserv_init(const ip_addr_t *bind, uint16_t port, dns_query_proc_t query_proc);
void dnserv_free(void);
#ifdef __cplusplus
}
#endif
#endif

View File

@@ -0,0 +1,185 @@
#include <pico/sync.h>
#include <pico/time.h>
#include <pico/unique_id.h>
#include "lwip/init.h"
#include "lwip/sys.h"
#include "lwip/timeouts.h"
#include "lwip/apps/httpd.h"
#include "log/log.h"
#include "led/led.h"
#include "shared.h"
#include "webserver/networking/dhserver.h"
#include "webserver/networking/dnserver.h"
#include "webserver/webserver.h"
typedef struct {
bool inited;
// uint16_t mtu;
netif_linkoutput_fn linkoutput_cb;
gamepad_rumble_cb_t rumble_cb;
gamepad_pad_t pad;
struct netif netif_data;
uint8_t mac_address[6];
} webserver_state_t;
static const ip_addr_t IP_ADDR = IPADDR4_INIT_BYTES(192, 168, 7, 1);
static const ip_addr_t NETMASK = IPADDR4_INIT_BYTES(255, 255, 255, 0);
static const ip_addr_t GATEWAY = IPADDR4_INIT_BYTES(0, 0, 0, 0);
/* database IP addresses that can be offered to the host; this must be in RAM to store assigned MAC addresses */
static dhcp_entry_t ENTRIES[] = {
/* mac ip address lease time */
{ {0}, IPADDR4_INIT_BYTES(192, 168, 7, 2), 24 * 60 * 60 },
{ {0}, IPADDR4_INIT_BYTES(192, 168, 7, 3), 24 * 60 * 60 },
{ {0}, IPADDR4_INIT_BYTES(192, 168, 7, 4), 24 * 60 * 60 },
};
static const dhcp_config_t DHCP_CONFIG = {
.router = IPADDR4_INIT_BYTES(0, 0, 0, 0), /* router address (if any) */
.port = 67, /* listen port */
.dns = IPADDR4_INIT_BYTES(192, 168, 7, 1), /* dns server (if any) */
"", /* dns suffix */
LWIP_ARRAYSIZE(ENTRIES), /* num entry */
ENTRIES /* entries */
};
static webserver_state_t webserver_state = {0};
// let our webserver do some dynamic handling
static const char *cgi_toggle_led(int iIndex, int iNumParams, char *pcParam[], char *pcValue[]) {
static bool led_state = false;
led_state = !led_state;
led_set_on(led_state);
return "/index.html";
}
static const char *cgi_reset_usb_boot(int iIndex, int iNumParams, char *pcParam[], char *pcValue[]) {
// reset_usb_boot(0, 0);
pico_full_reboot();
return "/index.html";
}
static const tCGI CGI_HANDLERS[] = {
{
"/toggle_led",
cgi_toggle_led
},
{
"/reset_usb_boot",
cgi_reset_usb_boot
}
};
static err_t netif_init_cb(struct netif *netif) {
if (netif == NULL) {
ogxm_loge("WEBSERVER: Netif pointer cannot be NULL");
return ERR_ARG;
}
netif->mtu = WEBSERVER_MTU;
netif->flags = NETIF_FLAG_BROADCAST | NETIF_FLAG_ETHARP | NETIF_FLAG_LINK_UP | NETIF_FLAG_UP;
netif->linkoutput = webserver_state.linkoutput_cb;
netif->output = etharp_output;
netif->state = NULL;
netif->name[0] = 'E';
netif->name[1] = 'X';
return ERR_OK;
}
bool dns_query_cb(const char *name, ip4_addr_t *addr) {
ogxm_logv("WEBSERVER: DNS query for %s\n", name);
// if (0 == strcmp(name, "wizio.pico")) {
*addr = IP_ADDR;
return true;
// }
// return false;
}
// Public API
bool webserver_init(netif_linkoutput_fn linkoutput_cb, gamepad_rumble_cb_t rumble_cb) {
if (webserver_state.inited) {
ogxm_logd("WEBSERVER: Already initialized\n");
return true;
}
if (linkoutput_cb == NULL) {
ogxm_loge("WEBSERVER: Link output callback cannot be NULL\n");
return false;
}
webserver_state.inited = true;
webserver_state.linkoutput_cb = linkoutput_cb;
lwip_init();
struct netif *netif = &webserver_state.netif_data;
pico_unique_board_id_t board_id;
pico_get_unique_board_id(&board_id);
webserver_state.mac_address[0] = 0x02;
memcpy(webserver_state.mac_address + 1, board_id.id, sizeof(webserver_state.mac_address) - 1);
memcpy(netif->hwaddr, webserver_state.mac_address, sizeof(webserver_state.mac_address));
netif = netif_add(netif, &IP_ADDR, &NETMASK, &GATEWAY, NULL, netif_init_cb, ip_input);
netif_set_default(netif);
return true;
}
void webserver_wait_ready(webserver_wait_loop_cb_t wait_loop_cb) {
while (!netif_is_up(&webserver_state.netif_data)) {
if (wait_loop_cb != NULL) {
wait_loop_cb();
}
}
ogxm_logd("WEBSERVER: Network interface initialized\n");
while (dhserv_init(&DHCP_CONFIG) != ERR_OK) {
if (wait_loop_cb != NULL) {
wait_loop_cb();
}
}
ogxm_logd("WEBSERVER: DHCP server initialized\n");
while (dnserv_init(&IP_ADDR, 53, dns_query_cb) != ERR_OK) {
if (wait_loop_cb != NULL) {
wait_loop_cb();
}
}
ogxm_logd("WEBSERVER: DNS server initialized\n");
}
void webserver_start(void) {
httpd_init();
http_set_cgi_handlers(CGI_HANDLERS, LWIP_ARRAYSIZE(CGI_HANDLERS));
ogxm_logi("WEBSERVER: Starting with MTU %d, MAC: %02x:%02x:%02x:%02x:%02x:%02x\n,",
WEBSERVER_MTU,
webserver_state.mac_address[0],
webserver_state.mac_address[1],
webserver_state.mac_address[2],
webserver_state.mac_address[3],
webserver_state.mac_address[4],
webserver_state.mac_address[5]);
}
void webserver_task(void) {
if (!webserver_state.inited) {
return;
}
sys_check_timeouts();
}
void webserver_set_frame(const uint8_t* frame, uint16_t len) {
struct pbuf* p = pbuf_alloc(PBUF_RAW, len, PBUF_RAM);
if (p == NULL) {
ogxm_loge("WEBSERVER: Failed to allocate pbuf for received data\n");
return;
}
memcpy(p->payload, frame, len);
if (ethernet_input(p, &webserver_state.netif_data) != ERR_OK) {
pbuf_free(p);
}
}
void webserver_get_mac_addr(uint8_t mac[6]) {
if (mac == NULL) {
ogxm_loge("WEBSERVER: MAC address pointer cannot be NULL");
return;
}
memcpy(mac, webserver_state.mac_address, sizeof(webserver_state.mac_address));
}

View File

@@ -0,0 +1,26 @@
#pragma once
#include <stdint.h>
#include "lwip/netif.h"
#include "gamepad/gamepad.h"
#include "gamepad/callbacks.h"
#ifdef __cplusplus
extern "C" {
#endif
#define WEBSERVER_MTU 1500U
typedef void (*webserver_wait_loop_cb_t)(void);
bool webserver_init(netif_linkoutput_fn linkoutput_cb, gamepad_rumble_cb_t rumble_cb);
void webserver_wait_ready(webserver_wait_loop_cb_t wait_loop_cb);
void webserver_start(void);
void webserver_task(void);
void webserver_set_frame(const uint8_t* frame, uint16_t len);
void webserver_get_mac_addr(uint8_t mac[6]);
void webserver_set_pad(const gamepad_pad_t* pad);
#ifdef __cplusplus
}
#endif

Binary file not shown.

After

Width:  |  Height:  |  Size: 1.8 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 220 KiB

View File

@@ -0,0 +1,226 @@
<!DOCTYPE html>
<html lang="en">
<head>
<meta charset="UTF-8">
<meta name="viewport" content="width=device-width, initial-scale=1.0">
<meta http-equiv="X-UA-Compatible" content="ie=edge">
<title>OGX-Mini Settings</title>
<link rel="stylesheet" href="style.css">
</head>
<body>
<div class="container">
<div class="header">
<div>
<h1>OGX-Mini</h1>
</div>
<div id="subheader" class="subheader">
<h3></h3>
</div>
</div>
<div class="separator"></div>
<div id="errorTxt" class="error hidden">
⚠️ An error occurred
<br>
</div>
<div class="connectPanel show" id="connectPanel">
<h3>Settings</h3>
<button class="connectButton" id="connectUsb">Connect via USB</button>
<button class="connectButton" id="connectBt">Connect via Bluetooth</button><br><br>
<label><b>Minimum firmware required:</b> OGX-Mini v1.0.0-alpha3</label><br><br>
<label><b>Note:</b> To ensure your OGX-Mini (wired) adapter is in WebApp mode, hold Start + Left Bumper + Right Bumper for 3 seconds.</label>
<div class="separator"></div>
<h3>Update Firmware</h3>
<button class="" id="connectOgxmW">OGX-Mini Wireless</button>
</div>
<div class="programPanel hidden" id="programPanel">
<label>
<img src="images/OGXMW_Boot.jpg" alt="OGX-Mini Boot Button" width="300" height="300">
<div class="separator"></div>
<b>Step 1:</b> Hold down the <b>BOOT</b> button on your OGX-Mini Wireless while plugging it into your computer.<br>
<b>Step 2:</b> Click <b>Update Part 1</b> and select the <b>RPI-RP2</b> drive from your file explorer.<br>
<b>Step 3:</b> Click <b>Update Part 2</b> and select <b>OGX-Mini</b> from the dropdown menu.<br><br>
<b>Note:</b> Do not remove your adapter while it is being updated. If the update fails, remove the adapter and plug it back in while holding the BOOT button, then reload this page to restart the process.<br>
</label>
<div class="separator"></div>
<button id="button-programPico">Update Part 1</button>
<button id="button-programEsp32">Update Part 2</button>
<div class="programLogPanel">
<textarea id="programLog" rows="16" cols="80" readonly></textarea>
</div>
</div>
<div class="settingsPanel hidden" id="settingsPanel">
<div class="triPanel">
<div class="section">
<div class="header">
<h3>Device Mode</h3>
</div>
<div class="dropDown">
<select id="dropdown-deviceMode"></select>
</div>
</div>
<div class="section">
<div class="header">
<h3>Gamepads</h3>
</div>
<div class="dropDown">
<select id="dropdown-playerIdx"></select>
</div>
</div>
<div class="section">
<h3>Profile</h3>
<select id="dropdown-profileId"></select>
</div>
</div>
<div class="togglePanelControl">
<div class="header">
<h3>Axis Settings</h3>
</div>
<div class="buttonPanel">
<button id="button-toggleAxisSettings">Hide</button>
</div>
</div>
<div class="axisSettingsPanel" id="axisSettingsPanel">
<div class="joystickPanel">
<div class="leftPanel">
<div class="headerButtonPair">
<div class="header">
<h4>Left Joystick</h4>
</div>
<div class="button">
<label for="checkbox-previewJoy-left">Preview</label>
<input type="checkbox" id="checkbox-previewJoy-left" class="invertCheckbox">
</div>
</div>
<div class="canvasContainer">
<canvas id="canvasJoystickBackground-left" width="260" height="260"></canvas>
<canvas id="canvasJoystickSettings-left" width="260" height="260"></canvas>
<canvas id="canvasJoystickCursor-left" width="260" height="260"></canvas>
</div>
<div class="joystickSettings">
<div id="joystickInput-left" class="joystickInput"></div>
</div>
</div>
<div class="rightPanel">
<div class="headerButtonPair">
<div class="header">
<h4>Right Joystick</h4>
</div>
<div class="button">
<label for="checkbox-previewJoy-right">Preview</label>
<input type="checkbox" id="checkbox-previewJoy-right" class="invertCheckbox">
</div>
</div>
<div class="canvasContainer">
<canvas id="canvasJoystickBackground-right" width="260" height="260"></canvas>
<canvas id="canvasJoystickSettings-right" width="260" height="260"></canvas>
<canvas id="canvasJoystickCursor-right" width="260" height="260"></canvas>
</div>
<div class="joystickSettings">
<div id="joystickInput-right" class="joystickInput"></div>
</div>
</div>
</div>
<div class="triggersPanel">
<div class="leftPanel">
<div class="headerButtonPair">
<div class="header">
<h4>Left Trigger</h4>
</div>
<div class="button">
<label for="checkbox-previewTrigger-left">Preview</label>
<input type="checkbox" id="checkbox-previewTrigger-left" class="invertCheckbox">
</div>
</div>
<div class="canvasContainer">
<canvas id="canvasTriggerBackground-left" width="300" height="50"></canvas>
<canvas id="canvasTriggerSettings-left" width="300" height="50"></canvas>
<canvas id="canvasTriggerCursor-left" width="300" height="50"></canvas>
</div>
<div class="triggerSettings">
<div id="triggerInput-left" class="triggerInput"></div>
</div>
</div>
<div class="rightPanel">
<div class="headerButtonPair">
<div class="header">
<h4>Right Trigger</h4>
</div>
<div class="button">
<label for="checkbox-previewTrigger-right">Preview</label>
<input type="checkbox" id="checkbox-previewTrigger-right" class="invertCheckbox">
</div>
</div>
<div class="canvasContainer">
<canvas id="canvasTriggerBackground-right" width="300" height="50"></canvas>
<canvas id="canvasTriggerSettings-right" width="300" height="50"></canvas>
<canvas id="canvasTriggerCursor-right" width="300" height="50"></canvas>
</div>
<div class="triggerSettings">
<div id="triggerInput-right" class="triggerInput"></div>
</div>
</div>
</div>
</div>
<div class="togglePanelControl">
<div class="header">
<h3>Digital Mappings</h3>
</div>
<div class="buttonPanel">
<button id="button-toggleDigitalButtons">Hide</button>
</div>
</div>
<div id="digitalButtonsPanel" class="digitalButtonsPanel">
<h4>D-Pad</h4>
<div class="dropdownGrid">
<div id="digitalDpadInput-left" class="digitalDpadInput"></div>
<div id="digitalDpadInput-right" class="digitalDpadInput"></div>
</div>
<h4>Buttons</h4>
<div class="dropdownGrid">
<div id="digitalButtonInput-left" class="digitalButtonInput"></div>
<div id="digitalButtonInput-right" class="digitalButtonInput"></div>
</div>
</div>
<div class="togglePanelControl">
<div class="header">
<h3>Analog Mappings</h3>
</div>
<div class="buttonPanel">
<button id="button-toggleAnalogButtons">Hide</button>
</div>
</div>
<div id="analogButtonsPanel" class="analogButtonsPanel">
<div class="analogEnabled">
<label for="checkbox-analogEnabled">Enable Analog Buttons</label>
<input type="checkbox" id="checkbox-analogEnabled" class="invertCheckbox">
</div>
<div class="dropdownGrid">
<div id="analogButtonsInput-left" class="analogButtonsInput"></div>
<div id="analogButtonsInput-right" class="analogButtonsInput"></div>
</div>
</div>
<div class="controlsPanel">
<button class="controlsButton" id="button-saveProfile">Save Profile</button>
<button class="controlsButton" id="button-reloadProfile">Reload Profile</button>
<button class="controlsButton" id="button-loadDefaults">Load Defaults</button>
<button class="controlsButton" id="button-disconnect">Disconnect</button>
</div>
</div>
</div>
<script type="module" src="index.js"></script>
<script src="https://cdn.jsdelivr.net/npm/crypto-js@4.1.1/crypto-js.js"></script>
</body>

View File

@@ -0,0 +1,18 @@
import { UserSettings } from "./modules/userSettings.js";
import { USB } from './modules/com/usbSerial.js';
import { BT } from './modules/com/bluetooth.js';
import { UsbEsp32 } from './modules/com/usbEsp32.js';
document.addEventListener("DOMContentLoaded", () => {
document.getElementById('connectUsb').addEventListener('click', async () => {
await USB.connect();
});
document.getElementById('connectBt').addEventListener('click', async () => {
await BT.connect();
});
document.getElementById('connectOgxmW').addEventListener('click', async () => {
await UsbEsp32.connect();
});
});

View File

@@ -0,0 +1,345 @@
import { BTInterface } from "./bluetoothInterface.js";
import { UserSettings } from "../userSettings.js";
import { UI } from "../uiSettings.js";
import { Gamepad } from "../gamepad.js";
import { Mutex } from "../mutex.js";
class BTManager {
static #getUuid(uuidSuffix) {
const UUIDPrefix = '12345678-1234-1234-1234-1234567890';
return `${UUIDPrefix}${uuidSuffix}`;
}
static UUID = Object.freeze({
PRIMARY : this.#getUuid('12'),
FIRMWARE_VER : this.#getUuid('20'),
FIRMWARE_NAME : this.#getUuid('21'),
SETUP_READ : this.#getUuid('30'),
SETUP_WRITE : this.#getUuid('31'),
GET_SETUP : this.#getUuid('32'),
PROFILE : this.#getUuid('40'),
GAMEPAD : this.#getUuid('50'),
});
static #PACKET_MAX_LEN = Object.freeze(20);
static #SETUP_PACKET_LEN = Object.freeze(4);
static #SETUP_PACKET = Object.freeze([
{ key: "deviceMode", size: 1 },
{ key: "maxGamepads", size: 1 },
{ key: "playerIdx", size: 1 },
{ key: "profileId", size: 1 },
// { key: "dataLen", size: 1 },
]);
#interface = null;
#mutex = null;
constructor() {
this.#interface = new BTInterface();
this.#mutex = new Mutex();
}
async init() {
const options = {
filters: [
{ name: "OGX-Wireless" },
{ name: "OGX-Wireless-Lite" },
{ name: "OGX-Mini" }
],
acceptAllDevices: false,
// acceptAllDevices: true,
optionalServices: [BTManager.UUID.PRIMARY]
};
if (await this.#interface.connect(BTManager.UUID.PRIMARY, options)) {
this.#interface.setDisconnectCb(() => {
window.location.reload();
});
return true;
}
console.warn('Failed to connect to Bluetooth device');
this.#interface.disconnect();
return false;
}
async getSetup(userSettings) {
await this.#mutex.lock();
const buffer = await this.#tryRead(BTManager.UUID.GET_SETUP);
if (!buffer || buffer.length === 0) {
console.warn('Failed to read setup data');
return false;
}
let offset = 0;
let setup = {};
for (let i = 0; i < BTManager.#SETUP_PACKET_LEN; i++) {
const packet = BTManager.#SETUP_PACKET[i];
setup[packet.key] = buffer[offset];
offset += packet.size;
}
userSettings.deviceMode = setup.deviceMode;
userSettings.maxGamepads = setup.maxGamepads;
userSettings.playerIdx = setup.playerIdx;
userSettings.profile.profileId = setup.profileId;
this.#mutex.unlock();
}
async getProfileById(userSettings) {
const setup = {
deviceMode: userSettings.deviceMode,
maxGamepads: userSettings.maxGamepads,
playerIdx: 0xFF,
profileId: userSettings.profile.profileId,
}
return await this.#readProfile(setup, userSettings);
}
async getProfileByIdx(userSettings) {
const setup = {
deviceMode: userSettings.deviceMode,
maxGamepads: userSettings.maxGamepads,
playerIdx: userSettings.playerIdx,
profileId: 0xFF,
}
return await this.#readProfile(setup, userSettings);
}
async saveProfile(userSettings) {
await this.stopGamepadTask();
await this.#mutex.lock();
await this.#sleep(500);
const header = {
deviceMode: userSettings.deviceMode,
maxGamepads: userSettings.maxGamepads,
playerIdx: userSettings.playerIdx,
profileId: userSettings.profile.profileId,
};
async function save() {
let success = false;
success = await this.#tryWrite(
BTManager.UUID.SETUP_WRITE,
new Uint8Array(Object.values(header))
);
if (!success) {
console.warn('Failed to write setup packet');
return false;
}
let profileOffset = 0;
const profileData = userSettings.getProfileBytes();
success = false;
while (profileOffset < UserSettings.PROFILE_LENGTH) {
const chunkLen = Math.min(
UserSettings.PROFILE_LENGTH - profileOffset,
BTManager.#PACKET_MAX_LEN
);
let buffer = new Uint8Array(chunkLen);
buffer.set(profileData.subarray(profileOffset, profileOffset + chunkLen), 0);
success = await this.#tryWrite(BTManager.UUID.PROFILE, buffer);
if (!success) {
console.warn('Failed to write profile chunk');
return false;
}
profileOffset += chunkLen;
}
};
let success = await save.bind(this)();
await this.#sleep(1000);
if (this.#interface.isConnected()) {
this.runGamepadTask(userSettings);
} else {
this.disconnect();
}
this.#mutex.unlock();
return success;
}
#gpTimer = null;
static #GP_INTERVAL = Object.freeze(100);
async runGamepadTask(userSettings) {
this.#gpTimer = setInterval(async () => {
if (!this.#interface.isConnected()) {
return;
}
if (!(await this.#mutex.tryLock())) {
return;
}
const gamepad = await this.#getGamepad();
if (!gamepad) {
this.#mutex.unlock();
return;
}
UI.drawGamepadInput(gamepad, userSettings);
this.#mutex.unlock();
}, BTManager.#GP_INTERVAL);
}
async stopGamepadTask() {
await this.#mutex.lock();
clearInterval(this.#gpTimer);
this.#mutex.unlock();
}
async disconnect() {
await this.stopGamepadTask();
await this.#mutex.lock();
if (this.#interface.isConnected()) {
await this.#interface.disconnect();
}
this.#mutex.unlock();
}
async #getGamepad() {
const buffer = await this.#interface.read(BTManager.UUID.GAMEPAD);
if (!buffer || buffer.length === 0) {
console.warn('Failed to read gamepad data');
return null;
}
const gamepad = new Gamepad();
gamepad.setReportFromBytes(buffer);
return gamepad;
}
async #readProfile(setup, userSettings) {
async function read() {
let success = await this.#tryWrite(
BTManager.UUID.SETUP_READ,
new Uint8Array(Object.values(setup))
);
if (!success) {
console.warn('Failed to write setup packet');
return false;
}
let bufferIn = new Uint8Array(UserSettings.PROFILE_LENGTH);
let offset = 0;
while (offset < UserSettings.PROFILE_LENGTH) {
const chunk = await this.#tryRead(BTManager.UUID.PROFILE);
if (!chunk || chunk.length === 0) {
console.warn('Failed to read profile chunk');
return false;
}
const copyLen = Math.min(chunk.length, UserSettings.PROFILE_LENGTH - offset);
bufferIn.set(chunk.subarray(0, copyLen), offset);
offset += copyLen;
}
return bufferIn;
};
await this.#mutex.lock();
const bufferIn = await read.bind(this)();
if (!bufferIn) {
this.#mutex.unlock();
return false;
}
userSettings.setProfileFromBytes(bufferIn);
console.log('Profile read, ID:', userSettings.profile.profileId);
this.#mutex.unlock();
return true;
}
async #tryWrite(uuid, data) {
const maxRetries = 4;
let retries = 0;
let success = false;
while (retries < maxRetries) {
success = await this.#interface.write(uuid, data);
if (success) {
return true;
}
retries++;
}
return false;
}
async #tryRead(uuid) {
const maxRetries = 4;
let retries = 0;
let buffer = null;
while (retries < maxRetries) {
buffer = await this.#interface.read(uuid);
if (buffer) {
return buffer;
}
retries++;
}
return null;
}
async #sleep(ms) {
return new Promise(resolve => setTimeout(resolve, ms));
}
}
export const BT = {
async connect() {
const userSettings = new UserSettings();
UI.init(userSettings);
const btManager = new BTManager();
try {
UI.connectButtonsEnabled(false);
if (!(await btManager.init())) {
throw new Error('Failed to connect to Bluetooth device');
}
await btManager.getSetup(userSettings);
await btManager.getProfileByIdx(userSettings);
UI.updateAll(userSettings);
UI.toggleConnected(true);
UI.setSubheaderText("Settings");
UI.addCallbackLoadProfile(async () => {
await btManager.getProfileById(userSettings);
UI.updateAll(userSettings);
}, userSettings);
UI.addCallbackSaveProfile(async () => {
console.log('Saving profile...', userSettings.profile);
await btManager.saveProfile(userSettings);
}, userSettings);
UI.addCallbackDisconnect(async () => {
btManager.disconnect();
UI.toggleConnected(false);
window.location.reload();
});
btManager.runGamepadTask(userSettings);
} catch (error) {
console.warn('Connection error:', error);
UI.toggleConnected(false);
await btManager.disconnect();
window.location.reload();
}
}
};

View File

@@ -0,0 +1,80 @@
export class BTInterface {
#device = null;
#server = null;
#service = null;
#connected = false;
async connect(uuid, options) {
if (!navigator.bluetooth) {
console.error("Web Bluetooth API is not available, try using a different browser.");
return false;
}
try {
this.#device = await navigator.bluetooth.requestDevice(options);
this.#device.addEventListener('gattserverdisconnected', () => {
this.disconnect();
});
this.#server = await this.#device.gatt.connect();
this.#service = await this.#server.getPrimaryService(uuid);
this.#connected = true;
} catch (error) {
console.error('Bluetooth connection failed:', error);
this.disconnect();
}
return this.#connected;
}
setDisconnectCb(cb) {
if (this.#device) {
this.#device.addEventListener('gattserverdisconnected', cb);
}
}
async disconnect() {
if (this.#device) {
await this.#device.gatt.disconnect();
this.#device = null;
}
this.#server = null;
this.#service = null;
this.#connected = false;
}
isConnected() {
return this.#connected && this.#device?.gatt?.connected && this.#server && this.#service;
}
async write(uuid, data) {
if (!this.isConnected()) {
console.error('Bluetooth device not connected.');
return;
}
try {
const characteristic = await this.#service.getCharacteristic(uuid);
await characteristic.writeValue(data);
return true;
} catch (error) {
console.error('Failed to write to Bluetooth device:', error);
}
return false;
}
async read(uuid) {
if (!this.isConnected()) {
console.error('Bluetooth device not connected.');
return null;
}
try {
const characteristic = await this.#service.getCharacteristic(uuid);
const value = await characteristic.readValue();
if (value) {
return new Uint8Array(value.buffer);
}
} catch (error) {
console.error('Failed to read from Bluetooth device:', error);
}
return null;
}
}

View File

@@ -0,0 +1,238 @@
import { ESPLoader, Transport } from "https://unpkg.com/esptool-js@0.5.1/bundle.js";
import { UIProgram } from './../uiProgram.js';
import { UI } from './../uiSettings.js';
const REPO_OWNER = "wiredopposite";
const REPO_NAME = "OGX-Mini-WebApp";
const BAUDRATE = 115200;
const LOG_MAX_LEN = 100;
const LOG = document.getElementById("programLog");
const SERIAL_LIB = !navigator.serial && navigator.usb ? serial : navigator.serial;
const terminal = {
clean() {
LOG.innerHTML = "";
},
writeLine(data) {
this.write(data + "\n");
},
write(data) {
LOG.innerHTML += data;
if (LOG.textContent.split("\n").length > LOG_MAX_LEN + 1) {
let logLines = LOG.innerHTML.replace(/(\n)/gm, "").split("<br>");
LOG.innerHTML = logLines.splice(-LOG_MAX_LEN).join("<br>\n");
}
LOG.scrollTop = LOG.scrollHeight;
},
};
async function getRepoContents(owner, repo, path = "", branch = "master") {
const url = `https://api.github.com/repos/${owner}/${repo}/contents/${path}?ref=${branch}`;
try {
const response = await fetch(url);
if (!response.ok) {
throw new Error(`Error fetching repo content: ${response.status} ${response.statusText}`);
}
const data = await response.json();;
return data;
} catch (error) {
console.error(error);
return null;
}
}
async function getFwFiles() {
const contents = await getRepoContents(REPO_OWNER, REPO_NAME, "firmware/PICO_ESP32", "master");
if (!contents) {
return null;
}
const files = {
uf2: contents.find(file => file.name.startsWith("OGX-Mini") && file.name.endsWith(".uf2")),
bootloader: contents.find(file => file.name.startsWith("bootloader") && file.name.endsWith(".bin")),
partitionTable: contents.find(file => file.name.startsWith("partition") && file.name.endsWith(".bin")),
firmware: contents.find(file => file.name.startsWith("OGX-Mini") && file.name.endsWith(".bin")),
};
if (!files.uf2 || !files.bootloader || !files.partitionTable || !files.firmware) {
console.error("Error: Firmware files not found.");
return null;
}
return files;
}
async function copyUf2ToPico(dirHandle, uf2File) {
if (!uf2File) {
return false;
}
try {
const response = await fetch(uf2File.path);
if (!response.ok) {
console.error(`Error fetching UF2: ${response.status} ${response.statusText}`);
return false;
}
const uf2Content = await response.blob();
const fileHandle = await dirHandle.getFileHandle(uf2File.name, { create: true });
const writable = await fileHandle.createWritable();
terminal.writeLine("Copying UF2 file...");
await writable.write(uf2Content);
await writable.close();
terminal.writeLine("UF2 file copied.");
return true;
} catch (error) {
console.error("Error: " + error.message);
}
return false;
}
async function programEsp32(files) {
terminal.writeLine("Requesting port...");
let device = await SERIAL_LIB.requestPort({});
let transport = new Transport(device, true);
const loaderOptions = {
transport: transport,
baudrate: BAUDRATE,
terminal: terminal,
debugLogging: false,
}
terminal.writeLine("Connecting to ESP32...");
let espLoader = new ESPLoader(loaderOptions);
let reset_mode = "no_reset";
let chip = await espLoader.main(reset_mode)
terminal.writeLine("Connected to ESP32.");
const fetchBinaryString = async (url) => {
const response = await fetch(url);
if (!response.ok) {
throw new Error(`Failed to fetch firmware file from ${url}: ${response.status}`);
}
const arrayBuffer = await response.arrayBuffer();
const uint8Array = new Uint8Array(arrayBuffer);
let binaryString = "";
for (let i = 0; i < uint8Array.length; i++) {
binaryString += String.fromCharCode(uint8Array[i]);
}
return binaryString;
};
const bootloaderData = await fetchBinaryString(files.bootloader.download_url);
const partitionTableData = await fetchBinaryString(files.partitionTable.download_url);
const firmwareData = await fetchBinaryString(files.firmware.download_url);
terminal.writeLine("Firmware files found:")
terminal.writeLine(" - Bootloader: " + files.bootloader.name);
terminal.writeLine(" - Partition Table: " + files.partitionTable.name);
terminal.writeLine(" - Firmware: " + files.firmware.name);
const flashOptions = {
fileArray: [
{ data: bootloaderData, address: 0x1000 },
{ data: partitionTableData, address: 0x8000 },
{ data: firmwareData, address: 0x10000 },
],
flashSize: "keep",
eraseAll: false,
compress: true,
reportProgress: (fileIndex, write, total) => {
// console.log(`Flashing ${fileIndex + 1} of 3: ${Math.round((write / total) * 100)}%`);
},
calculateMD5Hash: (image) => CryptoJS.MD5(CryptoJS.enc.Latin1.parse(image)),
};
terminal.writeLine("\nFlashing firmware...");
await espLoader.writeFlash(flashOptions);
const completeFlag = "PROGRAMMING_COMPLETE"
const encoder = new TextEncoder();
const flagBytes = encoder.encode(completeFlag);
terminal.writeLine("Sending programming complete flag: " + completeFlag);
try {
await transport.write(flagBytes);
} catch (error) {
console.error("Error: " + error.message);
return false;
}
await transport.disconnect();
await transport.waitForUnlock();
terminal.writeLine("Flashing complete.");
return true;
}
export const UsbEsp32 = {
async connect() {
UIProgram.enableProgramEsp32Button(false);
UIProgram.toggleConnected(true);
UI.setSubheaderText("Update");
try {
let dirHandle = null;
let fwFiles = null;
UIProgram.addProgramPicoCallback(async () => {
UIProgram.enableProgramPicoButton(false);
try {
terminal.clean();
terminal.writeLine("Select the drive named RPI-RP2");
dirHandle = await window.showDirectoryPicker();
if (!dirHandle) {
return;
}
fwFiles = await getFwFiles();
if (!fwFiles) {
throw new Error("Error: Firmware files not found.");
}
if (!await copyUf2ToPico(dirHandle, fwFiles.uf2)) {
throw new Error("Error: UF2 not copied to Pico.");
}
UIProgram.enableProgramEsp32Button(true);
terminal.writeLine("Click 'Program Part 2' to finish programming you adapter.");
} catch (error) {
console.warn("Error: " + error.message);
UIProgram.enableProgramPicoButton(true);
}
});
UIProgram.addProgramEsp32Callback(async () => {
UIProgram.enableProgramEsp32Button(false);
if (!fwFiles) {
throw new Error("Error: Firmware files not found.");
}
try {
await programEsp32(fwFiles);
} catch (error) {
console.warn("Error: " + error.message);
UIProgram.enableProgramEsp32Button(true);
}
});
} catch (error) {
console.error("Error: " + error.message);
}
}
};

View File

@@ -0,0 +1,88 @@
export class USBInterface {
constructor() {
this.reader = null;
this.writer = null;
this.port = null;
this.inBuffer = new Uint8Array();
this.disconnectCb = null;
}
async connect(baudrate, filters = null) {
if (!("serial" in navigator)) {
console.warn("Web Serial API not supported.");
return false;
}
if (!filters) {
this.port = await navigator.serial.requestPort({ });
} else {
this.port = await navigator.serial.requestPort({ filters });
}
await this.port.open({ baudRate: baudrate });
this.reader = this.port.readable.getReader();
this.writer = this.port.writable.getWriter();
return true;
}
registerDisconnectCb(callback) {
this.disconnectCb = callback;
}
async write(data) {
if (!this.writer) {
console.warn("Writer not initialized.");
return;
}
return await this.writer.write(data);
}
async readTask(length, processCallback) {
if (!this.reader) {
console.warn("Reader not initialized.");
return;
}
let inData = new Uint8Array();
try {
while (true) {
const { value, done } = await this.reader.read();
if (done) {
console.log("Stream closed.");
break;
}
if (value) {
let tempData = new Uint8Array(inData.length + value.length);
tempData.set(inData);
tempData.set(value, inData.length);
inData = tempData;
while (inData.length >= length) {
processCallback(inData.slice(0, length));
inData = inData.slice(length);
}
}
}
} catch (error) {
console.warn("Read error:", error.message || error);
console.warn("Stack trace:", error.stack);
await this.disconnect();
}
}
async disconnect() {
try {
if (this.reader) await this.reader.cancel();
if (this.writer) await this.writer.releaseLock();
if (this.port) await this.port.close();
} catch (error) {
console.warn("Error disconnecting:", error);
}
this.reader = null;
this.writer = null;
this.port = null;
if (this.disconnectCb) this.disconnectCb();
}
isConnected() {
return this.port && this.port.readable && this.port.writable;
}
}

View File

@@ -0,0 +1,274 @@
import { USBInterface } from "./usbInterface.js";
import { Gamepad } from "../gamepad.js";
import { UI } from "../uiSettings.js";
import { UserSettings } from "../userSettings.js";
class USBManager {
static #PACKET_LENGTH = Object.freeze(64);
static #HEADER_LENGTH = Object.freeze(9);
static #BAUDRATE = Object.freeze(9600);
static #BUFFER_LEN = Object.freeze(1024);
static #PACKET_ID = Object.freeze({
NONE: 0,
GET_PROFILE_BY_ID: 0x50,
GET_PROFILE_BY_IDX: 0x55,
SET_PROFILE_START: 0x60,
SET_PROFILE: 0x61,
SET_GP_IN: 0x80,
SET_GP_OUT: 0x81,
RESP_ERROR: 0xFF
});
static #PACKET_HEADER = Object.freeze([
{ key: "packetLen", size: 1 },
{ key: "packetId", size: 1 },
{ key: "deviceMode", size: 1 },
{ key: "maxGamepads", size: 1 },
{ key: "playerIdx", size: 1 },
{ key: "profileId", size: 1 },
{ key: "chunksTotal", size: 1 },
{ key: "chunkIdx", size: 1 },
{ key: "chunkLen", size: 1 },
]);
#interface = null;
#currentBufferInOffset = 0;
#bufferIn = null;
#userSettings = null;
constructor() {
this.#interface = new USBInterface();
this.#bufferIn = new Uint8Array(USBManager.#BUFFER_LEN);
}
async init(userSettings) {
try {
this.#userSettings = userSettings;
if (await this.#interface.connect(USBManager.#BAUDRATE)) {
this.#interface.registerDisconnectCb(() => {
window.location.reload();
});
this.#interface.readTask(USBManager.#PACKET_LENGTH, this.#processPacketIn.bind(this));
await this.#sleep(1000);
return true;
}
} catch (error) {
console.warn('Connection error:', error);
await this.#interface.disconnect();
return false;
}
}
async saveProfile() {
let header = this.#headerFromUi(USBManager.#PACKET_ID.SET_PROFILE_START);
await this.#writeToDevice(
header,
new Uint8Array([0xFF])
);
await this.#sleep(100);
const data = this.#userSettings.getProfileBytes();
header.packetId = USBManager.#PACKET_ID.SET_PROFILE;
await this.#writeToDevice(
header,
data
);
}
async getProfileById() {
let header = this.#headerFromUi(USBManager.#PACKET_ID.GET_PROFILE_BY_ID);
await this.#writeToDevice(
header,
new Uint8Array([0xFF])
);
}
async getProfileByIdx() {
let header = this.#headerFromUi(USBManager.#PACKET_ID.GET_PROFILE_BY_IDX);
await this.#writeToDevice(
header,
new Uint8Array([0xFF])
);
}
async disconnect() {
await this.#interface.disconnect();
}
#headerFromUi(packetId) {
return {
packetLen: USBManager.#PACKET_LENGTH,
packetId: packetId,
deviceMode: UI.getSelectedDeviceMode(),
maxGamepads: this.#userSettings.maxGamepads,
playerIdx: UI.getSelectedPlayerIdx(),
profileId: UI.getSelectedProfileId(),
chunksTotal: 1,
chunkIdx: 0,
chunkLen: 0
}
}
#deserializeHeader(packetData) {
if (packetData.length < USBManager.#HEADER_LENGTH) {
console.error("Invalid packet data length.");
return;
}
const header = {};
let offset = 0;
USBManager.#PACKET_HEADER.forEach(field => {
header[field.key] = packetData[offset];
offset += field.size;
});
return header;
}
#serializeHeader(header) {
const buffer = new Uint8Array(USBManager.#HEADER_LENGTH);
let offset = 0;
USBManager.#PACKET_HEADER.forEach(field => {
buffer[offset] = header[field.key];
offset += field.size;
});
return buffer;
}
#processPacketInData(header, bufferIn, dataLen) {
switch (header.packetId) {
case USBManager.#PACKET_ID.GET_PROFILE_BY_IDX:
console.log("Received profile data.");
this.#userSettings.setProfileFromBytes(bufferIn.subarray(0, dataLen));
this.#userSettings.maxGamepads = header.maxGamepads;
this.#userSettings.playerIdx = header.playerIdx;
this.#userSettings.deviceMode = header.deviceMode;
UI.updateAll(this.#userSettings);
break;
case USBManager.#PACKET_ID.GET_PROFILE_BY_ID:
console.log("Received profile data.");
this.#userSettings.setProfileFromBytes(bufferIn.subarray(0, dataLen));
this.#userSettings.maxGamepads = header.maxGamepads;
this.#userSettings.deviceMode = header.deviceMode;
UI.updateAll(this.#userSettings);
break;
case USBManager.#PACKET_ID.SET_GP_IN:
const gamepad = new Gamepad();
gamepad.setReportFromBytes(bufferIn.subarray(0, dataLen));
UI.drawGamepadInput(gamepad, this.#userSettings);
break;
default:
console.warn(`Unknown packet ID: ${header.packetId}`);
break;
}
}
#processPacketIn(data) {
if (data[0] !== USBManager.#PACKET_LENGTH) {
console.warn(`Invalid packet length: ${data[0]}`);
return;
}
const header = this.#deserializeHeader(data);
this.#bufferIn.set(
data.subarray(
USBManager.#HEADER_LENGTH,
USBManager.#HEADER_LENGTH + header.chunkLen
), this.#currentBufferInOffset
);
this.#currentBufferInOffset += header.chunkLen;
console.log("Received packet: " + (header.chunkIdx + 1) + " of " + header.chunksTotal);
if (header.chunkIdx + 1 === header.chunksTotal) {
this.#processPacketInData(header, this.#bufferIn, this.#currentBufferInOffset);
this.#currentBufferInOffset = 0;
}
}
async #writeToDevice(header, data) {
const dataLen = data.length;
const lenLimit = USBManager.#PACKET_LENGTH - USBManager.#HEADER_LENGTH;
const chunksTotal = Math.ceil(dataLen / lenLimit);;
let currentOffset = 0;
header.chunksTotal = chunksTotal;
for (let i = 0; i < chunksTotal; i++) {
const isLastChunk = (i === chunksTotal - 1);
const chunkLen = isLastChunk ? dataLen - currentOffset : lenLimit;
header.chunkIdx = i;
header.chunkLen = chunkLen;
const buffer = new Uint8Array(USBManager.#PACKET_LENGTH);
buffer.set(this.#serializeHeader(header), 0);
buffer.set(
data.subarray(currentOffset, currentOffset + chunkLen),
USBManager.#HEADER_LENGTH
);
console.log("Writing packet: " + (i + 1) + " of " + chunksTotal);
await this.#interface.write(buffer);
currentOffset += chunkLen;
}
}
async #sleep(ms) {
return new Promise(resolve => setTimeout(resolve, ms));
}
}
export const USB = {
async connect() {
if (!("serial" in navigator)) {
console.error("Web Serial API not supported.");
return;
}
const userSettings = new UserSettings();
UI.init(userSettings);
const usbManager = new USBManager();
try {
UI.connectButtonsEnabled(false);
if (!(await usbManager.init(userSettings))) {
throw new Error("Connection failed.");
}
await usbManager.getProfileByIdx();
UI.updateAll(userSettings);
UI.toggleConnected(true);
UI.setSubheaderText("Settings");
UI.addCallbackLoadProfile(async () => {
await usbManager.getProfileById();
UI.updateAll(userSettings);
}, userSettings);
UI.addCallbackSaveProfile(async () => {
await usbManager.saveProfile();
}, userSettings);
UI.addCallbackDisconnect(async () => {
await usbManager.disconnect();
UI.toggleConnected(false);
window.location.reload();
});
} catch (error) {
console.warn('Connection error:', error);
usbManager.disconnect();
window.location.reload();
}
}
};

View File

@@ -0,0 +1,247 @@
export const DrawUtils = {
drawRectangle(context, x, y, width, height, fillColor = null, strokeColor = null, strokeWidth = 1) {
context.beginPath();
context.rect(x, y, width, height);
if (fillColor) {
context.fillStyle = fillColor;
context.fill();
}
if (strokeColor) {
context.strokeStyle = strokeColor;
context.lineWidth = strokeWidth;
context.stroke();
}
context.closePath();
},
drawAngularFlare(context, centerX, centerY, radius, angle, flareAngle, color) {
function deg2rad(degrees) {
return (degrees * Math.PI) / 180;
}
const startAngle = deg2rad(angle - flareAngle / 2);
const endAngle = deg2rad(angle + flareAngle / 2);
context.beginPath();
context.moveTo(centerX, centerY);
context.arc(centerX, centerY, radius, startAngle, endAngle);
context.closePath();
context.fillStyle = color;
context.fill();
},
drawCircleCutoutOuter(context, centerX, centerY, radius) {
context.save();
context.beginPath();
context.rect(0, 0, context.canvas.width, context.canvas.height);
context.arc(centerX, centerY, radius, 0, Math.PI * 2, true);
context.clip('evenodd');
context.clearRect(0, 0, context.canvas.width, context.canvas.height);
context.restore();
},
drawCircleCutoutInner(context, centerX, centerY, radius, color) {
context.beginPath();
context.rect(0, 0, context.canvas.width, context.canvas.height);
context.arc(centerX, centerY, radius, 0, Math.PI * 2, true);
context.fillStyle = color;
context.fill('evenodd');
context.closePath();
},
drawCircle(context, centerX, centerY, radius, fillColor = null, strokeColor = null, strokeWidth = 1) {
context.beginPath();
context.arc(centerX, centerY, radius, 0, Math.PI * 2);
if (fillColor) {
context.fillStyle = fillColor;
context.fill();
}
if (strokeColor) {
context.strokeStyle = strokeColor;
context.lineWidth = strokeWidth;
context.stroke();
}
context.closePath();
},
drawScaledDiagonalCircleRaw(context, centerX, centerY, radius, scale, indentScale = 0) {
if (scale > 1.4) {
scale = 1.4;
}
if (indentScale > 0) {
indentScale = Math.max(0, Math.min(1, indentScale));
} else {
indentScale = 1.0;
}
for (let angle = 0; angle <= 360; angle += 1) {
const rad = (Math.PI / 180) * angle;
let x = Math.cos(rad);
let y = Math.sin(rad);
let angleDeg = Math.abs(rad * (180 / Math.PI)) % 90;
let diagonal = angleDeg > 45 ? (((angleDeg - 45) * -45) / 45) + 45 : angleDeg;
let cScale = (diagonal * (1.0 / Math.SQRT2)) / 45.0;
cScale = 1.0 - Math.sqrt(1.0 - Math.pow(cScale, 2));
let dScale = ((cScale * ((scale - 1.0)) * indentScale) / 0.29289) + 1.0;
// dScale = 1 + (dScale - 1) * indentScale;
x *= dScale;
y *= dScale;
const finalX = centerX + x * radius;
const finalY = centerY + y * radius;
if (angle === 0) {
context.moveTo(finalX, finalY);
} else {
context.lineTo(finalX, finalY);
}
}
},
drawScaledDiagonalCircle(context, centerX, centerY, radius, scale, fillColor = null, strokeColor = null, strokeWidth = 1, indentScale = 0) {
context.beginPath();
this.drawScaledDiagonalCircleRaw(context, centerX, centerY, radius, scale, indentScale);
if (fillColor) {
context.fillStyle = fillColor;
context.fill();
}
if (strokeColor) {
context.strokeStyle = strokeColor;
context.lineWidth = strokeWidth;
context.stroke();
}
context.closePath();
},
drawScaledDiagonalCircleEraseOuter(context, centerX, centerY, radius, scale, fillColor = null, strokeColor = null, strokeWidth = 1, indentScale = 0) {
if (fillColor || strokeColor) {
this.drawScaledDiagonalCircle(context, centerX, centerY, radius, scale, fillColor, strokeColor, strokeWidth * 2);
}
context.save();
context.beginPath();
context.globalCompositeOperation = 'destination-out';
context.rect(0, 0, context.canvas.width, context.canvas.height);
this.drawScaledDiagonalCircleRaw(context, centerX, centerY, radius, scale, indentScale);
context.closePath();
context.fillStyle = 'black';
context.fill('evenodd');
context.restore();
},
drawScaledDiagonalCircleEraseInner(context, centerX, centerY, radius, scale, fillColor = null, strokeColor = null, strokeWidth = 1, indentScale = 0) {
const offscreenCanvas = document.createElement('canvas');
offscreenCanvas.width = context.canvas.width;
offscreenCanvas.height = context.canvas.height;
const offscreenCtx = offscreenCanvas.getContext('2d');
if (fillColor) {
offscreenCtx.beginPath();
offscreenCtx.rect(0, 0, offscreenCanvas.width, offscreenCanvas.height);
offscreenCtx.fillStyle = fillColor;
offscreenCtx.fill();
offscreenCtx.closePath();
}
offscreenCtx.globalCompositeOperation = 'destination-out';
offscreenCtx.beginPath();
this.drawScaledDiagonalCircleRaw(offscreenCtx, centerX, centerY, radius, scale, indentScale);
offscreenCtx.closePath();
offscreenCtx.fillStyle = 'black';
offscreenCtx.fill();
context.drawImage(offscreenCanvas, 0, 0);
if (strokeColor) {
this.drawScaledDiagonalCircle(context, centerX, centerY, radius, null, strokeColor, strokeWidth, indentScale);
}
},
rotateRectangle90(rect, centerX, centerY) {
let rectCenterX = rect.startX + rect.width / 2;
let rectCenterY = rect.startY + rect.height / 2;
let offsetX = rectCenterX - centerX;
let offsetY = rectCenterY - centerY;
let rotatedX = -offsetY;
let rotatedY = offsetX;
rotatedX += centerX;
rotatedY += centerY;
return {
startX: rotatedX - rect.height / 2,
startY: rotatedY - rect.width / 2,
width: rect.height,
height: rect.width
};
},
drawCutoutCross(context, centerX, centerY, maxRadius, size, fillColor, strokeColor = null, strokeWidth = 1) {
let rects = [{
startX: 0,
startY: 0,
height: size,
width: size
}];
for (let i = 0; i < 3; i++) {
rects.push(DrawUtils.rotateRectangle90(rects[i], centerX, centerY));
}
rects.forEach(({ startX, startY, width, height }) => {
context.beginPath();
context.rect(startX, startY, width, height);
if (fillColor) {
context.fillStyle = fillColor;
context.fill();
}
if (strokeColor) {
context.strokeStyle = strokeColor;
context.lineWidth = strokeWidth;
context.stroke();
}
context.closePath();
});
},
drawScaledCross(context, centerX, centerY, maxRadius, size, fillColor, strokeColor = null, strokeWidth = 1) {
let rects = [{
startX: maxRadius - (size / 2),
startY: 0,
height: maxRadius - (size / 2),
width: size
}];
for (let i = 0; i < 3; i++) {
rects.push(DrawUtils.rotateRectangle90(rects[i], centerX, centerY));
}
//Center rectangle
rects.push({
startX: rects[0].startX,
startY: rects[0].startY + rects[0].height,
width: rects[0].width,
height: (maxRadius - rects[0].height) * 2
});
rects.forEach(({ startX, startY, width, height }) => {
context.beginPath();
context.rect(startX, startY, width, height);
context.fillStyle = fillColor;
context.fill();
if (strokeColor) {
context.strokeStyle = strokeColor;
context.lineWidth = strokeWidth;
context.stroke();
}
context.closePath();
});
},
};

View File

@@ -0,0 +1,80 @@
export class Gamepad {
static #REPORT_MAP = [
{ key: "dpad", size: 1 },
{ key: "buttons", size: 2 },
{ key: "triggerL", size: 1 },
{ key: "triggerR", size: 1 },
{ key: "joystickLx", size: 2 }, //int16_t
{ key: "joystickLy", size: 2 }, //int16_t
{ key: "joystickRx", size: 2 }, //int16_t
{ key: "joystickRy", size: 2 }, //int16_t
{ key: "analogUp", size: 1 },
{ key: "analogDown", size: 1 },
{ key: "analogLeft", size: 1 },
{ key: "analogRight", size: 1 },
{ key: "analogA", size: 1 },
{ key: "analogB", size: 1 },
{ key: "analogX", size: 1 },
{ key: "analogY", size: 1 },
{ key: "analogLb", size: 1 },
{ key: "analogRb", size: 1 },
];
constructor() {
this.report = {};
for (const field of Gamepad.#REPORT_MAP) {
this.report[field.key] = 0;
}
}
setReportFromBytes(data) {
if (!(data instanceof Uint8Array)) {
return console.warn("Invalid data type.");
} else if (data.length !== 23 && data.length !== 13) {
return console.warn("Invalid data length: expected 23 bytes, actual:", data.length);
}
const dataView = new DataView(data.buffer);
let offset = 0;
for (const field of Gamepad.#REPORT_MAP) {
const { key, size } = field;
if (size === 1) {
this.report[key] = data[offset];
} else if (size === 2) {
this.report[key] = dataView.getInt16(offset, true);
}
offset += size;
if (offset > data.length) {
break;
}
}
}
scaledJoystickLx() {
const value = this.report.joystickLx / 32767;
return (value > 1) ? 1 : (value < -1) ? -1 : value;
}
scaledJoystickLy() {
const value = this.report.joystickLy / 32767;
return (value > 1) ? 1 : (value < -1) ? -1 : value;
}
scaledJoystickRx() {
const value = this.report.joystickRx / 32767;
return (value > 1) ? 1 : (value < -1) ? -1 : value;
}
scaledJoystickRy() {
const value = this.report.joystickRy / 32767;
return (value > 1) ? 1 : (value < -1) ? -1 : value;
}
scaledTriggerL() {
const value = this.report.triggerL / 255;
return (value > 1) ? 1 : value;
}
scaledTriggerR() {
const value = this.report.triggerR / 255;
return (value > 1) ? 1 : value;
}
}

View File

@@ -0,0 +1,39 @@
export class JoystickSettings {
static SETTINGS = Object.freeze([
{ type: "float", key: 'dzInner', min: 0.0, max: 0.5, def: 0.0, label: "Deadzone Inner", tip: "Value of desired circular deadzone." },
{ type: "float", key: 'dzOuter', min: 0.6, max: 1.0, def: 1.0, label: "Deadzone Outer", tip: "Value of the maximum range you want to limit stick output." },
{ type: "float", key: 'antiDzInnerC', min: 0.0, max: 0.5, def: 0.0, label: "Anti-Deadzone Circular", tip: "Value of the game's circular deadzone. Common sizes are 0.2 to 0.25." },
{ type: "float", key: 'antiDzInnerCYScale', min: 0.0, max: 0.5, def: 0.0, label: "Anti-Deadzone Circular Y", tip: "Only change if deadzone is ellipical. When changed, antiCircleDeadzone will control width and this the height." },
{ type: "float", key: 'antiDzSquare', min: 0.0, max: 0.5, def: 0.0, label: "Anti-Deadzone Square", tip: "Value of the game's square/axial deadzone. Common sizes are 0.2 to 0.25." },
{ type: "float", key: 'antiDzSquareYScale', min: 0.0, max: 0.5, def: 0.0, label: "Anti-Deadzone Square Y", tip: "Only change if deadzone is rectangular. When changed, antiSquareDeadzone will control the width and this the height." },
{ type: "float", key: 'antiDzAngular', min: 0.0, max: 0.44, def: 0.0, label: "Anti-Deadzone Angular", tip: "Use to counter reticted diagonal movement around the axes based on angle." },
{ type: "float", key: 'antiDzOuter', min: 0.5, max: 1.0, def: 1.0, label: "Anti-Deadzone Outer", tip: "Once reached, stick outputs 100%. Useful if user's stick is unable to reach maximum magnitudes." },
{ type: "float", key: 'axialRestrict', min: 0.0, max: 0.49, def: 0.0, label: "Axial Restrict", tip: "Restrict diagonal movement based on distance from the axis." },
{ type: "float", key: 'angularRestrict', min: 0.0, max: 0.44, def: 0.0, label: "Angular Restrict", tip: "Restrict diagonal movement around axis based on angle." },
{ type: "float", key: 'diagonalScaleMin', min: 0.5, max: 1.42, def: 1.0, label: "Diagonal Scale Inner", tip: "Use to warp lower magnitude diagonal values." },
{ type: "float", key: 'diagonalScaleMax', min: 0.5, max: 1.42, def: 1.0, label: "Diagonal Scale Outer", tip: "Use to warp higher magnitude diagonal values." },
{ type: "float", key: 'curve', min: 0.3, max: 3.0, def: 1.0, label: "Curve", tip: "Value of the game's curve to cancel it into a linear curve. Larger values result in faster starting movement." },
{ type: "bool", key: 'uncapRadius', def: true, label: "Uncap Radius", tip: "Uncap joystick position so it can move beyond the circular radius." },
{ type: "bool", key: 'invertY', def: false, label: "Invert Y", tip: "Invert Y axis." },
{ type: "bool", key: 'invertX', def: false, label: "Invert X", tip: "Invert X axis." },
]);
constructor() {
this.resetAll();;
}
resetAll() {
JoystickSettings.SETTINGS.forEach((setting) => {
this[setting.key] = setting.def;
});
}
getDefaultValue(key) {
const intSetting = JoystickSettings.SETTINGS.find(s => s.key === key);
if (intSetting !== undefined) {
return intSetting.def;
}
console.warn(`Invalid key: ${key}`);
return null;
}
};

View File

@@ -0,0 +1,436 @@
import { DrawUtils } from "./../drawUtils.js";
export class JoystickVisualizer {
#settings = null;
#cursor = null;
constructor(backgroundCanvas, settingsCanvas, cursorCanvas) {
this.#settings = new Settings(settingsCanvas, backgroundCanvas);
this.#cursor = new Cursor(cursorCanvas);
}
init(joystickSettings) {
this.#settings.init(joystickSettings);
this.#cursor.draw(0, 0);
}
drawSettings(joystickSettings) {
this.#settings.draw(joystickSettings);
}
drawInput(joyX, joyY, settings = null, preview = false) {
this.#cursor.draw(joyX, joyY, settings, preview);
}
}
class Cursor {
constructor(canvas) {
this.canvas = canvas;
this.context = canvas.getContext('2d');
this.maxRadius = canvas.width / 2;
this.centerX = canvas.width / 2;
this.centerY = canvas.height / 2;
this.colors = {
cursor: 'rgba(0, 0, 255, 0.91)',
}
this.lastJoy = { x: -2, y: -2 };
}
draw(joyX, joyY, settings = null, preview = false) {
const { canvas, context, centerX, centerY, maxRadius, colors, lastJoy } = this;
if (preview && settings) {
const scaled = applyJoystickSettings(
joyX, joyY,
settings.dzInner, settings.antiDzInnerC,
settings.antiDzInnerCYScale, settings.antiDzSquare, settings.antiDzSquareYScale,
settings.antiDzOuter, settings.dzOuter, settings.curve,
settings.axialRestrict * 100, settings.angularRestrict * 100, settings.antiDzAngular * 100,
settings.diagonalScaleMin, settings.diagonalScaleMax, settings.uncapRadius,
settings.invertY, settings.invertX
);
joyX = scaled.x;
joyY = scaled.y;
// console.log(`Preview: ${joyX}, ${joyY}`);
}
if (joyX !== lastJoy.x || joyY !== lastJoy.y) {
lastJoy.x = joyX;
lastJoy.y = joyY;
context.clearRect(0, 0, canvas.width, canvas.height);
let canvasJoyX = joyX * maxRadius;
let canvasJoyY = joyY * maxRadius;
canvasJoyX += centerX;
canvasJoyY += centerY;
context.beginPath();
context.arc(canvasJoyX, canvasJoyY, 5, 0, Math.PI * 2);
context.fillStyle = colors.cursor;
context.fill();
context.closePath();
}
}
}
class SettingsBackground {
constructor(canvas) {
this.canvas = canvas;
this.context = canvas.getContext('2d');
this.maxRadius = canvas.width / 2;
this.centerX = canvas.width / 2;
this.centerY = canvas.height / 2;
this.colors = {
background: 'rgb(249, 249, 249)',
grid: 'rgba(0, 0, 0, 0.1)',
gridMid: 'rgba(0, 0, 0, 0.7)',
strokeColor: 'rgba(0, 0, 0, 0.75)',
};
this.strokeWidth = {
outer: 1,
inner: 2,
}
}
draw(joystickSettings) {
const { canvas, context, centerX, centerY, maxRadius, colors } = this;
const strokeWidth = this.strokeWidth;
context.clearRect(0, 0, canvas.width, canvas.height);
context.beginPath();
context.fillStyle = colors.background;
context.fill();
context.closePath();
const gridSpacing = canvas.width / 20;
const mid = gridSpacing * 10;
context.lineWidth = strokeWidth.inner;
for (let x = 0; x < canvas.width; x += gridSpacing) {
if (x !== mid) {
context.strokeStyle = colors.grid;
} else {
context.strokeStyle = colors.mid;
}
context.beginPath();
context.moveTo(x, 0);
context.lineTo(x, canvas.height);
context.stroke();
context.closePath();
}
for (let y = 0; y < canvas.height; y += gridSpacing) {
if (y !== mid) {
context.strokeStyle = colors.grid;
} else {
context.strokeStyle = colors.mid;
}
context.beginPath();
context.moveTo(0, y);
context.lineTo(canvas.width, y);
context.stroke();
context.closePath();
}
DrawUtils.drawScaledDiagonalCircleEraseOuter(context, centerX, centerY, maxRadius, joystickSettings.diagonalScaleMax);
}
}
class Settings {
#background = null;
constructor(settingsCanvas, backgroundCanvas) {
this.#background = new SettingsBackground(backgroundCanvas);
this.canvas = settingsCanvas;
this.context = this.canvas.getContext('2d');
this.maxRadius = this.canvas.width / 2;
this.centerX = this.canvas.width / 2;
this.centerY = this.canvas.height / 2;
this.colors = {
stroke: 'rgba(0, 0, 0, 0.72)',
antiDeadzone: 'rgba(0, 255, 0, 0.73)',
antiSquareDeadzone: 'rgba(0, 102, 255, 0.82)',
deadzone: 'rgba(255, 0, 0, 0.6)',
angularAnti: 'rgba(97, 0, 97, 0.62)',
angularRestrict: 'rgba(0, 0, 255, 0.5)',
axialRestrict: 'rgba(228, 10, 180, 0.62)',
}
this.strokeWidth = 2;
this.lastDiagonalScaleMax = 1;
}
init(joystickSettings) {
this.#background.draw(joystickSettings);
this.draw(joystickSettings);
}
draw(joystickSettings) {
const { canvas, context, centerX, centerY, maxRadius, colors, strokeWidth } = this;
context.clearRect(0, 0, canvas.width, canvas.height);
const antiDzInnerCRadius = joystickSettings.antiDzInnerC * maxRadius;
const antiDzSquareSize = canvas.width * joystickSettings.antiDzSquare;
const dzInnerRadius = joystickSettings.dzInner * maxRadius;
const antiDzOuterRadius = joystickSettings.antiDzOuter * maxRadius;
const dzOuterRadius = joystickSettings.dzOuter * maxRadius;
const axialRestrictWidth = joystickSettings.axialRestrict * canvas.width;
const antiDzSquareYScaleHeight = canvas.height * joystickSettings.antiDzSquareYScale;
// const axialRestrictWidth = joystickSettings.axialRestrict * 100;
const angularRestrictAngle = joystickSettings.angularRestrict * 100;
const antiDzAngular = joystickSettings.antiDzAngular * 100;
const diagonalScaleMax = joystickSettings.diagonalScaleMax;
const diagonalScaleMin = joystickSettings.diagonalScaleMin;
if (antiDzSquareSize > 0) {
DrawUtils.drawScaledCross(
context,
centerX,
centerY,
maxRadius,
antiDzSquareSize,
colors.antiSquareDeadzone
);
}
if (antiDzSquareYScaleHeight > 0) {
DrawUtils.drawRectangle(
context,
0,
canvas.height / 2 - antiDzSquareYScaleHeight / 2,
canvas.width,
antiDzSquareYScaleHeight,
colors.antiSquareDeadzone
);
}
if (angularRestrictAngle > 0) {
const angles = [45, 135, 225, 315];
angles.forEach((angle) => {
DrawUtils.drawAngularFlare(
context,
centerX,
centerY,
dzOuterRadius,
angle,
angularRestrictAngle,
colors.angularRestrict
);
});
}
if (antiDzAngular > 0) {
const angles = [0, 90, 180, 270];
angles.forEach((angle) => {
DrawUtils.drawAngularFlare(
context,
centerX,
centerY,
dzOuterRadius,
angle,
antiDzAngular,
colors.angularAnti
);
});
}
if (joystickSettings.antiDzOuter < 1) {
DrawUtils.drawScaledDiagonalCircleEraseInner(
context,
centerX,
centerY,
antiDzOuterRadius,
diagonalScaleMax,
colors.antiDeadzone
);
}
if (joystickSettings.dzOuter < 1) {
DrawUtils.drawScaledDiagonalCircleEraseInner(
context,
centerX,
centerY,
dzOuterRadius,
diagonalScaleMax,
colors.deadzone
);
}
if (axialRestrictWidth > 0) {
DrawUtils.drawCutoutCross(
context,
centerX,
centerY,
maxRadius,
axialRestrictWidth,
colors.axialRestrict
);
}
if (antiDzInnerCRadius > 0) {
DrawUtils.drawScaledDiagonalCircle(
context,
centerX,
centerY,
antiDzInnerCRadius,
diagonalScaleMin,
colors.antiDeadzone
);
}
if (dzInnerRadius > 0) {
// drawCircleCutoutInner(context, centerX, centerY, innerDeadzoneRadius);
DrawUtils.drawCircle(context, centerX, centerY, dzInnerRadius, colors.deadzone);
}
if (diagonalScaleMax < 1.4) {
DrawUtils.drawScaledDiagonalCircleEraseOuter(
context,
centerX,
centerY,
maxRadius,
diagonalScaleMax,
null,
colors.stroke,
strokeWidth
);
} else {
DrawUtils.drawRectangle(context, 0, 0, context.canvas.width,context.canvas.height, null, colors.stroke, strokeWidth * 2);
}
if (diagonalScaleMax != this.lastDiagonalScaleMax) {
this.#background.draw(joystickSettings);
this.lastDiagonalScaleMax = diagonalScaleMax;
}
}
}
function applyJoystickSettings(
x, y,
dzInner, antiDzInnerC,
antiDzInnerCYScale, antiDzSquare, antiDzSquareYScale,
antiDzOuter, dzOuter, curve,
axialRestrict, angularRestrict, antiDzAngular,
diagonalScaleMin, diagonalScaleMax, uncapRadius,
invertY, invertX
) {
if (invertY) {
y = -y;
}
if (invertX) {
x = -x;
}
// Helper functions
const rad2deg = (rad) => rad * (180 / Math.PI);
const deg2rad = (deg) => deg * (Math.PI / 180);
const clamp = (val, min, max) => Math.max(min, Math.min(max, val));
const sq = (v) => v * v;
const inv = (v) => (Math.abs(v) > 0.0001 ? 1.0 / v : 0.0);
let rAngle = rad2deg(Math.abs(Math.atan(y/x)));
if(Math.abs(x) < 0.0001){rAngle = 90.0;}
//Setting up axial angle deadzone values
let axialX, axialY;
if(Math.abs(x) <= axialRestrict && rAngle > 45.0){axialX = 0.0;}
else{ axialX = (Math.abs(x) - axialRestrict)/(1.0 - axialRestrict); }
if(Math.abs(y) <= axialRestrict && rAngle <= 45.0){axialY = 0.0;}
else{ axialY = (Math.abs(y) - axialRestrict)/(1.0 - axialRestrict); }
let inputMagnitude = Math.sqrt(x*x + y*y);
let outputMagnitude;
let angle = rad2deg(Math.abs(Math.atan(axialY/axialX)));
if(Math.abs(axialX) < 0.0001){angle = 90.0;} //avoids angle change with Atan by avoiding dividing by 0
//Checks if rectangular deadone is used.
if(antiDzSquareYScale == 0.00){ antiDzSquareYScale = antiDzSquare; }
//Ellipse warping
if(antiDzInnerCYScale > 0.00 && antiDzInnerC > 0.00){
antiDzInnerCYScale = antiDzInnerCYScale/antiDzInnerC;
let ellipseAngle = Math.atan((1.0/antiDzInnerCYScale)*Math.tan(deg2rad(rAngle))); //Find scaled ellipse angle
if(ellipseAngle < 0.0){ellipseAngle = 1.570796;} //Capping range to avoid negative rollover
let ellipseX = Math.cos(ellipseAngle); //use cos to find horizontal alligned value
let ellipseY = Math.sqrt( sq(antiDzInnerCYScale)*(1.0 - sq(ellipseX)) ); //use ellipse to find vertical value
antiDzInnerC = antiDzInnerC*Math.sqrt( sq(ellipseX) + sq(ellipseY)); //Find magnitude to scale antiCircleDeadzone
}
//Resizes circular antideadzone to output expected value(counters shrinkage when scaling for the square antideadzone below).
if (antiDzInnerC > 0.0) {
antiDzInnerC = antiDzInnerC/( (antiDzInnerC*(1.0 - antiDzSquare/dzOuter) )/( antiDzInnerC*(1.0 - antiDzSquare) ) );
}
//Angular Restriction
if(Math.abs(x) > axialRestrict && Math.abs(y) > axialRestrict){
if((angle > 0.0) && (angle < angularRestrict/2.0)){angle = 0.00;}
if(angle > 90.0 - angularRestrict/2.0 && angle < 90.0){angle = 90.0;}
if((angle > angularRestrict/2.0) && (angle < (90.0 - angularRestrict/2.0))){
angle = ((angle - angularRestrict/2.0)*(90.0))/((90.0 - angularRestrict/2.0) - angularRestrict/2.0);
}
}
let refAngle = angle;
if(refAngle < 0.001){refAngle = 0.0;}
//Diagonal ScalePrep
let diagonal = angle;
if(diagonal > 45.0){
diagonal = (((diagonal - 45.0)*(-45.0))/(45.0)) + 45.0;
}
//Angular Restriction Countering
if(angle < 90.0 && angle > 0.0){
angle = ((angle - 0.0)*((90.0 - (antiDzAngular/2.0)) - (antiDzAngular/2.0)))/(90.0) + (antiDzAngular/2.0);
}
//Flipping angles back to correct quadrant
if(axialX < 0.0 && axialY > 0.0){angle = -angle;}
if(axialX > 0.0 && axialY < 0.0){angle = angle - 180.0;}
if(axialX < 0.0 && axialY < 0.0){angle = angle + 180.0;}
//~~~~~~~~~~Deadzone wrap~~~~~~~~~~~~~~~~~~//
if(inputMagnitude > dzInner){
outputMagnitude = (inputMagnitude - dzInner)/(antiDzOuter - dzInner);
//Circular antideadzone scaling
outputMagnitude = ((Math.pow(outputMagnitude, (1.0/curve))*(dzOuter - antiDzInnerC) + antiDzInnerC));
//Capping max range
if(outputMagnitude > dzOuter && !uncapRadius){
outputMagnitude = dzOuter;
}
//Diagonal Scale
let dScale = (((outputMagnitude - antiDzInnerC)*(diagonalScaleMax - diagonalScaleMin))/(dzOuter - antiDzInnerC)) + diagonalScaleMin;
let cScale = (((diagonal - 0.0)*(1.0/Math.sqrt(2.0)))/(45.0)); //Both these lines scale the intensity of the warping
cScale = 1.0 - Math.sqrt(1.0 - cScale*cScale); //based on a circular curve to the perfect diagonal
dScale = (((cScale - 0.0)*(dScale - 1.0))/(.29289)) + 1.0;
outputMagnitude = outputMagnitude*dScale;
//Scaling values for square antideadzone
let newX = Math.cos(deg2rad(angle))*outputMagnitude;
let newY = Math.sin(deg2rad(angle))*outputMagnitude;
//Magic angle wobble fix by user ME.
// if (angle > 45.0 && angle < 225.0) {
// newX = inv(Math.sin(deg2rad(angle - 90.0)))*outputMagnitude;
// newY = inv(Math.cos(deg2rad(angle - 270.0)))*outputMagnitude;
// }
//Square antideadzone scaling
let outputX = Math.abs(newX)*(1.0 - antiDzSquare/dzOuter) + antiDzSquare;
if(x < 0.0){outputX = outputX*(-1.0);}
if(refAngle == 90.0){outputX = 0.0;}
let outputY = Math.abs(newY)*(1.0 - antiDzSquareYScale/dzOuter) + antiDzSquareYScale;
if(y < -0.0){outputY = outputY*(-1.0);}
if(refAngle == 0.0){outputY = 0.0;}
return { x: clamp(outputX, -dzOuter, dzOuter),
y: clamp(outputY, -dzOuter, dzOuter) };
} else {
return { x: 0.0, y: 0.0 };
}
}

View File

@@ -0,0 +1,29 @@
export class Mutex {
constructor() {
this.locked = false;
this.queue = [];
}
async lock() {
while (this.locked) {
await new Promise(resolve => this.queue.push(resolve));
}
this.locked = true;
}
async tryLock() {
if (this.locked) {
return false;
}
await this.lock();
return true;
}
unlock() {
this.locked = false;
if (this.queue.length > 0) {
const resolve = this.queue.shift();
resolve();
}
}
}

View File

@@ -0,0 +1,28 @@
export class TriggerSettings {
static SETTINGS = Object.freeze([
{ type: "float", key: "dzInner", min: 0.0, max: 0.5, def: 0.0, label: "Deadzone Inner", tip: "" },
{ type: "float", key: "dzOuter", min: 0.5, max: 1.0, def: 1.0, label: "Deadzone Outer", tip: "" },
{ type: "float", key: "antiDzInner", min: 0.0, max: 0.5, def: 0.0, label: "Anti-Deadzone Inner", tip: "" },
{ type: "float", key: "antiDzOuter", min: 0.5, max: 1.0, def: 1.0, label: "Anti-Deadzone Outer", tip: "" },
{ type: "float", key: 'curve', min: 0.3, max: 3.0, def: 1.0, label: "Curve", tip: "" },
]);
constructor() {
this.resetAll();
}
resetAll() {
TriggerSettings.SETTINGS.forEach(setting => {
this[setting.key] = setting.def;
});
}
getDefaultValue(key) {
const setting = TriggerSettings.SETTINGS.find(setting => setting.key === key);
if (setting !== undefined) {
return setting.def;
}
console.warn(`Setting not found: ${key}`);
return null;
}
}

View File

@@ -0,0 +1,171 @@
import { DrawUtils } from "./../drawUtils.js";
export class TriggerVisualizer {
#settings = null;
#input = null;
constructor(backgroundCanvas, settingsCanvas, inputCanvas) {
this.#settings = new Settings(settingsCanvas, backgroundCanvas);
this.#input = new Input(inputCanvas);
}
init(triggerSettings) {
this.#settings.init(triggerSettings);
this.#input.draw(-1);
}
drawSettings(triggerSettings) {
this.#settings.draw(triggerSettings);
}
drawInput(value, settings = null, preview = false) {
this.#input.draw(value, settings, preview);
}
}
class Input {
constructor (canvas) {
this.canvas = canvas;
this.context = canvas.getContext('2d');
this.colors = {
inputBar: 'rgba(44, 44, 255, 0.91)',
stroke: 'rgba(0, 0, 0, 0.72)',
}
this.strokeWidth = 4;
this.barWidth = 4;
this.lastValue = -2;
}
draw(value, settings, preview) {
let { canvas, context, colors, lastValue, barWidth, strokeWidth } = this;
if (settings && preview) {
value = applySettings(value, settings.dzInner, settings.dzOuter, settings.antiDzInner, settings.antiDzOuter, settings.curve);
}
if (value !== lastValue) {
lastValue = value;
const width = canvas.width - barWidth;
context.clearRect(0, 0, canvas.width, canvas.height);
const x = value * width;
const y = 2;
DrawUtils.drawRectangle(context, x, 0, barWidth, canvas.height, colors.inputBar);
}
DrawUtils.drawRectangle(context, 0, 0, canvas.width, canvas.height, null, colors.stroke, strokeWidth);
}
}
class Background {
constructor(canvas) {
this.canvas = canvas;
this.context = canvas.getContext('2d');
this.colors = {
background: 'rgb(249, 249, 249)',
stroke: 'rgba(0, 0, 0, 0.32)',
}
this.strokeWidth = 1
}
draw(triggersettings) {
const { canvas, context, colors, strokeWidth } = this;
context.clearRect(0, 0, canvas.width, canvas.height);
context.beginPath();
context.fillStyle = colors.background;
context.fill();
context.closePath();
const gridSpacing = canvas.width / 10;
context.lineWidth = strokeWidth;
context.strokeStyle = colors.stroke;
for (let x = 0; x < canvas.width; x += gridSpacing) {
context.beginPath();
context.moveTo(x, 0);
context.lineTo(x, canvas.height);
context.stroke();
context.closePath();
}
}
}
class Settings {
#background = null;
constructor(settingsCanvas, backgroundCanvas) {
this.#background = new Background(backgroundCanvas);
this.canvas = settingsCanvas;
this.context = this.canvas.getContext('2d');
this.colors = {
stroke: 'rgba(0, 0, 0, 0.72)',
antiDeadzone: 'rgba(0, 255, 0, 0.73)',
deadzone: 'rgba(255, 0, 0, 0.6)',
}
this.strokeWidth = 4;
}
init(triggerSettings) {
this.#background.draw(triggerSettings);
this.draw(triggerSettings);
}
draw(triggerSettings) {
const { canvas, context, background, colors, strokeWidth } = this;
const { dzInner, dzOuter, antiDzInner, antiDzOuter } = triggerSettings;
const dzInnerWidth = dzInner * canvas.width;
const dzOuterWidth = (1 - dzOuter) * canvas.width;
const antiDzInnerWidth = antiDzInner * canvas.width;
const antiDzOuterWidth = (1 - antiDzOuter) * canvas.width;
context.clearRect(0, 0, canvas.width, canvas.height);
if (antiDzInnerWidth) {
DrawUtils.drawRectangle(context, 0, 0, antiDzInnerWidth, canvas.height, colors.antiDeadzone);
}
if (antiDzOuterWidth) {
DrawUtils.drawRectangle(context, canvas.width - antiDzOuterWidth, 0, antiDzOuterWidth, canvas.height, colors.antiDeadzone);
}
if (dzInnerWidth) {
DrawUtils.drawRectangle(context, 0, 0, dzInnerWidth, canvas.height, colors.deadzone);
}
if (dzOuterWidth) {
DrawUtils.drawRectangle(context, canvas.width - dzOuterWidth, 0, dzOuterWidth, canvas.height, colors.deadzone);
}
}
}
function applySettings(value, dzInner, dzOuter, antiDzInner, antiDzOuter, curve) {
const clamp = (v, min, max) => Math.max(min, Math.min(max, v));
const absValue = Math.abs(value);
if (absValue < dzInner) {
return 0.0;
}
let normalizedValue = (absValue - dzInner) / (dzOuter - dzInner);
normalizedValue = clamp(normalizedValue, 0.0, 1.0);
if (antiDzInner > 0.0) {
normalizedValue = antiDzInner + (1.0 - antiDzInner) * normalizedValue;
}
if (curve !== 1.0) {
normalizedValue = Math.pow(normalizedValue, 1.0 / curve);
}
if (antiDzOuter < 1.0) {
const scaleFactor = 1.0 / (1.0 - antiDzOuter);
normalizedValue = clamp(normalizedValue * scaleFactor, 0.0, 1.0);
}
normalizedValue *= dzOuter;
return normalizedValue;
}

View File

@@ -0,0 +1,46 @@
export const UIProgram = {
addProgramPicoCallback(callback) {
const buttonProgramPico = document.getElementById("button-programPico");
buttonProgramPico.addEventListener("click", async () => {
await callback();
});
},
addProgramEsp32Callback(callback) {
const buttonProgramEsp32 = document.getElementById("button-programEsp32");
buttonProgramEsp32.addEventListener("click", async () => {
await callback();
});
},
enableProgramPicoButton(enabled) {
const buttonProgramPico = document.getElementById("button-programPico");
buttonProgramPico.disabled = !enabled;
},
enableProgramEsp32Button(enabled) {
const buttonProgramEsp32 = document.getElementById("button-programEsp32");
buttonProgramEsp32.disabled = !enabled;
},
toggleConnected(connected) {
const connectPanel = document.getElementById("connectPanel");
const programPanel = document.getElementById("programPanel");
if (connected) {
if (programPanel.classList.contains("hidden")) {
programPanel.classList.remove("hidden");
connectPanel.classList.add("hidden");
programPanel.classList.add("show");
}
} else {
if (connectPanel.classList.contains("hidden")) {
connectPanel.classList.remove("hidden");
programPanel.classList.add("hidden");
connectPanel.classList.add("show");
}
}
}
};

View File

@@ -0,0 +1,677 @@
import { JoystickSettings } from "./joystick/joystickSettings.js";
import { JoystickVisualizer } from "./joystick/joystickVisualizer.js";
import { TriggerSettings } from "./trigger/triggerSettings.js";
import { TriggerVisualizer } from "./trigger/triggerVisualizer.js";
import { UserSettings } from "./userSettings.js";
const SliderSnapThreshold = 0.02;
function uiCreateSlider(settings, visualizer, prefix, side, { key, label, min, max, def, tip }) {
const wrapper = document.createElement("div");
wrapper.classList.add("settingsSubPair");
const elementId = `slider-${prefix}-${key}-${side}`;
const labelElement = document.createElement("label");
labelElement.setAttribute("for", elementId);
labelElement.textContent = label;
const slider = document.createElement("input");
slider.type = "range";
slider.id = elementId;
slider.min = parseFloat(min) * 100;
slider.max = parseFloat(max) * 100;
slider.step = 1;
slider.value = parseFloat(def) * 100;
slider.title = tip;
const valueDisplay = document.createElement("span");
valueDisplay.id = `${elementId}-value`;
valueDisplay.textContent = (parseFloat(def)).toFixed(2);
slider.addEventListener("input", () => {
let value = (slider.value / 100).toFixed(2);
if (Math.abs(value - def) <= SliderSnapThreshold) {
value = def;
}
valueDisplay.textContent = (value * 1).toFixed(2)
slider.value = value * 100;
settings[key] = parseFloat(value);
visualizer.drawSettings(settings);
});
wrapper.appendChild(labelElement);
wrapper.appendChild(slider);
wrapper.appendChild(valueDisplay);
return wrapper;
}
function uiCreateCheckbox(settings, visualizer, prefix, suffix, { key, label, def, tip }) {
const wrapper = document.createElement("div");
wrapper.classList.add("settingsSubPair");
const elementId = `checkbox-${prefix}-${key}-${suffix}`;
const labelElement = document.createElement("label");
labelElement.setAttribute("for", elementId);
labelElement.textContent = label;
const checkbox = document.createElement("input");
checkbox.type = "checkbox";
checkbox.id = elementId;
checkbox.checked = def;
checkbox.title = tip;
const valueDisplay = document.createElement("span");
valueDisplay.id = `${elementId}-value`;
valueDisplay.textContent = "";
checkbox.addEventListener("change", () => {
const isChecked = checkbox.checked;
settings[key] = isChecked;
visualizer.drawSettings(settings);
});
wrapper.appendChild(labelElement);
wrapper.appendChild(checkbox);
wrapper.appendChild(valueDisplay);
return wrapper;
}
function uiCreateResetButton(settings, visualizer, fields, prefix, suffix) {
const wrapper = document.createElement("div");
const button = document.createElement("button");
button.textContent = "Reset";
button.addEventListener("click", () => {
settings.resetAll();
fields.forEach(field => {
const elementId = field.type === "float"
? `slider-${prefix}-${field.key}-${suffix}`
: `checkbox-${prefix}-${field.key}-${suffix}`;
const element = document.getElementById(elementId);
const valueDisplay = document.getElementById(`${elementId}-value`);
if (element) {
if (field.type === "float") {
element.value = field.def * 100;
if (valueDisplay) {
valueDisplay.textContent = field.def.toFixed(2);
}
} else if (field.type === "bool") {
element.checked = field.def;
}
} else {
console.warn(`Element not found: ${elementId}`);
}
});
visualizer.drawSettings(settings);
});
wrapper.appendChild(button);
return wrapper;
}
function uiGenerateJoystickSettings(settings, visualizer, side, containerPrefix) {
const container = document.getElementById(`${containerPrefix}-${side}`);
if (!container) {
console.warn(`Container not found: ${containerPrefix}-${side}`);
return;
}
const prefix = "joystick";
JoystickSettings.SETTINGS.forEach(field => {
let element;
if (field.type === "float") {
// const elementId = `slider-${prefix}-${setting.key}-${side}`;
element = uiCreateSlider(settings, visualizer, prefix, side, field);
} else {
element = uiCreateCheckbox(settings, visualizer, prefix, side, field);
}
container.appendChild(element);
});
const resetButton = uiCreateResetButton(settings, visualizer, JoystickSettings.SETTINGS, prefix, side);
container.appendChild(resetButton);
}
function uiGenerateTriggerSettings(settings, visualizer, suffix, containerPrefix) {
const container = document.getElementById(`${containerPrefix}-${suffix}`);
if (!container) {
console.warn(`Container not found: ${containerPrefix}-${suffix}`);
return;
}
const prefix = "trigger";
TriggerSettings.SETTINGS.forEach(field => {
let element;
if (field.type === "float") {
element = uiCreateSlider(settings, visualizer, prefix, suffix, field);
} else if (field.type === "bool") {
element = uiCreateCheckbox(settings, visualizer, prefix, suffix, field);
}
container.appendChild(element);
});
const resetButton = uiCreateResetButton(settings, visualizer, TriggerSettings.SETTINGS, prefix, suffix);
container.appendChild(resetButton);
}
function uiCreateButtonDropdown(userSettings, field, fields) {
const wrapper = document.createElement("div");
wrapper.classList.add("dropdownSubPair");
const labelElement = document.createElement("label");
labelElement.setAttribute("for", `dropdown-${field.key}`);
labelElement.textContent = field.label;
const dropdown = document.createElement("select");
dropdown.id = `dropdown-${field.key}`;
fields.forEach((option) => {
const optionElement = document.createElement("option");
optionElement.value = option.def;
optionElement.textContent = option.label;
dropdown.appendChild(optionElement);
if (option.def === userSettings.profile[field.key]) {
optionElement.selected = true;
}
});
dropdown.addEventListener("change", () => {
const value = parseInt(dropdown.value, 10);
userSettings.profile[field.key] = value;
});
wrapper.appendChild(labelElement);
wrapper.appendChild(dropdown);
return wrapper;
}
function uiGenerateButtonSettings(userSettings) {
const dpadFields = userSettings.getDpadFields();
const dpadContainerPrefix = "digitalDpadInput";
let containerSuffix = "left";
userSettings.getDpadFields().forEach(field => {
const element = uiCreateButtonDropdown(userSettings, field, dpadFields);
const container = document.getElementById(`${dpadContainerPrefix}-${containerSuffix}`);
container.appendChild(element);
if (containerSuffix === "left") {
containerSuffix = "right";
} else {
containerSuffix = "left";
}
});
const buttonFields = userSettings.getButtonFields();
const buttonContainerPrefix = "digitalButtonInput";
containerSuffix = "left";
userSettings.getButtonFields().forEach(field => {
const element = uiCreateButtonDropdown(userSettings, field, buttonFields);
const container = document.getElementById(`${buttonContainerPrefix}-${containerSuffix}`);
container.appendChild(element);
if (containerSuffix === "left") {
containerSuffix = "right";
} else {
containerSuffix = "left";
}
});
const analogFields = userSettings.getAnalogFields();
const analogContainerPrefix = "analogButtonsInput";
containerSuffix = "left";
userSettings.getAnalogFields().forEach(field => {
const element = uiCreateButtonDropdown(userSettings, field, analogFields);
const container = document.getElementById(`${analogContainerPrefix}-${containerSuffix}`);
container.appendChild(element);
if (containerSuffix === "left") {
containerSuffix = "right";
} else {
containerSuffix = "left";
}
});
}
function uiSetupGeneralSettings(userSettings) {
const elementProfileId = document.getElementById("dropdown-profileId");
if (!elementProfileId) {
console.warn("Profile dropdown not found.");
return;
}
UserSettings.PROFILE_ID_OPTIONS.fields.forEach(field => {
const optionElement = document.createElement("option");
optionElement.value = field.value;
optionElement.textContent = field.label;
elementProfileId.appendChild(optionElement);
if (field.value === userSettings.profile.profileId) {
optionElement.selected = true;
}
});
elementProfileId.addEventListener("change", () => {
userSettings.profile.profileId = parseInt(elementProfileId.value, 10);
});
const elementPlayerIdx = document.getElementById("dropdown-playerIdx");
if (!elementPlayerIdx) {
console.warn("Player index dropdown not found.");
return;
}
UserSettings.PLAYER_IDX_OPTIONS.fields.forEach(field => {
const optionElement = document.createElement("option");
optionElement.value = field.value;
optionElement.textContent = field.label;
elementPlayerIdx.appendChild(optionElement);
if (field.value === userSettings.playerIdx) {
optionElement.selected = true;
}
});
if (userSettings.maxGamepads < 2) {
elementPlayerIdx.disabled = true;
}
elementPlayerIdx.addEventListener("change", () => {
userSettings.playerIdx = parseInt(elementPlayerIdx.value, 10);
});
const elementDeviceMode = document.getElementById("dropdown-deviceMode");
if (!elementDeviceMode) {
console.warn("Device mode dropdown not found.");
return;
}
UserSettings.DEVICE_MODE_OPTIONS.fields.forEach(field => {
const optionElement = document.createElement("option");
optionElement.value = field.value;
optionElement.textContent = field.label;
elementDeviceMode.appendChild(optionElement);
if (field.value === userSettings.deviceMode) {
optionElement.selected = true;
}
});
elementDeviceMode.addEventListener("change", () => {
userSettings.deviceMode = parseInt(elementDeviceMode.value, 10);
});
const elementEnableAnalog = document.getElementById("checkbox-analogEnabled");
if (!elementEnableAnalog) {
console.warn("Analog button checkbox not found.");
return;
}
elementEnableAnalog.checked = userSettings.profile.analogEnabled;
elementEnableAnalog.addEventListener("change", () => {
userSettings.profile.analogEnabled = elementEnableAnalog.checked;
});
}
function uiSetupHidePanelListeners() {
function togglePanel(panel, button) {
panel.classList.toggle("hidden");
if (panel.classList.contains("hidden")) {
button.textContent = "Show";
} else {
button.textContent = "Hide";
}
}
const axisPanelButton = document.getElementById("button-toggleAxisSettings");
axisPanelButton.addEventListener("click", () => {
const panel = document.getElementById("axisSettingsPanel");
togglePanel(panel, axisPanelButton);
});
const digitalPanelButton = document.getElementById("button-toggleDigitalButtons");
digitalPanelButton.addEventListener("click", () => {
const panel = document.getElementById("digitalButtonsPanel")
togglePanel(panel, digitalPanelButton);
});
const analogPanelButton = document.getElementById("button-toggleAnalogButtons");
analogPanelButton.addEventListener("click", () => {
const panel = document.getElementById("analogButtonsPanel");
togglePanel(panel, analogPanelButton);
});
}
function uiSetupAxisPreviewCheckboxes(userSettings) {
const tip = "To get an accurate preview, reset the profile to defaults and save it before enabling this feature.";
let elements = [];
elements.push(document.getElementById("checkbox-previewJoy-left"));
elements.push(document.getElementById("checkbox-previewJoy-right"));
elements.push(document.getElementById("checkbox-previewTrigger-left"));
elements.push(document.getElementById("checkbox-previewTrigger-right"));
elements.forEach(element => {
element.title = tip;
});
}
export const UI = {
Joysticks: new Map(),
Triggers: new Map(),
init(userSettings) {
UserSettings.SIDES.forEach(side => {
const canvasJoystickBackground = document.getElementById(`canvasJoystickBackground-${side}`);
const canvasJoystickSettings = document.getElementById(`canvasJoystickSettings-${side}`);
const canvasJoystickCursor = document.getElementById(`canvasJoystickCursor-${side}`);
this.Joysticks.set(side, {
visualizer: new JoystickVisualizer(
canvasJoystickBackground,
canvasJoystickSettings,
canvasJoystickCursor
)
});
const joystickVisualizer = this.Joysticks.get(side).visualizer;
const joystickSettings = userSettings.profile[`joystickSettings-${side}`];
uiGenerateJoystickSettings(joystickSettings, joystickVisualizer, side, "joystickInput");
joystickVisualizer.init(joystickSettings);
const canvasTriggerBackground = document.getElementById(`canvasTriggerBackground-${side}`);
const canvasTriggerSettings = document.getElementById(`canvasTriggerSettings-${side}`);
const canvasTriggerCursor = document.getElementById(`canvasTriggerCursor-${side}`);
this.Triggers.set(side, {
visualizer: new TriggerVisualizer(
canvasTriggerBackground,
canvasTriggerSettings,
canvasTriggerCursor
)
});
const triggerVisualizer = this.Triggers.get(side).visualizer;
const triggerSettings = userSettings.profile[`triggerSettings-${side}`];
uiGenerateTriggerSettings(triggerSettings, triggerVisualizer, side, "triggerInput");
triggerVisualizer.init(triggerSettings);
});
uiSetupGeneralSettings(userSettings);
uiGenerateButtonSettings(userSettings);
uiSetupAxisPreviewCheckboxes(userSettings);
uiSetupHidePanelListeners();
const loadDefaultButton = document.getElementById("button-loadDefaults");
if (loadDefaultButton) {
loadDefaultButton.addEventListener("click", () => {
userSettings.resetProfile();
UI.updateAll(userSettings);
});
}
},
addCallbackSaveProfile(listenerFunc, userSettings) {
const saveButton = document.getElementById("button-saveProfile");
if (saveButton) {
saveButton.addEventListener("click", () => listenerFunc());
} else {
console.warn("Save button not found.");
}
},
addCallbackLoadProfile(listenerFunc, userSettings) {
if (!userSettings) {
console.error("User settings not provided.");
}
const reloadButton = document.getElementById("button-reloadProfile");
if (reloadButton) {
reloadButton.addEventListener("click", () => {
const profileIdDropdown = document.getElementById("dropdown-profileId");
if (profileIdDropdown) {
userSettings.profile.profileId = parseInt(profileIdDropdown.value, 10);
listenerFunc();
} else {
console.warn("Profile ID dropdown not found.");
}
});
} else {
console.warn("Reload button not found.");
}
const profileIdDropdown = document.getElementById("dropdown-profileId");
if (profileIdDropdown) {
profileIdDropdown.addEventListener("change", () => {
userSettings.profile.profileId = parseInt(profileIdDropdown.value, 10);
listenerFunc();
});
} else {
console.warn("Profile ID dropdown not found.");
}
},
addCallbackDisconnect(listenerFunc) {
const disconnectButton = document.getElementById("button-disconnect");
if (disconnectButton) {
disconnectButton.addEventListener("click", () => listenerFunc());
} else {
console.warn("Disconnect button not found.");
}
},
toggleConnected(connected) {
const settingsElement = document.getElementById("settingsPanel");
const connectElement = document.getElementById("connectPanel");
if (connected) {
if (settingsElement.classList.contains("hidden")) {
settingsElement.classList.remove("hidden");
connectElement.classList.add("hidden");
settingsElement.classList.add("show");
}
} else {
if (connectElement.classList.contains("hidden")) {
connectElement.classList.remove("hidden");
settingsElement.classList.add("hidden");
connectElement.classList.add("show");
}
}
},
updateAll(userSettings) {
const elementProfileId = document.getElementById("dropdown-profileId");
const elementPlayerIdx = document.getElementById("dropdown-playerIdx");
const elementDeviceMode = document.getElementById("dropdown-deviceMode");
if (elementProfileId) {
elementProfileId.value = userSettings.profile.profileId;
}
if (elementPlayerIdx) {
elementPlayerIdx.value = userSettings.playerIdx;
}
if (elementDeviceMode) {
elementDeviceMode.value = userSettings.deviceMode;
}
UserSettings.SIDES.forEach(side => {
const prefix = "joystick";
const joystickSettings = userSettings.profile[`joystickSettings-${side}`];
const visualizer = this.Joysticks.get(side).visualizer;
JoystickSettings.SETTINGS.forEach(field => {
const elementId = field.type === "float"
? `slider-${prefix}-${field.key}-${side}`
: `checkbox-${prefix}-${field.key}-${side}`;
const element = document.getElementById(elementId);
if (element) {
const value = joystickSettings[field.key];
if (field.type === "float") {
element.value = value * 100;
const valueDisplay = document.getElementById(`${elementId}-value`);
if (valueDisplay) {
valueDisplay.textContent = value.toFixed(2);
}
} else if (field.type === "bool") {
element.checked = value;
}
}
});
if (!visualizer) {
console.warn("Visualizer not found for joystick.");
}
visualizer.drawSettings(joystickSettings);
});
UserSettings.SIDES.forEach(side => {
const prefix = "trigger";
const triggerSettings = userSettings.profile[`triggerSettings-${side}`];
TriggerSettings.SETTINGS.forEach(field => {
const elementId = field.type === "float"
? `slider-${prefix}-${field.key}-${side}`
: `checkbox-${prefix}-${field.key}-${side}`;
const element = document.getElementById(elementId);
if (element) {
const value = triggerSettings[field.key];
if (field.type === "float") {
element.value = value * 100;
const valueDisplay = document.getElementById(`${elementId}-value`);
if (valueDisplay) {
valueDisplay.textContent = value.toFixed(2);
}
} else if (field.type === "bool") {
element.checked = value;
}
}
});
this.Triggers.get(side).visualizer.drawSettings(triggerSettings);
});
const updateButtonDropdowns = (fields, prefix) => {
fields.forEach(field => {
const dropdown = document.getElementById(`dropdown-${field.key}`);
if (dropdown) {
dropdown.value = userSettings.profile[field.key];
}
});
};
updateButtonDropdowns(userSettings.getDpadFields(), "digitalDpadInput");
updateButtonDropdowns(userSettings.getButtonFields(), "digitalButtonInput");
updateButtonDropdowns(userSettings.getAnalogFields(), "analogButtonsInput");
const elementEnableAnalog = document.getElementById("checkbox-analogEnabled");
if (elementEnableAnalog) {
elementEnableAnalog.checked = userSettings.profile.analogEnabled;
}
},
drawGamepadInput(gamepad, userSettings) {
const joyVisualizerL = this.Joysticks.get("left").visualizer;
const joyVisualizerR = this.Joysticks.get("right").visualizer;
const trigVisualizerL = this.Triggers.get("left").visualizer;
const trigVisualizerR = this.Triggers.get("right").visualizer;
let joyLx = gamepad.scaledJoystickLx();
let joyLy = gamepad.scaledJoystickLy();
let joyRx = gamepad.scaledJoystickRx();
let joyRy = gamepad.scaledJoystickRy();
let triggerL = gamepad.scaledTriggerL();
let triggerR = gamepad.scaledTriggerR();
const prevJoyL = document.getElementById("checkbox-previewJoy-left").checked;
const prevJoyR = document.getElementById("checkbox-previewJoy-right").checked;
const prevTrigL = document.getElementById("checkbox-previewTrigger-left").checked;
const prevTrigR = document.getElementById("checkbox-previewTrigger-right").checked;
joyVisualizerL.drawInput(joyLx, joyLy, userSettings.profile[`joystickSettings-left`], prevJoyL);
joyVisualizerR.drawInput(joyRx, joyRy, userSettings.profile[`joystickSettings-right`], prevJoyR);
trigVisualizerL.drawInput(triggerL, userSettings.profile[`triggerSettings-left`], prevTrigL);
trigVisualizerR.drawInput(triggerR, userSettings.profile[`triggerSettings-right`], prevTrigR);
},
connectButtonsEnabled(enabled) {
const connectButtonUsb = document.getElementById("connectUsb");
if (connectButtonUsb) {
connectButtonUsb.disabled = !enabled;
} else {
console.warn("Connect button not found.");
}
const connectButtonBt = document.getElementById("connectBt");
if (connectButtonBt) {
connectButtonBt.disabled = !enabled;
} else {
console.warn("Connect button not found.");
}
const programButton = document.getElementById("connectOgxmW");
if (programButton) {
programButton.disabled = !enabled;
} else {
console.warn("Connect button not found.");
}
},
setSubheaderText(text) {
const subheader = document.getElementById("subheader");
if (subheader) {
subheader.querySelector("h3").textContent = text;
} else {
console.warn("Subheader not found.");
}
},
getSelectedProfileId() {
const elementProfileId = document.getElementById("dropdown-profileId");
if (elementProfileId) {
return parseInt(elementProfileId.value, 10);
} else {
console.warn("Profile ID dropdown not found.");
return -1;
}
},
getSelectedPlayerIdx() {
const elementPlayerIdx = document.getElementById("dropdown-playerIdx");
if (elementPlayerIdx) {
return parseInt(elementPlayerIdx.value, 10);
} else {
console.warn("Player index dropdown not found.");
return -1;
}
},
getSelectedDeviceMode() {
const elementDeviceMode = document.getElementById("dropdown-deviceMode");
if (elementDeviceMode) {
return parseInt(elementDeviceMode.value, 10);
} else {
console.warn("Device mode dropdown not found.");
return -1;
}
}
};

View File

@@ -0,0 +1,302 @@
import { JoystickSettings } from "./joystick/joystickSettings.js";
import { TriggerSettings } from "./trigger/triggerSettings.js";
export class UserSettings {
static PROFILE_LENGTH = Object.freeze(190);
static #FIX16_LENGTH = Object.freeze(4);
static SIDES = Object.freeze(["left", "right"]);
static PLAYER_IDX_OPTIONS = Object.freeze({
key: "playerIdx",
def: 0,
fields: [
{ label: "Player 1", value: 0 },
{ label: "Player 2", value: 1 },
{ label: "Player 3", value: 2 },
{ label: "Player 4", value: 3 },
]
});
static DEVICE_MODE_OPTIONS = Object.freeze({
key: "deviceMode",
def: 100,
fields: [
{ label: "Xbox OG", value: 1 },
{ label: "Xbox OG: Steel Battalion", value: 2 },
{ label: "Xbox OG: XRemote", value: 3 },
{ label: "XInput", value: 4 },
{ label: "PS3", value: 5 },
{ label: "DInput", value: 6 },
{ label: "PS Classic", value: 7 },
{ label: "Switch", value: 8 },
{ label: "WebApp", value: 100 },
]
});
static DEVICE_MODE_OPTIONS_MULTI_GP = Object.freeze({
key: "deviceMode",
def: 100,
fields: [
{ label: "DInput", value: 6 },
{ label: "Switch", value: 8 },
{ label: "WebApp", value: 100 },
]
});
static DEVICE_MODE_OPTIONS_4CH = Object.freeze({
key: "deviceMode",
def: 100,
fields: [
{ label: "Xbox OG", value: 1 },
{ label: "Xbox OG: Steel Battalion", value: 2 },
{ label: "Xbox OG: XRemote", value: 3 },
{ label: "XInput", value: 4 },
{ label: "PS3", value: 5 },
{ label: "PS Classic", value: 7 },
{ label: "WebApp", value: 100 },
]
});
static PROFILE_ID_OPTIONS = Object.freeze({
key: "profile.profileId",
def: 1,
fields: [
{ label: "Profile 1", value: 1 },
{ label: "Profile 2", value: 2 },
{ label: "Profile 3", value: 3 },
{ label: "Profile 4", value: 4 },
{ label: "Profile 5", value: 5 },
{ label: "Profile 6", value: 6 },
{ label: "Profile 7", value: 7 },
{ label: "Profile 8", value: 8 },
]
});
static #PROFILE_SETTINGS = Object.freeze([
{ type: "int", key: "profileId", size: 1, def: 1 },
{ type: "map", key: "joystickSettings-left", size: 55, map: JoystickSettings.SETTINGS },
{ type: "map", key: "joystickSettings-right", size: 55, map: JoystickSettings.SETTINGS },
{ type: "map", key: "triggerSettings-left", size: 20, map: TriggerSettings.SETTINGS },
{ type: "map", key: "triggerSettings-right", size: 20, map: TriggerSettings.SETTINGS },
{ type: "int", key: "dpadUp", size: 1, def: 0x01, label: "Up" },
{ type: "int", key: "dpadDown", size: 1, def: 0x02, label: "Down" },
{ type: "int", key: "dpadLeft", size: 1, def: 0x04, label: "Left" },
{ type: "int", key: "dpadRight", size: 1, def: 0x08, label: "Right" },
{ type: "int", key: "buttonA", size: 2, def: 0x0001, label: "A" },
{ type: "int", key: "buttonB", size: 2, def: 0x0002, label: "B" },
{ type: "int", key: "buttonX", size: 2, def: 0x0004, label: "X" },
{ type: "int", key: "buttonY", size: 2, def: 0x0008, label: "Y" },
{ type: "int", key: "buttonL3", size: 2, def: 0x0010, label: "L3" },
{ type: "int", key: "buttonR3", size: 2, def: 0x0020, label: "R3" },
{ type: "int", key: "buttonBack", size: 2, def: 0x0040, label: "Back" },
{ type: "int", key: "buttonStart", size: 2, def: 0x0080, label: "Start" },
{ type: "int", key: "buttonLb", size: 2, def: 0x0100, label: "LB" },
{ type: "int", key: "buttonRb", size: 2, def: 0x0200, label: "RB" },
{ type: "int", key: "buttonSys", size: 2, def: 0x0400, label: "Sys" },
{ type: "int", key: "buttonMisc", size: 2, def: 0x0800, label: "Misc" },
{ type: "bool",key: "analogEnabled", size: 1, def: true },
{ type: "int", key: "analogOffUp", size: 1, def: 0, label: "Up" },
{ type: "int", key: "analogOffDown", size: 1, def: 1, label: "Down" },
{ type: "int", key: "analogOffLeft", size: 1, def: 2, label: "Left" },
{ type: "int", key: "analogOffRight", size: 1, def: 3, label: "Right" },
{ type: "int", key: "analogOffA", size: 1, def: 4, label: "A" },
{ type: "int", key: "analogOffB", size: 1, def: 5, label: "B" },
{ type: "int", key: "analogOffX", size: 1, def: 6, label: "X" },
{ type: "int", key: "analogOffY", size: 1, def: 7, label: "Y" },
{ type: "int", key: "analogOffLb", size: 1, def: 8, label: "LB" },
{ type: "int", key: "analogOffRb", size: 1, def: 9, label: "RB" },
]);
/* Each joystickSettings-SIDE and triggerSettings-SIDE are referenced
by the UI, don't replace them with a new object after calling UI.init() */
constructor() {
this.profile = {};
for (const field of UserSettings.#PROFILE_SETTINGS) {
const { type, key, size, map } = field;
if (type === "map") {
if (key.toLowerCase().includes("joystick")) {
this.profile[key] = new JoystickSettings();
} else if (key.toLowerCase().includes("trigger")) {
this.profile[key] = new TriggerSettings();
}
} else {
this.profile[key] = field.def;
}
}
this.playerIdx = UserSettings.PLAYER_IDX_OPTIONS.def;
this.deviceMode = UserSettings.DEVICE_MODE_OPTIONS.def;
this.maxGamepads = 1;
}
resetProfile() {
UserSettings.#PROFILE_SETTINGS.forEach(field => {
if (field.type !== "map" && field.key !== "profileId") {
this.profile[field.key] = field.def;
} else if (field.type === "map") {
this.profile[field.key].resetAll();
}
});
}
getDeviceModeOptions(maxGamepads) {
if (maxGamepads === 1) {
return UserSettings.DEVICE_MODE_OPTIONS;
} else if (maxGamepads === 4) {
return UserSettings.DEVICE_MODE_OPTIONS_4CH;
}
return UserSettings.DEVICE_MODE_OPTIONS_MULTI_GP;
}
setProfileFromBytes(buffer) {
if (!(buffer instanceof Uint8Array)) {
throw new Error("Invalid buffer type.");
} else if (buffer.length !== UserSettings.PROFILE_LENGTH) {
throw new Error(`Invalid buffer length: expected ${UserSettings.PROFILE_LENGTH} bytes`);
}
let offset = 0;
for (const field of UserSettings.#PROFILE_SETTINGS) {
const { type, key, map, size } = field;
if (type === "map") {
map.forEach(subField => {
const { type: subType, key: subKey, def: def } = subField;
if (subType === "float") {
this.profile[key][subKey] = this.#fix16ToFloat(buffer.slice(offset, offset + UserSettings.#FIX16_LENGTH));
offset += UserSettings.#FIX16_LENGTH;
} else if (subType === "bool") {
this.profile[key][subKey] = (buffer[offset] > 0);
offset += 1;
}
});
} else if (type === "bool") {
this.profile[key] = buffer[offset] > 0;
offset += 1;
} else if (type === "int") {
if (size === 1) {
this.profile[key] = buffer[offset];
offset += 1;
} else if (size === 2) {
this.profile[key] = this.#uint16ToInt(buffer[offset], buffer[offset + 1]);
offset += 2;
} else {
throw new Error(`Unsupported size for key: ${key}`);
}
} else {
throw new Error(`Unsupported size for key: ${key}`);
}
}
if (offset !== UserSettings.PROFILE_LENGTH) {
throw new Error(`Invalid profile size: expected ${UserSettings.PROFILE_LENGTH}, got ${offset}`);
}
}
getProfileBytes() {
let data = [];
for (const field of UserSettings.#PROFILE_SETTINGS) {
const { type, key, map, size } = field;
if (type === "map") {
for (const subField of map) {
const { type: subType, key: subKey } = subField;
if (subType === "float") {
data.push(...this.#floatToFix16(this.profile[key][subKey])); // fix16_t (int32_t)
} else if (subType === "bool") {
data.push(this.profile[key][subKey] ? 1 : 0); // uint8_t
}
}
} else {
const value = this.profile[key];
if (size === 1) {
data.push(value); // uint8_t
} else if (size === 2) {
data.push(...this.#intToUint16(value)); // uint16_t
} else {
throw new Error(`Unsupported size for key: ${key}`);
}
}
}
const bytes = new Uint8Array(data);
if (bytes.length !== UserSettings.PROFILE_LENGTH) {
throw new Error(`Invalid profile size: expected ${UserSettings.PROFILE_LENGTH}, got ${bytes.length}`);
}
return bytes;
}
getDpadFields() {
let dpadFields = [];
UserSettings.#PROFILE_SETTINGS.forEach((field) => {
if (field.key.toLowerCase().startsWith("dpad")) {
dpadFields.push(field);
}
});
return dpadFields;
}
getButtonFields() {
let buttonFields = [];
UserSettings.#PROFILE_SETTINGS.forEach((field) => {
if (field.key.toLowerCase().startsWith("button")) {
buttonFields.push(field);
}
});
return buttonFields;
}
getAnalogFields() {
let analogFields = [];
UserSettings.#PROFILE_SETTINGS.forEach((field) => {
if (field.key.toLowerCase().startsWith("analog")
&& field.key !== "analogEnabled") {
analogFields.push(field);
}
});
return analogFields;
}
#uint16ToInt(byte0, byte1) {
return byte0 | (byte1 << 8);
}
#intToUint16(value) {
return [value & 0xff, value >> 8];
}
#floatToFix16(value) {
let temp = value * 65536;
temp += (temp >= 0) ? 0.5 : -0.5;
const rawValue = temp | 0;
const buffer = new ArrayBuffer(4);
const view = new DataView(buffer);
view.setInt32(0, rawValue, true);
return new Uint8Array(buffer);
}
#fix16ToFloat(bytes) {
if (!(bytes instanceof Uint8Array) || bytes.length !== 4) {
throw new Error("fix16_t must be a 4-byte Uint8Array.");
}
const int32 = new Int32Array(bytes.buffer, bytes.byteOffset, bytes.byteLength / 4);
const rawValue = int32[0];
return rawValue / 0x00010000;
}
}

View File

@@ -0,0 +1 @@
python -m http.server 8000

267
Firmware/pico/web/style.css Normal file
View File

@@ -0,0 +1,267 @@
:root {
--font: -apple-system, BlinkMacSystemFont, "Segoe UI", Roboto, "Helvetica Neue", Arial, sans-serif;
--primary-color: #007bff;
--background-color: #f8f9fa;
--text-color: #212529;
}
h1 {
margin-top: 0px;
margin-bottom: 6px;
}
h1, h2, h3, h4, h5, h6 {
margin-top: 10px;
margin-bottom: 10px;
}
body {
font-family: var(--font);
background-color: var(--background-color);
color: var(--text-color);
padding: 20px;
}
button:hover {
opacity: 0.5;
}
.connectPanel button:disabled {
background-color: #e9ecef;
color: #6c757d;
cursor: not-allowed;
}
.error {
color: rgb(255, 0, 0);
margin-top: 10px;
}
.hidden {
display: none;
}
select {
width: 100%;
padding: 4px;
margin-bottom: 4px;
}
select:disabled {
background-color: #e9ecef;
color: #6c757d;
cursor: not-allowed;
border: 1px solid #ced4da;
}
.container {
max-width: 740px;
margin: auto;
background-color: #fff;
padding: 20px;
border-radius: 5px;
box-shadow: 0 2px 4px rgba(0,0,0,0.1);
}
.separator {
display: flex;
align-items: center;
margin-top: 15px;
margin-bottom: 15px;
border-bottom: #000000 1px solid;
}
.programPanel button:disabled {
background-color: #e9ecef;
color: #6c757d;
cursor: not-allowed;
}
.programLogPanel {
margin-top: 20px;
}
.connectPanel {
margin-bottom: 20px;
}
.connectPanel .separator {
display: flex;
align-items: center;
margin-top: 20px;
margin-bottom: 20px;
border-bottom: #000000 1px solid;
}
.connectPanel button,
.programPanel button {
background-color: var(--primary-color);
color: #fff;
border: none;
padding: 10px 20px;
border-radius: 5px;
cursor: pointer;
transition: background-color 0.2s;
margin-right: 15px;
}
.controlsPanel {
display: flex;
justify-content: left;
align-items: center;
flex-wrap: wrap;
margin-top: 20px;
border-top: #000000 1px solid;
}
.controlsPanel button {
background-color: var(--primary-color);
color: #fff;
border: none;
padding: 10px 20px;
border-radius: 5px;
cursor: pointer;
transition: background-color 0.2s;
margin-top: 20px;
margin-right: 20px;
}
.settingsPanel .triPanel {
display: grid;
grid-template-columns: 1fr 1fr 1fr;
gap: 20px;
align-items: left;
}
.settingsPanel .triPanel .section {
width: 100%;
}
.settingsPanel .togglePanelControl {
display: flex;
justify-content: space-between;
align-items: center;
border-bottom: 1px solid #13508d;
margin-top: 10px;
}
.settingsPanel .togglePanelControl button,
.settingsPanel .joystickSettings button,
.settingsPanel .triggerSettings button {
background-color: var(--primary-color);
color: #fff;
border: none;
padding: 5px 15px;
border-radius: 5px;
cursor: pointer;
transition: background-color 0.2s;
}
.settingsPanel .joystickPanel,
.settingsPanel .triggersPanel {
display: grid;
grid-template-columns: 1fr 1fr;
gap: 20px;
align-items: center;
}
.settingsPanel .leftPanel,
.settingsPanel .rightPanel {
display: flex;
flex-direction: column;
align-items: center;
gap: 10px;
}
.settingsPanel .headerButtonPair {
display: flex;
justify-content: space-between;
align-items: center;
width: 100%;
}
.settingsPanel .headerButtonPair .header {
text-align: left;
}
.settingsPanel .headerButtonPair .button {
text-align: right;
}
.settingsPanel .triggersPanel .headerButtonPair {
margin-top: 15px;
border-top: 1px solid #000000;
}
.settingsPanel .joystickPanel .canvasContainer {
position: relative;
width: 260px;
height: 260px;
}
.settingsPanel .triggersPanel .canvasContainer {
position: relative;
width: 300px;
height: 50px;
}
.settingsPanel .joystickPanel .canvasContainer canvas,
.settingsPanel .triggersPanel .canvasContainer canvas {
position: absolute;
top: 0;
left: 0;
width: 100%;
height: 100%;
pointer-events: none;
}
.joystickInput,
.triggerInput {
display: grid;
grid-template-columns: max-content 2fr 1fr;
gap: 5px;
align-items: center;
width: 100%;
}
.settingsSubPair {
display: contents;
}
.settingsSubPair label {
text-align: left;
/* font-size: 14px; */
}
.settingsSubPair .controlGroup {
display: flex;
align-items: left;
gap: 5px;
}
.dropdownGrid {
display: grid;
grid-template-columns: repeat(2, 1fr);
gap: 30px;
margin-top: 10px;
}
.dropdownSubPair {
display: grid;
grid-template-columns: 1fr 2fr;
align-items: center;
gap: 10px;
}
.dropdownSubPair label {
text-align: left;
white-space: nowrap;
}
.analogEnabled {
display: flex;
align-items: left;
gap: 10px;
margin-top: 10px;
margin-bottom: 15px;
}