basic os (WIP)

This commit is contained in:
Anthony Rabine 2023-07-12 17:10:51 +02:00
parent ad482ab026
commit b43e0b1ac0
32 changed files with 2559 additions and 978 deletions

4
.gitignore vendored
View file

@ -44,3 +44,7 @@ build-story-player-Desktop_Qt_GCC_64bit-Debug/
software/build/
software/.vscode/.cortex-debug.registers.state.json
story-player/build/
story-editor/tools/build-audio-System_Qt5_15_8-Debug/

View file

@ -23,6 +23,7 @@
"executable": "${workspaceRoot}/build/RaspberryPico/open-story-teller.elf",
"request": "launch",
"type": "cortex-debug",
"showDevDebugOutput": "raw",
"BMPGDBSerialPort": "/dev/ttyACM0",
"servertype": "bmp",
"interface": "swd",

View file

@ -9,6 +9,23 @@
"sdcard.h": "c",
"ff.h": "c",
"debug.h": "c",
"ffconf.h": "c"
"ffconf.h": "c",
"picture.h": "c",
"ost_tasker.h": "c",
"audio_pio.h": "c",
"audio_player.h": "c",
"compare": "c",
"pio.h": "c",
"*.tcc": "c",
"memory_resource": "c",
"memory": "c",
"ostream": "c",
"streambuf": "c",
"random": "c",
"algorithm": "c",
"gpio.h": "c",
"pico_i2s.h": "c",
"stdlib.h": "c",
"os.h": "c"
}
}

View file

@ -35,7 +35,9 @@ set(OST_SRCS
system/debug.c
system/picture.c
system/filesystem.c
system/ost_tasker.c
system/os.c
system/qor_armv6m.s
system/audio_player.c
system/ff/ff.c
system/ff/ffsystem.c
system/ff/ff_stubs.c
@ -132,7 +134,7 @@ elseif(${OST_BUNDLE} STREQUAL "RASPI_PICO")
# ------ Link
target_link_libraries(${PROJECT_NAME} PUBLIC "-Wl,--start-group"
gcc m c stdc++ raspberry-pico-w pico_stdlib hardware_spi hardware_dma "-Wl,--end-group")
gcc m c stdc++ raspberry-pico-w pico_stdlib hardware_spi hardware_dma hardware_pio "-Wl,--end-group")
set_target_properties(${PROJECT_NAME} PROPERTIES OUTPUT_NAME "${PROJECT_NAME}")
pico_add_extra_outputs(${PROJECT_NAME})

View file

@ -41,12 +41,17 @@ extern "C"
} ost_hal_gpio_t;
// ----------------------------------------------------------------------------
// SYSTEM HAL
// HIGH LEVEL API
// ----------------------------------------------------------------------------
void ost_system_initialize();
void system_putc(char ch);
void ost_system_delay_ms(uint32_t delay);
void ost_audio_play(const char *filename);
// ----------------------------------------------------------------------------
// GPIO HAL
// ----------------------------------------------------------------------------
int ost_hal_gpio_get(ost_hal_gpio_t gpio);
void ost_hal_gpio_set(ost_hal_gpio_t gpio, int value);
@ -93,6 +98,13 @@ extern "C"
uint8_t ost_display_transfer_byte(uint8_t dat);
void ost_display_transfer_multi(uint8_t *buff, uint32_t btr);
// ----------------------------------------------------------------------------
// AUDIO HAL
// ----------------------------------------------------------------------------
void ost_hal_audio_frame_end();
void ost_hal_audio_frame_start(const volatile void *, int dma_trans_number);
void ost_hal_audio_loop();
#ifdef __cplusplus
}
#endif

View file

@ -18,17 +18,19 @@ set(PICO_SRCS
${CMAKE_CURRENT_LIST_DIR}/pico_hal_wrapper.c
${CMAKE_CURRENT_LIST_DIR}/pico_lcd_spi.c
${CMAKE_CURRENT_LIST_DIR}/pico_sdcard_spi.c
${CMAKE_CURRENT_LIST_DIR}/pico_i2s.c
)
include_directories(../../src ../../hal ../../library)
include_directories(../../src ../../hal ../../library .)
add_library(
${PROJECT_NAME}
INTERFACE
# ${PICO_SRCS}
)
pico_generate_pio_header(${PROJECT_NAME} ${CMAKE_CURRENT_LIST_DIR}/pico_i2s.pio)
pico_generate_pio_header(${PROJECT_NAME} ${CMAKE_CURRENT_LIST_DIR}/i2s.pio)
target_link_libraries(${PROJECT_NAME} INTERFACE pico_stdlib)
target_include_directories(${PROJECT_NAME} INTERFACE ${CMAKE_CURRENT_LIST_DIR})

View file

@ -0,0 +1,253 @@
; i2s.pio
;
; Author: Daniel Collins
; Date: 2022-02-25
;
; Copyright (c) 2022 Daniel Collins
;
; This file is part of rp2040_i2s_example.
;
; rp2040_i2s_example is free software: you can redistribute it and/or modify it under
; the terms of the GNU General Public License, version 3 as published by the
; Free Software Foundation.
;
; rp2040_i2s_example is distributed in the hope that it will be useful, but WITHOUT ANY
; WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR
; A PARTICULAR PURPOSE. See the GNU General Public License for more details.
;
; You should have received a copy of the GNU General Public License along with
; rp2040_i2s_example. If not, see <https://www.gnu.org/licenses/>.
; An I2S bi-directional peripheral with master clock (SCK) output.
.program i2s_sck
; Transmit an I2S system / master clock.
;
; Usually this needs to be 256 * fs (the word clock rate).
; (e.g. for 48kHz audio, this should be precisely 12.288000 MHz.)
; Since all of these transmit at 1 I2S-clock per 2 sys-clock cycles,
; you need to set the clock divider at 2x the desired rate
; (for the 48kHz example, this should be 2 * 12,288,000 = 24.5760000 MHz).
;
; Use this as one state machine of the I2S PIO unit as a whole for perfect
; synchronization, e.g.:
; state machine 0 = clock (divide to 48000 * 256 * 2 = 24.576000 MHz for 48kHz stereo audio)
; state machine 1 = out (divide to 48000 * 64 * 2 = 6.144000 MHz for 48kHz stereo audio)
; state machine 2 = in (divide to 48000 * 256 * 2 = 24.576000 MHz for 48kHz stereo audio)
;
; One output pin is used for the clock output.
.wrap_target
set pins 1
set pins 0
.wrap
.program i2s_out_master
; I2S audio output block. Synchronous with clock and input.
; Must run at BCK * 2.
;
; This block also outputs the word clock (also called frame or LR clock) and
; the bit clock.
;
; Set register x to (bit depth - 2) (e.g. for 24 bit audio, set to 22).
; Note that if this is needed to be synchronous with the SCK module,
; it is not possible to run 24-bit frames with an SCK of 256x fs. You must either
; run SCK at 384x fs (if your codec permits this) or use 32-bit frames, which
; work fine with 24-bit codecs.
.side_set 2
public entry_point:
; /--- LRCLK
; |/-- BCLK
frameL: ; ||
set x, 30 side 0b00 ; start of Left frame
pull noblock side 0b01 ; One clock after edge change with no data
dataL:
out pins, 1 side 0b00
jmp x-- dataL side 0b01
frameR:
set x, 30 side 0b10
pull noblock side 0b11 ; One clock after edge change with no data
dataR:
out pins, 1 side 0b10
jmp x-- dataR side 0b11
.program i2s_bidi_slave
; I2S audio bidirectional (input/output) block, both in slave mode.
; Requires external BCK and LRCK, usually from the codec directly.
; This block provides both the output and input components together,
; so should not be used in combination with either of the other output or
; input units on the same I2S bus.
;
; Input pin order: DIN, BCK, LRCK
; Set JMP pin to LRCK.
;
; Clock synchronously with the system clock, or *at least* 4x the usual
; bit clock for a given fs (e.g. for 48kHz 24-bit, clock at at least
; (48000 * 24 * 2 (stereo)) * 4 = 9.216 MHz. Ideally 8x or more.
start_l:
wait 1 pin 1 ; DIN should be sampled on rising transition of BCK
in pins, 1 ; first "bit" of new frame is actually LSB of last frame, per I2S
pull noblock ;
push noblock ;
wait 0 pin 1 ; ignore first BCK transition after edge
public_entry_point:
wait 0 pin 2 ; wait for L frame to come around before we start
out pins 1 ; update DOUT on falling BCK edge
loop_l:
wait 1 pin 1 ; DIN should be sampled on rising transition of BCK
in pins, 1 ; read DIN
wait 0 pin 1 ; DOUT should be updated on falling transition of BCK
out pins 1 ; update DOUT
jmp pin start_r ; if LRCK has gone high, we're "done" with this word (1 bit left to read)
jmp loop_l ;
start_r:
wait 1 pin 1 ; wait for the last bit of the previous frame
in pins, 1 ; first "bit" of new frame is actually LSB of last frame, per I2S
pull noblock ; pull next output word from FIFO
push noblock ; push the completed word to the FIFO
wait 0 pin 1 ; wait for next clock cycle
out pins 1 ; update DOUT on falling edge
loop_r:
wait 1 pin 1 ;
in pins 1 ;
wait 0 pin 1 ;
out pins 1 ; update DOUT
jmp pin loop_r ; if LRCK is still high, we're still sampling this word
; implicit jmp to start_l: otherwise, start the loop over
; I2S Audio Input - Slave or Synchronous with Output Master
; Inputs must be sequential in order: DIN, BCK, LRCK
; Must run at same speed of SCK block, or at least 4x BCK.
;
; NOTE: Set JMP pin to LRCK pin.
; NOTE: The very first word read is potentially corrupt, since there is a
; chance to start in the middle of an L frame and only read part of it.
; Nevertheless, the frame order should be synchronized (first word is L,
; second is R, etc.)
.program i2s_in_slave
start_sample_l:
wait 1 pin 1 ; DIN should be sampled on rising transition of BCK
in pins, 1 ; first "bit" of new frame is actually LSB of last frame, per I2S
push noblock ; push however many bits we read into the FIFO
wait 0 pin 1 ; ignore first BCK transition after edge
public_entry_point:
wait 0 pin 2 ; wait for L frame to come around before we start
sample_l:
wait 1 pin 1 ; DIN should be sampled on rising transition of BCK
in pins, 1 ; read DIN
wait 0 pin 1 ; don't sample more than once per rising edge, wait for next clock
jmp pin start_sample_r ; if LRCK has gone high, we're "done" with this word (1 bit left to read)
jmp sample_l
start_sample_r:
wait 1 pin 1 ; wait for the last bit of the previous frame
in pins, 1 ; first "bit" of new frame is actually LSB of last frame, per I2S
push noblock ; push the completed word to the FIFO
wait 0 pin 1 ; wait for next clock cycle
sample_r:
wait 1 pin 1
in pins, 1
wait 0 pin 1
jmp pin sample_r ; if LRCK is still high, we're still sampling this word
; implicit jmp to start_sample_l: otherwise, start the loop over
% c-sdk {
// These constants are the I2S clock to pio clock ratio
const int i2s_sck_program_pio_mult = 2;
const int i2s_out_master_program_pio_mult = 2;
/*
* System ClocK (SCK) is only required by some I2S peripherals.
* This outputs it at 1 SCK per 2 PIO clocks, so scale the dividers correctly
* first.
* NOTE: Most peripherals require that this is *perfectly* aligned in ratio,
* if not phase, to the bit and word clocks of any master peripherals.
* It is up to you to ensure that the divider config is set up for a
* precise (not approximate) ratio between the BCK, LRCK, and SCK outputs.
*/
static void i2s_sck_program_init(PIO pio, uint8_t sm, uint8_t offset, uint8_t sck_pin) {
pio_gpio_init(pio, sck_pin);
pio_sm_config sm_config = i2s_sck_program_get_default_config(offset);
sm_config_set_set_pins(&sm_config, sck_pin, 1);
uint pin_mask = (1u << sck_pin);
pio_sm_set_pins_with_mask(pio, sm, 0, pin_mask); // zero output
pio_sm_set_pindirs_with_mask(pio, sm, pin_mask, pin_mask);
pio_sm_init(pio, sm, offset, &sm_config);
}
static inline void i2s_out_master_program_init(PIO pio, uint8_t sm, uint8_t offset, uint8_t bit_depth, uint8_t dout_pin, uint8_t clock_pin_base) {
pio_gpio_init(pio, dout_pin);
pio_gpio_init(pio, clock_pin_base);
pio_gpio_init(pio, clock_pin_base + 1);
pio_sm_config sm_config = i2s_out_master_program_get_default_config(offset);
sm_config_set_out_pins(&sm_config, dout_pin, 1);
sm_config_set_sideset_pins(&sm_config, clock_pin_base);
sm_config_set_out_shift(&sm_config, false, false, bit_depth);
sm_config_set_fifo_join(&sm_config, PIO_FIFO_JOIN_TX);
pio_sm_init(pio, sm, offset, &sm_config);
uint32_t pin_mask = (1u << dout_pin) | (3u << clock_pin_base);
pio_sm_set_pins_with_mask(pio, sm, 0, pin_mask); // zero output
pio_sm_set_pindirs_with_mask(pio, sm, pin_mask, pin_mask);
}
static inline void i2s_bidi_slave_program_init(PIO pio, uint8_t sm, uint8_t offset, uint8_t dout_pin, uint8_t in_pin_base) {
pio_gpio_init(pio, dout_pin);
pio_gpio_init(pio, in_pin_base);
pio_gpio_init(pio, in_pin_base + 1);
pio_gpio_init(pio, in_pin_base + 2);
pio_sm_config sm_config = i2s_bidi_slave_program_get_default_config(offset);
sm_config_set_out_pins(&sm_config, dout_pin, 1);
sm_config_set_in_pins(&sm_config, in_pin_base);
sm_config_set_jmp_pin(&sm_config, in_pin_base + 2);
sm_config_set_out_shift(&sm_config, false, false, 0);
sm_config_set_in_shift(&sm_config, false, false, 0);
pio_sm_init(pio, sm, offset, &sm_config);
// Setup output pins
uint32_t pin_mask = (1u << dout_pin);
pio_sm_set_pins_with_mask(pio, sm, 0, pin_mask); // zero output
pio_sm_set_pindirs_with_mask(pio, sm, pin_mask, pin_mask);
// Setup input pins
pin_mask = (7u << in_pin_base); // Three input pins
pio_sm_set_pindirs_with_mask(pio, sm, 0, pin_mask);
}
/*
* Designed to be used with output master module, requiring overlapping pins:
* din_pin_base + 0 = input pin
* din_pin_base + 1 = out_master clock_pin_base
* din_pin_base + 2 = out_master clock_pin_base + 1
*
* Intended to be run at SCK rate (4x BCK), so clock same as SCK module if using
* it, or 4x the BCK frequency (BCK is 64x fs, so 256x fs).
*/
static inline void i2s_in_slave_program_init(PIO pio, uint8_t sm, uint8_t offset, uint8_t din_pin_base) {
pio_gpio_init(pio, din_pin_base);
gpio_set_pulls(din_pin_base, false, false);
gpio_set_dir(din_pin_base, GPIO_IN);
pio_sm_config sm_config = i2s_in_slave_program_get_default_config(offset);
sm_config_set_in_pins(&sm_config, din_pin_base);
sm_config_set_in_shift(&sm_config, false, false, 0);
sm_config_set_fifo_join(&sm_config, PIO_FIFO_JOIN_RX);
sm_config_set_jmp_pin(&sm_config, din_pin_base + 2);
pio_sm_init(pio, sm, offset, &sm_config);
uint32_t pin_mask = (7u << din_pin_base); // Three input pins
pio_sm_set_pindirs_with_mask(pio, sm, 0, pin_mask);
}
%}

View file

@ -10,13 +10,22 @@
#include "pico/stdlib.h"
#include "hardware/uart.h"
#include "hardware/spi.h"
#include "hardware/dma.h"
#include "hardware/irq.h"
#include "hardware/pio.h"
#include "hardware/clocks.h"
#include "pico.h"
// Local
#include "pico_lcd_spi.h"
#include "pico_sdcard_spi.h"
#include "audio_player.h"
#include "pico_i2s.h"
static volatile uint32_t msTicks = 0;
static audio_ctx_t audio_ctx;
void __isr __time_critical_func(audio_i2s_dma_irq_handler)();
// ----------------------------------------------------------------------------
// SYSTEM HAL
@ -32,6 +41,10 @@ static volatile uint32_t msTicks = 0;
static struct repeating_timer sys_timer;
// static audio_i2s_config_t i2s_config = {28, 26, 0};
static __attribute__((aligned(8))) pio_i2s i2s;
void ost_system_delay_ms(uint32_t delay)
{
sleep_ms(delay);
@ -45,24 +58,44 @@ const uint8_t LCD_BL = 13;
const uint8_t ROTARY_A = 6;
const uint8_t ROTARY_B = 7;
const uint8_t ROTARY_BUTTON = 3;
const uint8_t SD_CARD_CS = 17;
const uint8_t SD_CARD_PRESENCE = 24;
extern void disk_timerproc();
#include "os.h"
static bool sys_timer_callback(struct repeating_timer *t)
{
msTicks++;
// disk_timerproc();
// qor_switch_context();
return true;
}
extern void init_spi(void);
void dma_init();
void gpio_callback(uint gpio, uint32_t events)
{
static bool one_time = true;
// if (one_time)
{
one_time = false;
// debouncer
debug_printf("G\n");
qor_switch_context();
}
}
void ost_system_initialize()
{
// stdio_init_all();
set_sys_clock_khz(125000, true);
////------------------- Init DEBUG LED
gpio_init(LED_PIN);
@ -107,18 +140,42 @@ void ost_system_initialize()
gpio_init(ROTARY_B);
gpio_set_dir(ROTARY_B, GPIO_IN);
gpio_init(ROTARY_BUTTON);
gpio_set_dir(ROTARY_BUTTON, GPIO_IN);
gpio_disable_pulls(ROTARY_BUTTON);
gpio_set_irq_enabled_with_callback(ROTARY_BUTTON, GPIO_IRQ_EDGE_FALL, true, &gpio_callback);
//------------------- Init SDCARD
gpio_init(SD_CARD_CS);
gpio_put(SD_CARD_CS, 1);
gpio_set_dir(SD_CARD_CS, GPIO_OUT);
// gpio_init(SD_CARD_CS);
// gpio_put(SD_CARD_CS, 1);
// gpio_set_dir(SD_CARD_CS, GPIO_OUT);
gpio_init(SD_CARD_PRESENCE);
gpio_set_dir(SD_CARD_PRESENCE, GPIO_IN);
// gpio_init(SD_CARD_PRESENCE);
// gpio_set_dir(SD_CARD_PRESENCE, GPIO_IN);
pico_sdcard_spi_init(10000);
// pico_sdcard_spi_init(1000000);
//------------------- Init Sound
static const audio_i2s_config_t config = {
.freq = 44100,
.bps = 32,
.data_pin = 28,
.clock_pin_base = 26};
// i2s_program_start_synched(pio0, audio_i2s_dma_irq_handler, &i2s, &config);
// pico_i2s_setup(&config);
init_spi();
audio_init(&audio_ctx);
//------------------- System timer (1ms)
add_repeating_timer_ms(1, sys_timer_callback, NULL, &sys_timer);
// add_repeating_timer_ms(1, sys_timer_callback, NULL, &sys_timer);
// ------------ Everything is initialized, print stuff here
debug_printf("System Clock: %lu\n", clock_get_hz(clk_sys));
}
void system_putc(char ch)
@ -234,3 +291,128 @@ void ost_display_transfer_multi(uint8_t *buff, uint32_t btr)
{
pico_lcd_spi_transfer(buff, btr);
}
// ----------------------------------------------------------------------------
// AUDIO HAL
// ----------------------------------------------------------------------------
// extern shared_state_t shared_state;
void hal_audio_test();
#include "pico/critical_section.h"
critical_section_t acrit;
void ost_audio_play(const char *filename)
{
#ifndef OST_AUDIO_TEST
audio_play(&audio_ctx, filename);
critical_section_init(&acrit);
// audio_i2s_set_enabled(true);
audio_process(&audio_ctx);
#else
hal_audio_test();
#endif
// audio_step = 1;
}
#ifndef OST_AUDIO_TEST
void ost_hal_audio_frame_end()
{
critical_section_enter_blocking(&acrit);
critical_section_exit(&acrit);
// uint dma_channel = shared_state.dma_channel;
// if (dma_irqn_get_channel_status(PICO_AUDIO_I2S_DMA_IRQ, dma_channel))
// {
// dma_irqn_acknowledge_channel(PICO_AUDIO_I2S_DMA_IRQ, dma_channel);
// }
}
void ost_hal_audio_frame_start(const volatile void *buff, int dma_trans_number)
{
// dma_channel_transfer_from_buffer_now(shared_state.dma_channel, buff, dma_trans_number);
// dma_channel_start(shared_state.dma_channel);
dma_hw->ints0 = 1u << i2s.dma_ch_out_data; // clear the IRQ
}
void __isr __time_critical_func(audio_i2s_dma_irq_handler)()
{
/*
uint dma_channel = shared_state.dma_channel;
if (dma_irqn_get_channel_status(PICO_AUDIO_I2S_DMA_IRQ, dma_channel))
{
dma_irqn_acknowledge_channel(PICO_AUDIO_I2S_DMA_IRQ, dma_channel);
}
audio_process(&audio_ctx);
*/
}
void ost_hal_audio_loop()
{
}
#else
#define SAMPLE_RATE (44100)
#define DMA_BUF_LEN (32)
#define I2S_NUM (0)
#define WAVE_FREQ_HZ (235.0f)
#define TWOPI (6.28318531f)
#define PHASE_INC (TWOPI * WAVE_FREQ_HZ / SAMPLE_RATE)
// Accumulated phase
static float p = 0.0f;
// Output buffer (2ch interleaved)
static uint32_t out_buf[DMA_BUF_LEN * 2];
uint32_t audio_count = 0;
#include <math.h>
// Fill the output buffer and write to I2S DMA
static void write_buffer()
{
// out_buf[0] = 0x70010001;
// out_buf[1] = 0xAAAA0001;
dma_channel_transfer_from_buffer_now(shared_state.dma_channel, out_buf, 2);
dma_channel_start(shared_state.dma_channel);
// You could put a taskYIELD() here to ensure other tasks always have a chance to run.
// taskYIELD();
}
void hal_audio_test()
{
audio_i2s_set_enabled(true);
audio_count = 0;
write_buffer();
}
// irq handler for DMA
void __isr __time_critical_func(audio_i2s_dma_irq_handler)()
{
uint dma_channel = shared_state.dma_channel;
if (dma_irqn_get_channel_status(PICO_AUDIO_I2S_DMA_IRQ, dma_channel))
{
dma_irqn_acknowledge_channel(PICO_AUDIO_I2S_DMA_IRQ, dma_channel);
}
write_buffer();
// busy_wait_ms(1);
// audio_process(&audio_ctx);
}
#endif

View file

@ -0,0 +1,122 @@
/*
* Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#include <stdio.h>
#include "pico_i2s.h"
#include "pico_i2s.pio.h"
#include "hardware/pio.h"
#include "hardware/gpio.h"
#include "hardware/dma.h"
#include "hardware/irq.h"
#include "hardware/clocks.h"
#include "debug.h"
void pico_i2s_set_frequency(const audio_i2s_config_t *config)
{
float bitClk = config->freq * config->bps * 2.0 /* channels */ * 2.0 /* edges per clock */;
// pio_sm_set_clkdiv(audio_pio, shared_state.pio_sm, (float)clock_get_hz(clk_sys) / bitClk);
}
#if 0
static bool audio_enabled;
void audio_i2s_set_enabled(bool enabled)
{
if (enabled != audio_enabled)
{
#ifndef NDEBUG
if (enabled)
{
puts("Enabling PIO I2S audio\n");
printf("(on core %d\n", get_core_num());
}
#endif
irq_set_enabled(DMA_IRQ_0 + PICO_AUDIO_I2S_DMA_IRQ, enabled);
if (enabled)
{
// audio_start_dma_transfer();
}
else
{
/*
// if there was a buffer in flight, it will not be freed by DMA IRQ, let's do it manually
if (shared_state.playing_buffer)
{
give_audio_buffer(audio_i2s_consumer, shared_state.playing_buffer);
shared_state.playing_buffer = NULL;
}
*/
}
pio_sm_set_enabled(audio_pio, shared_state.pio_sm, enabled);
audio_enabled = enabled;
}
}
#endif
//---------------------------------------------------------------------------------------------------------------------------
static void dma_double_buffer_init(pio_i2s *i2s, void (*dma_handler)(void))
{
i2s->dma_ch_out_ctrl = dma_claim_unused_channel(true);
i2s->dma_ch_out_data = dma_claim_unused_channel(true);
i2s->out_ctrl_blocks[0] = i2s->output_buffer;
i2s->out_ctrl_blocks[1] = &i2s->output_buffer[STEREO_BUFFER_SIZE];
dma_channel_config c = dma_channel_get_default_config(i2s->dma_ch_out_ctrl);
channel_config_set_read_increment(&c, true);
channel_config_set_write_increment(&c, false);
channel_config_set_ring(&c, false, 3);
channel_config_set_transfer_data_size(&c, DMA_SIZE_32);
dma_channel_configure(i2s->dma_ch_out_ctrl, &c, &dma_hw->ch[i2s->dma_ch_out_data].al3_read_addr_trig, i2s->out_ctrl_blocks, 1, false);
c = dma_channel_get_default_config(i2s->dma_ch_out_data);
channel_config_set_read_increment(&c, true);
channel_config_set_write_increment(&c, false);
channel_config_set_chain_to(&c, i2s->dma_ch_out_ctrl);
channel_config_set_dreq(&c, pio_get_dreq(i2s->pio, i2s->sm_dout, true));
dma_channel_configure(i2s->dma_ch_out_data,
&c,
&i2s->pio->txf[i2s->sm_dout],
NULL,
STEREO_BUFFER_SIZE,
false);
dma_channel_set_irq0_enabled(i2s->dma_ch_out_data, true);
irq_set_exclusive_handler(DMA_IRQ_0, dma_handler);
irq_set_enabled(DMA_IRQ_0, true);
dma_channel_start(i2s->dma_ch_out_ctrl);
}
static void i2s_sync_program_init(PIO pio, pio_i2s *i2s, audio_i2s_config_t *config)
{
uint offset = 0;
i2s->pio = pio;
i2s->sm_mask = 0;
i2s->sm_dout = pio_claim_unused_sm(pio, true);
i2s->sm_mask |= (1u << i2s->sm_dout);
offset = pio_add_program(pio0, &i2s_out_master_program);
// 4th argument is bit depth, 5th dout, 6th bclk pin base (lrclk is bclk pin + 1)
i2s_out_master_program_init(pio, i2s->sm_dout, offset, config->bps, config->data_pin, config->clock_pin_base);
// pio_sm_set_clkdiv(pio, i2s->sm_dout, 89); // Approximately 11KHz audio
}
void i2s_program_start_synched(PIO pio, void (*dma_handler)(void), pio_i2s *i2s, audio_i2s_config_t *config)
{
// i2s_sync_program_init(pio, i2s);
pico_i2s_set_frequency(config);
dma_double_buffer_init(i2s, dma_handler);
pio_enable_sm_mask_in_sync(i2s->pio, i2s->sm_mask);
}

View file

@ -0,0 +1,195 @@
/*
* Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#ifndef PICO_I2S_H
#define PICO_I2S_H
#include <stdbool.h>
#include "hardware/dma.h"
#include "hardware/irq.h"
#include "hardware/pio.h"
#ifdef __cplusplus
extern "C"
{
#endif
#if 0
/** \file audio_i2s.h
* \defgroup pico_audio_i2s pico_audio_i2s
* I2S audio output using the PIO
*
* This library uses the \ref hardware_pio system to implement a I2S audio interface
*
* \todo Must be more we need to say here.
* \todo certainly need an example
*
*/
#ifndef PICO_AUDIO_I2S_DMA_IRQ
#ifdef PICO_AUDIO_DMA_IRQ
#define PICO_AUDIO_I2S_DMA_IRQ PICO_AUDIO_DMA_IRQ
#else
#define PICO_AUDIO_I2S_DMA_IRQ 0
#endif
#endif
#ifndef PICO_AUDIO_I2S_PIO
#ifdef PICO_AUDIO_PIO
#define PICO_AUDIO_I2S_PIO PICO_AUDIO_PIO
#else
#define PICO_AUDIO_I2S_PIO 0
#endif
#endif
#if !(PICO_AUDIO_I2S_DMA_IRQ == 0 || PICO_AUDIO_I2S_DMA_IRQ == 1)
#error PICO_AUDIO_I2S_DMA_IRQ must be 0 or 1
#endif
#if !(PICO_AUDIO_I2S_PIO == 0 || PICO_AUDIO_I2S_PIO == 1)
#error PICO_AUDIO_I2S_PIO ust be 0 or 1
#endif
#ifndef PICO_AUDIO_I2S_MAX_CHANNELS
#ifdef PICO_AUDIO_MAX_CHANNELS
#define PICO_AUDIO_I2S_MAX_CHANNELS PICO_AUDIO_MAX_CHANNELS
#else
#define PICO_AUDIO_I2S_MAX_CHANNELS 2u
#endif
#endif
#ifndef PICO_AUDIO_I2S_BUFFERS_PER_CHANNEL
#ifdef PICO_AUDIO_BUFFERS_PER_CHANNEL
#define PICO_AUDIO_I2S_BUFFERS_PER_CHANNEL PICO_AUDIO_BUFFERS_PER_CHANNEL
#else
#define PICO_AUDIO_I2S_BUFFERS_PER_CHANNEL 3u
#endif
#endif
#ifndef PICO_AUDIO_I2S_BUFFER_SAMPLE_LENGTH
#ifdef PICO_AUDIO_BUFFER_SAMPLE_LENGTH
#define PICO_AUDIO_I2S_BUFFER_SAMPLE_LENGTH PICO_AUDIO_BUFFER_SAMPLE_LENGTH
#else
#define PICO_AUDIO_I2S_BUFFER_SAMPLE_LENGTH 576u
#endif
#endif
#ifndef PICO_AUDIO_I2S_SILENCE_BUFFER_SAMPLE_LENGTH
#ifdef PICO_AUDIO_I2S_SILENCE_BUFFER_SAMPLE_LENGTH
#define PICO_AUDIO_I2S_SILENCE_BUFFER_SAMPLE_LENGTH PICO_AUDIO_SILENCE_BUFFER_SAMPLE_LENGTH
#else
#define PICO_AUDIO_I2S_SILENCE_BUFFER_SAMPLE_LENGTH 256u
#endif
#endif
// Allow use of pico_audio driver without actually doing anything much
#ifndef PICO_AUDIO_I2S_NOOP
#ifdef PICO_AUDIO_NOOP
#define PICO_AUDIO_I2S_NOOP PICO_AUDIO_NOOP
#else
#define PICO_AUDIO_I2S_NOOP 0
#endif
#endif
#ifndef PICO_AUDIO_I2S_MONO_INPUT
#define PICO_AUDIO_I2S_MONO_INPUT 0
#endif
#ifndef PICO_AUDIO_I2S_MONO_OUTPUT
#define PICO_AUDIO_I2S_MONO_OUTPUT 0
#endif
#ifndef PICO_AUDIO_I2S_DATA_PIN
// #warning PICO_AUDIO_I2S_DATA_PIN should be defined when using AUDIO_I2S
#define PICO_AUDIO_I2S_DATA_PIN 28
#endif
#ifndef PICO_AUDIO_I2S_CLOCK_PIN_BASE
// #warning PICO_AUDIO_I2S_CLOCK_PIN_BASE should be defined when using AUDIO_I2S
#define PICO_AUDIO_I2S_CLOCK_PIN_BASE 26
#endif
/** \brief Base configuration structure used when setting up
* \ingroup pico_audio_i2s
*/
typedef struct
{
uint32_t freq;
uint32_t bps;
uint8_t data_pin;
uint8_t clock_pin_base;
} audio_i2s_config_t;
typedef struct
{
uint32_t freq;
uint8_t pio_sm;
uint8_t dma_channel;
} shared_state_t;
typedef struct audio_format
{
uint32_t sample_freq; ///< Sample frequency in Hz
uint16_t format; ///< Audio format \ref audio_formats
uint16_t channel_count; ///< Number of channels
} audio_format_t;
/** \brief Set up system to output I2S audio
* \ingroup pico_audio_i2s
*
* \param intended_audio_format \todo
* \param config The configuration to apply.
*/
void pico_i2s_setup(const audio_i2s_config_t *config);
/** \brief Set up system to output I2S audio
* \ingroup pico_audio_i2s
*
* \param enable true to enable I2S audio, false to disable.
*/
void audio_i2s_set_enabled(bool enabled);
void audio_start_dma_transfer(const int32_t *bytes, uint32_t count);
#endif
//----------------------------------------------------------------------------------
//----------------------------------------------------------------------------------
//----------------------------------------------------------------------------------
//----------------------------------------------------------------------------------
//----------------------------------------------------------------------------------
#define AUDIO_BUFFER_FRAMES 48
#define STEREO_BUFFER_SIZE AUDIO_BUFFER_FRAMES * 2
typedef struct
{
uint32_t freq;
uint32_t bps;
uint8_t data_pin;
uint8_t clock_pin_base;
} audio_i2s_config_t;
typedef struct pio_i2s
{
PIO pio;
uint8_t sm_mask;
uint8_t sm_dout;
uint dma_ch_out_ctrl;
uint dma_ch_out_data;
int32_t *out_ctrl_blocks[2];
int32_t output_buffer[STEREO_BUFFER_SIZE * 2];
} pio_i2s;
void i2s_program_start_synched(PIO pio, void (*dma_handler)(void), pio_i2s *i2s, audio_i2s_config_t *config);
#ifdef __cplusplus
}
#endif
#endif //_AUDIO_I2S_H

View file

@ -0,0 +1,82 @@
; i2s.pio
;
; Author: Daniel Collins
; Date: 2022-02-25
;
; Copyright (c) 2022 Daniel Collins
;
; This file is part of rp2040_i2s_example.
;
; rp2040_i2s_example is free software: you can redistribute it and/or modify it under
; the terms of the GNU General Public License, version 3 as published by the
; Free Software Foundation.
;
; rp2040_i2s_example is distributed in the hope that it will be useful, but WITHOUT ANY
; WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR
; A PARTICULAR PURPOSE. See the GNU General Public License for more details.
;
; You should have received a copy of the GNU General Public License along with
; rp2040_i2s_example. If not, see <https://www.gnu.org/licenses/>.
; An I2S bi-directional peripheral with master clock (SCK) output.
.program i2s_out_master
; I2S audio output block. Synchronous with clock and input.
; Must run at BCK * 2.
;
; This block also outputs the word clock (also called frame or LR clock) and
; the bit clock.
;
; Set register x to (bit depth - 2) (e.g. for 24 bit audio, set to 22).
; Note that if this is needed to be synchronous with the SCK module,
; it is not possible to run 24-bit frames with an SCK of 256x fs. You must either
; run SCK at 384x fs (if your codec permits this) or use 32-bit frames, which
; work fine with 24-bit codecs.
.side_set 2
public entry_point:
; /--- LRCLK
; |/-- BCLK
frameL: ; ||
set x, 30 side 0b00 ; start of Left frame
pull noblock side 0b01 ; One clock after edge change with no data
dataL:
out pins, 1 side 0b00
jmp x-- dataL side 0b01
frameR:
set x, 30 side 0b10
pull noblock side 0b11 ; One clock after edge change with no data
dataR:
out pins, 1 side 0b10
jmp x-- dataR side 0b11
% c-sdk {
// These constants are the I2S clock to pio clock ratio
const int i2s_sck_program_pio_mult = 2;
const int i2s_out_master_program_pio_mult = 2;
static inline void i2s_out_master_program_init(PIO pio, uint8_t sm, uint8_t offset, uint8_t bit_depth, uint8_t dout_pin, uint8_t clock_pin_base) {
pio_gpio_init(pio, dout_pin);
pio_gpio_init(pio, clock_pin_base);
pio_gpio_init(pio, clock_pin_base + 1);
pio_sm_config sm_config = i2s_out_master_program_get_default_config(offset);
sm_config_set_out_pins(&sm_config, dout_pin, 1);
sm_config_set_sideset_pins(&sm_config, clock_pin_base);
sm_config_set_out_shift(&sm_config, false, false, bit_depth);
sm_config_set_fifo_join(&sm_config, PIO_FIFO_JOIN_TX);
pio_sm_init(pio, sm, offset, &sm_config);
uint32_t pin_mask = (1u << dout_pin) | (3u << clock_pin_base);
pio_sm_set_pins_with_mask(pio, sm, 0, pin_mask); // zero output
pio_sm_set_pindirs_with_mask(pio, sm, pin_mask, pin_mask);
}
%}

View file

@ -13,7 +13,7 @@ static uint dma_tx;
void pico_lcd_spi_init()
{
spi_init(spi1, 1000 * 1000);
spi_init(spi1, 10000000);
// gpio_set_function(LCD_RX, GPIO_FUNC_SPI);
gpio_set_function(LCD_SCK, GPIO_FUNC_SPI);

View file

@ -0,0 +1,315 @@
// Copyright (c) 2023, Anthony Rabine
// Copyright (c) 2020, Elehobica (original version)
// Released under the BSD-2-Clause
// refer to https://opensource.org/licenses/BSD-2-Clause
#include "audio_player.h"
#include "debug.h"
#include <string.h>
#include "ost_hal.h"
#include "libutil.h"
// 1 sample = one 16-bit data for left, one 16-bit data for right (stereo example)
#define SIZE_OF_SAMPLES (1024)
// Audio Double Buffer for DMA transfer
int32_t audio_buf[2][SIZE_OF_SAMPLES];
// int16_t audio_buf16[2][SIZE_OF_SAMPLES];
// Audio Buffer for File Read
uint8_t raw_buf[SIZE_OF_SAMPLES * 2 * 2]; // x2 for 16-bit, L+R
int32_t DAC_ZERO_VALUE = 1; //
union U
{
uint32_t i;
uint16_t s[2];
} u;
static const uint32_t vol_table[101] = {
0, 4, 8, 12, 16, 20, 24, 27, 29, 31,
34, 37, 40, 44, 48, 52, 57, 61, 67, 73,
79, 86, 94, 102, 111, 120, 131, 142, 155, 168,
183, 199, 217, 236, 256, 279, 303, 330, 359, 390, // vol_table[34] = 256;
424, 462, 502, 546, 594, 646, 703, 764, 831, 904,
983, 1069, 1163, 1265, 1376, 1496, 1627, 1770, 1925, 2094,
2277, 2476, 2693, 2929, 3186, 3465, 3769, 4099, 4458, 4849,
5274, 5736, 6239, 6785, 7380, 8026, 8730, 9495, 10327, 11232,
12216, 13286, 14450, 15716, 17093, 18591, 20220, 21992, 23919, 26015,
28294, 30773, 33470, 36403, 39592, 43061, 46835, 50938, 55402, 60256,
65536};
static uint32_t swap16b(uint32_t in_val)
{
u.i = in_val;
return ((uint32_t)u.s[0] << 16) | ((uint32_t)u.s[1]);
}
void audio_init(audio_ctx_t *ctx)
{
memset(ctx->audio_info.filename, 0, sizeof(ctx->audio_info.filename));
memset(ctx->audio_info.artist, 0, sizeof(ctx->audio_info.artist));
memset(ctx->audio_info.title, 0, sizeof(ctx->audio_info.title));
memset(ctx->audio_info.album, 0, sizeof(ctx->audio_info.album));
memset(ctx->audio_info.number, 0, sizeof(ctx->audio_info.number));
ctx->idx_play = 0;
ctx->next_is_end = 0;
ctx->data_offset = 0;
ctx->playing = 0;
ctx->pausing = 0;
ctx->volume = 65;
ctx->count = 0;
for (int i = 0; i < SIZE_OF_SAMPLES; i++)
{
audio_buf[0][i] = DAC_ZERO_VALUE;
audio_buf[1][i] = DAC_ZERO_VALUE;
// audio_buf16[0][i] = DAC_ZERO_VALUE;
// audio_buf16[1][i] = DAC_ZERO_VALUE;
}
ctx->dma_trans_number = SIZE_OF_SAMPLES / 4;
}
static int list_chunk_is_info_type(audio_ctx_t *ctx)
{
FRESULT fr; /* FatFs return code */
UINT br;
char chunk_id[4];
fr = f_read(&ctx->fil, chunk_id, 4, &br);
// if (fr) printf("ERROR D: f_read %d\n\r", (int) fr);
return (memcmp(chunk_id, "info", 4) == 0 || memcmp(chunk_id, "INFO", 4) == 0);
}
static int load_next_file(audio_ctx_t *ctx, const char *fname_ptr)
{
int len;
FRESULT fr; /* FatFs return code */
UINT br;
char chunk_id[4];
uint32_t size;
uint32_t offset;
len = strlen(fname_ptr);
if (strncmp(&fname_ptr[len - 4], ".wav", 4) == 0 || strncmp(&fname_ptr[len - 4], ".WAV", 4) == 0)
{
memcpy(ctx->audio_info.filename, fname_ptr, 256);
ctx->audio_info.info_start = 0;
fr = f_open(&ctx->fil, ctx->audio_info.filename, FA_READ);
if (fr != FR_OK)
{
debug_printf("ERROR: f_open %d\n\r", (int)fr);
}
ctx->idx_play++;
FRESULT res = f_read(&ctx->fil, ctx->header, sizeof(ctx->header), &br);
// Find 'data' chunk
offset = 0;
while (1)
{
res = f_read(&ctx->fil, chunk_id, 4, &br);
res = f_read(&ctx->fil, &size, 4, &br);
offset += 8;
if (res == FR_OK)
{
if (memcmp(chunk_id, "data", 4) == 0 || memcmp(chunk_id, "DATA", 4) == 0)
{
break;
}
}
else
{
break;
}
}
ctx->audio_info.data_size = size;
// printf("Audio data size = %d\n\r", (int) audio_info.data_size);
ctx->audio_info.data_start = offset;
ctx->audio_info.data_offset = 0;
return 1;
}
return 0;
}
static int get_level(uint32_t val)
{
int i;
for (i = 0; i < 101; i++)
{
if (val * 2 < vol_table[i])
break;
}
return i;
}
int32_t swp(int16_t data)
{
int32_t r = (data & 0xFF) << 8;
r = r | ((data >> 8) & 0xFF);
return r;
}
// trans_number: DMA transfer count of 16bit->32bit transfer (NOT Byte count)
// but it equals Byte count of 16bit RAW data (actually equals (Byte count of 16bit RAW data)*2/2)
// because 16bit RAW data is expanded into 32bit data for 24bit DAC
static int get_audio_buf(audio_ctx_t *ctx, int32_t *buf_32b)
{
int i;
FRESULT fr; /* FatFs return code */
UINT br;
int _next_is_end = 0; /* 0: continue, 1: next is end */
uint32_t number;
uint32_t file_rest;
uint32_t trans_rest;
uint32_t trans;
uint32_t lvl_l = 0;
uint32_t lvl_r = 0;
number = 0; // number to transfer (en octets)
while (number < sizeof(raw_buf))
{
file_rest = ctx->audio_info.data_size - ctx->audio_info.data_offset;
trans_rest = sizeof(raw_buf) - number; // en octets, 2048 au début
trans = (file_rest >= trans_rest) ? trans_rest : file_rest;
// LEDR(1);
fr = f_read(&ctx->fil, &raw_buf[number], trans, &br);
// LEDR(0);
if (fr == FR_OK)
{
number += trans;
ctx->audio_info.data_offset += trans;
}
else
{
debug_printf("ERROR: f_read %d, data_offset = %d\n\r", (int)fr, (int)ctx->audio_info.data_offset);
f_close(&ctx->fil);
ctx->dma_trans_number = number / 4;
return 1;
}
if (ctx->audio_info.data_size <= ctx->audio_info.data_offset)
{
f_close(&ctx->fil);
_next_is_end = 1;
break;
}
}
static bool onetime = true;
// samples : total bytes devided by 2 (16 bits) and by two again (2 channels)
for (i = 0; i < number / 4; i++)
{
// buf_32b[i * 2 + 0] = (int32_t)swap16b((int32_t)buf_16b[i * 2 + 0] * vol_table[ctx->volume]) + DAC_ZERO_VALUE; // L
// buf_32b[i * 2 + 1] = (int32_t)swap16b((int32_t)buf_16b[i * 2 + 1] * vol_table[ctx->volume]) + DAC_ZERO_VALUE; // R
// Avec le AUDIO PICO de waveshare, on entend un truc
buf_32b[i * 2] = ((int32_t)((int16_t)leu16_get(&raw_buf[i * 4])));
buf_32b[i * 2 + 1] = ((int32_t)((int16_t)leu16_get(&raw_buf[i * 4 + 2])));
// buf_32b[i * 2] = 1;
// buf_32b[i * 2 + 1] = 4;
// lvl_l += ((int32_t)buf_16b[i * 2 + 0] * buf_16b[i * 2 + 0]) / 32768;
// lvl_r += ((int32_t)buf_16b[i * 2 + 1] * buf_16b[i * 2 + 1]) / 32768;
}
/*
if (onetime)
{
onetime = false;
for (int i = 0; i < 10; i++)
{
debug_printf("Sample left: %d\r\n", buf_32b[i * 2]);
debug_printf("Sample right: %d\r\n", buf_32b[i * 2 + 1]);
}
}
*/
// ctx->audio_info.lvl_l = get_level(lvl_l / (number / 4));
// ctx->audio_info.lvl_r = get_level(lvl_r / (number / 4));
ctx->dma_trans_number = (number / 4); // 32 bytes tranfers
return _next_is_end;
}
void audio_process(audio_ctx_t *ctx)
{
int nxt1 = (ctx->count & 0x1) ^ 0x1;
int nxt2 = 1 - nxt1;
// dma_flag_clear(DMA1, DMA_CH1, DMA_FLAG_FTF);
// dma_channel_disable(DMA1, DMA_CH1);
ost_hal_audio_frame_end();
if (ctx->next_is_end)
{
ctx->playing = 0;
ctx->pausing = 0;
}
// init_dma_i2s2(audio_buf[nxt1], dma_trans_number);
// dma_channel_enable(DMA1, DMA_CH1);
ost_hal_audio_frame_start(audio_buf[nxt1], ctx->dma_trans_number);
if (ctx->playing && !ctx->pausing)
{
ctx->next_is_end = get_audio_buf(ctx, audio_buf[nxt2]);
}
else
{
for (int i = 0; i < SIZE_OF_SAMPLES; i++)
{
audio_buf[nxt2][i] = DAC_ZERO_VALUE;
}
ctx->dma_trans_number = SIZE_OF_SAMPLES / 4;
}
ctx->count++;
// dma_interrupt_flag_clear(DMA1, DMA_CH1, DMA_INT_FLAG_G); /* not needed */
}
int audio_play(audio_ctx_t *ctx, const char *fname_ptr)
{
if (ctx->playing)
return 0;
memset(ctx->audio_info.filename, 0, sizeof(ctx->audio_info.filename));
if (!load_next_file(ctx, fname_ptr))
{
ctx->finished = 1;
return 0;
}
memset(ctx->audio_info.artist, 0, sizeof(ctx->audio_info.artist));
memset(ctx->audio_info.title, 0, sizeof(ctx->audio_info.title));
memset(ctx->audio_info.album, 0, sizeof(ctx->audio_info.album));
memset(ctx->audio_info.number, 0, sizeof(ctx->audio_info.number));
ctx->count = 0;
ctx->playing = 1; // After playing is set to 1, only IRQ routine can access file otherwise conflict occurs
ctx->pausing = 0;
ctx->next_is_end = 0;
ctx->finished = 0;
return 1;
}
void audio_pause(audio_ctx_t *ctx)
{
if (!ctx->playing)
return;
ctx->pausing = 1 - ctx->pausing;
}
void audio_stop(audio_ctx_t *ctx)
{
if (ctx->playing || ctx->pausing)
{
ctx->playing = 0;
ctx->pausing = 0;
f_close(&ctx->fil);
}
}

View file

@ -0,0 +1,50 @@
#pragma once
#include <stdint.h>
#include <stdbool.h>
#include <stdlib.h>
#include <ff.h>
#define FILENAME_MAX_SIZE 260
typedef struct
{
char filename[FILENAME_MAX_SIZE];
uint32_t info_start;
uint32_t info_size;
uint32_t info_offset;
uint32_t data_start;
uint32_t data_size;
uint32_t data_offset;
char artist[256];
char title[256];
char album[256];
char number[8];
uint32_t lvl_l;
uint32_t lvl_r;
} audio_info_type_t;
typedef struct
{
FIL fil;
audio_info_type_t audio_info;
int32_t dma_trans_number;
uint16_t idx_play;
int next_is_end;
int playing;
int pausing;
int finished; // means the player has finished to play whole files in the folder (by not stop)
uint32_t data_offset;
uint8_t header[36];
int count;
int volume; // 0 ~ 100;
} audio_ctx_t;
void audio_init(audio_ctx_t *ctx);
void audio_process(audio_ctx_t *ctx);
int audio_play(audio_ctx_t *ctx, const char *fname_ptr);
void audio_pause(audio_ctx_t *ctx);
void audio_stop(audio_ctx_t *ctx);

View file

@ -1,149 +1,644 @@
/*------------------------------------------------------------------------*/
/* STM32F100: MMCv3/SDv1/SDv2 (SPI mode) control module */
/*------------------------------------------------------------------------*/
/*
/ Copyright (C) 2018, ChaN, all right reserved.
/
/ * This software is a free software and there is NO WARRANTY.
/ * No restriction on use. You can use, modify and redistribute it for
/ personal, non-profit or commercial products UNDER YOUR RESPONSIBILITY.
/ * Redistributions of source code must retain the above copyright notice.
/
/-------------------------------------------------------------------------*/
#define PIN_SPI0_CS 17
#define PIN_SPI0_SCK 18
#define PIN_SPI0_MOSI 19
#define PIN_SPI0_MISO 16
/*--------------------------------------------------------------------------
Module Private Functions
---------------------------------------------------------------------------*/
// const uint8_t SD_CARD_CS = 17;
// #define SDCARD_SCK 18
// #define SDCARD_MOSI 19
// #define SDCARD_MISO 16
#include "ost_hal.h"
#include "debug.h"
#include "pico.h"
#include "pico/stdlib.h"
#include "hardware/clocks.h"
#include "hardware/spi.h"
#include "hardware/gpio.h"
#include "ff.h"
#include "diskio.h"
#include "sdcard.h"
#include "ffconf.h"
/*--------------------------------------------------------------------------
Module Private Functions
---------------------------------------------------------------------------*/
/* MMC/SD command */
#define CMD0 (0) /* GO_IDLE_STATE */
#define CMD1 (1) /* SEND_OP_COND (MMC) */
#define ACMD41 (0x80 + 41) /* SEND_OP_COND (SDC) */
#define CMD8 (8) /* SEND_IF_COND */
#define CMD9 (9) /* SEND_CSD */
#define CMD10 (10) /* SEND_CID */
#define CMD12 (12) /* STOP_TRANSMISSION */
#define ACMD13 (0x80 + 13) /* SD_STATUS (SDC) */
#define CMD16 (16) /* SET_BLOCKLEN */
#define CMD17 (17) /* READ_SINGLE_BLOCK */
#define CMD18 (18) /* READ_MULTIPLE_BLOCK */
#define CMD23 (23) /* SET_BLOCK_COUNT (MMC) */
#define ACMD23 (0x80 + 23) /* SET_WR_BLK_ERASE_COUNT (SDC) */
#define CMD24 (24) /* WRITE_BLOCK */
#define CMD25 (25) /* WRITE_MULTIPLE_BLOCK */
#define CMD32 (32) /* ERASE_ER_BLK_START */
#define CMD33 (33) /* ERASE_ER_BLK_END */
#define CMD38 (38) /* ERASE */
#define CMD55 (55) /* APP_CMD */
#define CMD58 (58) /* READ_OCR */
/* MMC card type flags (MMC_GET_TYPE) */
#define CT_MMC 0x01 /* MMC ver 3 */
#define CT_SD1 0x02 /* SD ver 1 */
#define CT_SD2 0x04 /* SD ver 2 */
#define CT_SDC (CT_SD1 | CT_SD2) /* SD */
#define CT_BLOCK 0x08 /* Block addressing */
#define CLK_SLOW (100 * KHZ)
#define CLK_FAST (40 * MHZ)
static volatile DSTATUS Stat = STA_NOINIT; /* Physical drive status */
static BYTE CardType; /* Card type flags */
static inline uint32_t _millis(void)
{
return to_ms_since_boot(get_absolute_time());
}
/*-----------------------------------------------------------------------*/
/* Initialize a Drive */
/* SPI controls (Platform dependent) */
/*-----------------------------------------------------------------------*/
static inline void cs_select(uint cs_pin)
{
asm volatile("nop \n nop \n nop"); // FIXME
gpio_put(cs_pin, 0);
asm volatile("nop \n nop \n nop"); // FIXME
}
static inline void cs_deselect(uint cs_pin)
{
asm volatile("nop \n nop \n nop"); // FIXME
gpio_put(cs_pin, 1);
asm volatile("nop \n nop \n nop"); // FIXME
}
static void FCLK_SLOW(void)
{
spi_set_baudrate(spi0, CLK_SLOW);
}
static void FCLK_FAST(void)
{
spi_set_baudrate(spi0, CLK_FAST);
}
static void CS_HIGH(void)
{
cs_deselect(PIN_SPI0_CS);
}
static void CS_LOW(void)
{
cs_select(PIN_SPI0_CS);
}
/* Initialize MMC interface */
void init_spi(void)
{
/* GPIO pin configuration */
/* pull up of MISO is MUST (10Kohm external pull up is recommended) */
/* Set drive strength and slew rate if needed to meet wire condition */
gpio_init(PIN_SPI0_SCK);
gpio_disable_pulls(PIN_SPI0_SCK);
// gpio_pull_up(PIN_SPI0_SCK);
// gpio_set_drive_strength(PIN_SPI0_SCK, PADS_BANK0_GPIO0_DRIVE_VALUE_4MA); // 2mA, 4mA (default), 8mA, 12mA
// gpio_set_slew_rate(PIN_SPI0_SCK, 0); // 0: SLOW (default), 1: FAST
gpio_set_function(PIN_SPI0_SCK, GPIO_FUNC_SPI);
gpio_init(PIN_SPI0_MISO);
gpio_disable_pulls(PIN_SPI0_MISO);
// gpio_pull_up(PIN_SPI0_MISO);
// gpio_set_schmitt(PIN_SPI0_MISO, 1); // 0: Off, 1: On (default)
gpio_set_function(PIN_SPI0_MISO, GPIO_FUNC_SPI);
gpio_init(PIN_SPI0_MOSI);
gpio_disable_pulls(PIN_SPI0_MOSI);
// gpio_pull_up(PIN_SPI0_MOSI);
// gpio_set_drive_strength(PIN_SPI0_MOSI, PADS_BANK0_GPIO0_DRIVE_VALUE_4MA); // 2mA, 4mA (default), 8mA, 12mA
// gpio_set_slew_rate(PIN_SPI0_MOSI, 0); // 0: SLOW (default), 1: FAST
gpio_set_function(PIN_SPI0_MOSI, GPIO_FUNC_SPI);
gpio_init(PIN_SPI0_CS);
gpio_disable_pulls(PIN_SPI0_CS);
// gpio_pull_up(PIN_SPI0_CS);
// gpio_set_drive_strength(PIN_SPI0_CS, PADS_BANK0_GPIO0_DRIVE_VALUE_4MA); // 2mA, 4mA (default), 8mA, 12mA
// gpio_set_slew_rate(PIN_SPI0_CS, 0); // 0: SLOW (default), 1: FAST
gpio_set_dir(PIN_SPI0_CS, GPIO_OUT);
/* chip _select invalid*/
CS_HIGH();
spi_init(spi0, CLK_SLOW);
/* SPI0 parameter config */
spi_set_format(spi0,
8, /* data_bits */
SPI_CPOL_0, /* cpol */
SPI_CPHA_0, /* cpha */
SPI_MSB_FIRST /* order */
);
}
/* Exchange a byte */
static BYTE xchg_spi(
BYTE dat /* Data to send */
)
{
uint8_t *buff = (uint8_t *)&dat;
spi_write_read_blocking(spi0, buff, buff, 1);
return (BYTE)*buff;
}
/* Receive multiple byte */
static void rcvr_spi_multi(
BYTE *buff, /* Pointer to data buffer */
UINT btr /* Number of bytes to receive (even number) */
)
{
uint8_t *b = (uint8_t *)buff;
spi_read_blocking(spi0, 0xff, b, btr);
}
/*-----------------------------------------------------------------------*/
/* Wait for card ready */
/*-----------------------------------------------------------------------*/
static int wait_ready( /* 1:Ready, 0:Timeout */
UINT wt /* Timeout [ms] */
)
{
BYTE d;
uint32_t t = _millis();
do
{
d = xchg_spi(0xFF);
/* This loop takes a time. Insert rot_rdq() here for multitask envilonment. */
} while (d != 0xFF && _millis() < t + wt); /* Wait for card goes ready or timeout */
return (d == 0xFF) ? 1 : 0;
}
/*-----------------------------------------------------------------------*/
/* Deselect card and release SPI */
/*-----------------------------------------------------------------------*/
static void deselect(void)
{
CS_HIGH(); /* Set CS# high */
xchg_spi(0xFF); /* Dummy clock (force DO hi-z for multiple slave SPI) */
}
/*-----------------------------------------------------------------------*/
/* Select card and wait for ready */
/*-----------------------------------------------------------------------*/
static int _select(void) /* 1:OK, 0:Timeout */
{
CS_LOW(); /* Set CS# low */
xchg_spi(0xFF); /* Dummy clock (force DO enabled) */
if (wait_ready(500))
return 1; /* Wait for card ready */
deselect();
return 0; /* Timeout */
}
/*-----------------------------------------------------------------------*/
/* Receive a data packet from the MMC */
/*-----------------------------------------------------------------------*/
static int rcvr_datablock( /* 1:OK, 0:Error */
BYTE *buff, /* Data buffer */
UINT btr /* Data block length (byte) */
)
{
BYTE token;
const uint32_t timeout = 200;
uint32_t t = _millis();
do
{ /* Wait for DataStart token in timeout of 200ms */
token = xchg_spi(0xFF);
/* This loop will take a time. Insert rot_rdq() here for multitask envilonment. */
} while (token == 0xFF && _millis() < t + timeout);
if (token != 0xFE)
return 0; /* Function fails if invalid DataStart token or timeout */
rcvr_spi_multi(buff, btr); /* Store trailing data to the buffer */
xchg_spi(0xFF);
xchg_spi(0xFF); /* Discard CRC */
return 1; /* Function succeeded */
}
/*-----------------------------------------------------------------------*/
/* Send a command packet to the MMC */
/*-----------------------------------------------------------------------*/
static BYTE send_cmd( /* Return value: R1 resp (bit7==1:Failed to send) */
BYTE cmd, /* Command index */
DWORD arg /* Argument */
)
{
BYTE n, res;
if (cmd & 0x80)
{ /* Send a CMD55 prior to ACMD<n> */
cmd &= 0x7F;
res = send_cmd(CMD55, 0);
if (res > 1)
return res;
}
/* Select the card and wait for ready except to stop multiple block read */
if (cmd != CMD12)
{
deselect();
if (!_select())
return 0xFF;
}
/* Send command packet */
xchg_spi(0x40 | cmd); /* Start + command index */
xchg_spi((BYTE)(arg >> 24)); /* Argument[31..24] */
xchg_spi((BYTE)(arg >> 16)); /* Argument[23..16] */
xchg_spi((BYTE)(arg >> 8)); /* Argument[15..8] */
xchg_spi((BYTE)arg); /* Argument[7..0] */
n = 0x01; /* Dummy CRC + Stop */
if (cmd == CMD0)
n = 0x95; /* Valid CRC for CMD0(0) */
if (cmd == CMD8)
n = 0x87; /* Valid CRC for CMD8(0x1AA) */
xchg_spi(n);
/* Receive command resp */
if (cmd == CMD12)
xchg_spi(0xFF); /* Diacard following one byte when CMD12 */
n = 10; /* Wait for response (10 bytes max) */
do
{
res = xchg_spi(0xFF);
} while ((res & 0x80) && --n);
return res; /* Return received response */
}
/*--------------------------------------------------------------------------
Public Functions
---------------------------------------------------------------------------*/
/*-----------------------------------------------------------------------*/
/* Initialize disk drive */
/*-----------------------------------------------------------------------*/
DSTATUS disk_initialize(
BYTE drv /* Physical drive number (0..) */
BYTE drv /* Physical drive number (0) */
)
{
BYTE n, cmd, ty, ocr[4];
const uint32_t timeout = 1000; /* Initialization timeout = 1 sec */
uint32_t t;
if (drv)
return STA_NOINIT;
return STA_NOINIT; /* Supports only drive 0 */
init_spi(); /* Initialize SPI */
sleep_ms(10);
if (sdcard_init() != SD_RESPONSE_NO_ERROR)
return STA_NOINIT;
if (Stat & STA_NODISK)
return Stat; /* Is card existing in the soket? */
return 0;
FCLK_SLOW();
for (n = 10; n; n--)
xchg_spi(0xFF); /* Send 80 dummy clocks */
ty = 0;
if (send_cmd(CMD0, 0) == 1)
{ /* Put the card SPI/Idle state */
t = _millis();
if (send_cmd(CMD8, 0x1AA) == 1)
{ /* SDv2? */
for (n = 0; n < 4; n++)
ocr[n] = xchg_spi(0xFF); /* Get 32 bit return value of R7 resp */
if (ocr[2] == 0x01 && ocr[3] == 0xAA)
{ /* Is the card supports vcc of 2.7-3.6V? */
while (_millis() < t + timeout && send_cmd(ACMD41, 1UL << 30))
; /* Wait for end of initialization with ACMD41(HCS) */
if (_millis() < t + timeout && send_cmd(CMD58, 0) == 0)
{ /* Check CCS bit in the OCR */
for (n = 0; n < 4; n++)
ocr[n] = xchg_spi(0xFF);
ty = (ocr[0] & 0x40) ? CT_SD2 | CT_BLOCK : CT_SD2; /* Card id SDv2 */
}
}
}
else
{ /* Not SDv2 card */
if (send_cmd(ACMD41, 0) <= 1)
{ /* SDv1 or MMC? */
ty = CT_SD1;
cmd = ACMD41; /* SDv1 (ACMD41(0)) */
}
else
{
ty = CT_MMC;
cmd = CMD1; /* MMCv3 (CMD1(0)) */
}
while (_millis() < t + timeout && send_cmd(cmd, 0))
; /* Wait for end of initialization */
if (_millis() >= t + timeout || send_cmd(CMD16, 512) != 0) /* Set block length: 512 */
ty = 0;
}
}
CardType = ty; /* Card type */
deselect();
if (ty)
{ /* OK */
FCLK_FAST(); /* Set fast clock */
Stat &= ~STA_NOINIT; /* Clear STA_NOINIT flag */
}
else
{ /* Failed */
Stat = STA_NOINIT;
}
return Stat;
}
/*-----------------------------------------------------------------------*/
/* Return Drive Status */
/* Get disk status */
/*-----------------------------------------------------------------------*/
DSTATUS disk_status(
BYTE drv /* Physical drive number (0..) */
BYTE drv /* Physical drive number (0) */
)
{
if (drv)
return STA_NOINIT;
return STA_NOINIT; /* Supports only drive 0 */
return Stat; /* Return disk status */
}
/*-----------------------------------------------------------------------*/
/* Read sector(s) */
/*-----------------------------------------------------------------------*/
DRESULT disk_read(
BYTE drv, /* Physical drive number (0) */
BYTE *buff, /* Pointer to the data buffer to store read data */
LBA_t sector, /* Start sector number (LBA) */
UINT count /* Number of sectors to read (1..128) */
)
{
if (drv || !count)
return RES_PARERR; /* Check parameter */
if (Stat & STA_NOINIT)
return RES_NOTRDY; /* Check if drive is ready */
if (!(CardType & CT_BLOCK))
sector *= 512; /* LBA ot BA conversion (byte addressing cards) */
if (count == 1)
{ /* Single sector read */
if ((send_cmd(CMD17, sector) == 0) /* READ_SINGLE_BLOCK */
&& rcvr_datablock(buff, 512))
{
count = 0;
}
}
else
{ /* Multiple sector read */
if (send_cmd(CMD18, sector) == 0)
{ /* READ_MULTIPLE_BLOCK */
do
{
if (!rcvr_datablock(buff, 512))
break;
buff += 512;
} while (--count);
send_cmd(CMD12, 0); /* STOP_TRANSMISSION */
}
}
deselect();
return count ? RES_ERROR : RES_OK; /* Return result */
}
#if !FF_FS_READONLY && !FF_FS_NORTC
/* get the current time */
DWORD get_fattime(void)
{
return 0;
}
#endif
/*-----------------------------------------------------------------------*/
/* Read Sector(s) */
/*-----------------------------------------------------------------------*/
DRESULT disk_read(
BYTE pdrv, /* Physical drive nmuber to identify the drive */
BYTE *buff, /* Data buffer to store read data */
LBA_t sector, /* Start sector in LBA */
UINT count /* Number of sectors to read */
#if FF_FS_READONLY == 0
/* Transmit multiple byte */
static void xmit_spi_multi(
const BYTE *buff, /* Pointer to data buffer */
UINT btx /* Number of bytes to transmit (even number) */
)
{
DRESULT res;
if (pdrv || !count)
return RES_PARERR;
if (count == 1)
res = (DRESULT)sdcard_sector_read(sector, buff);
else
res = (DRESULT)sdcard_sectors_read(sector, buff, count);
if (res == 0x00)
return RES_OK;
return RES_ERROR;
const uint8_t *b = (const uint8_t *)buff;
spi_write_blocking(spi0, b, btx);
}
/*-----------------------------------------------------------------------*/
/* Write Sector(s) */
/* Transmit a data packet to the MMC */
/*-----------------------------------------------------------------------*/
#if _READONLY == 0
static int xmit_datablock( /* 1:OK, 0:Error */
const BYTE *buff, /* 512 byte data block to be transmitted */
BYTE token /* Data/Stop token */
)
{
BYTE resp;
if (!wait_ready(500))
return 0;
xchg_spi(token); /* Xmit data token */
if (token != 0xFD)
{ /* Is data token */
xmit_spi_multi(buff, 512); /* Xmit the data block to the MMC */
xchg_spi(0xFF); /* CRC (Dummy) */
xchg_spi(0xFF);
resp = xchg_spi(0xFF); /* Reveive data response */
if ((resp & 0x1F) != 0x05) /* If not accepted, return with error */
return 0;
}
return 1;
}
/*-----------------------------------------------------------------------*/
/* Write sector(s) */
/*-----------------------------------------------------------------------*/
DRESULT disk_write(
BYTE pdrv, /* Physical drive nmuber to identify the drive */
const BYTE *buff, /* Data to be written */
LBA_t sector, /* Start sector in LBA */
UINT count /* Number of sectors to write */
BYTE drv, /* Physical drive number (0) */
const BYTE *buff, /* Ponter to the data to write */
LBA_t sector, /* Start sector number (LBA) */
UINT count /* Number of sectors to write (1..128) */
)
{
DRESULT res;
if (pdrv || !count)
return RES_PARERR;
if (drv || !count)
return RES_PARERR; /* Check parameter */
if (Stat & STA_NOINIT)
return RES_NOTRDY; /* Check drive status */
if (Stat & STA_PROTECT)
return RES_WRPRT; /* Check write protect */
if (!(CardType & CT_BLOCK))
sector *= 512; /* LBA ==> BA conversion (byte addressing cards) */
if (!_select())
return RES_NOTRDY;
if (count == 1)
res = (DRESULT)sdcard_sector_write(sector, buff);
else
res = (DRESULT)sdcard_sectors_write(sector, buff, count);
if (res == 0)
return RES_OK;
return RES_ERROR;
{ /* Single sector write */
if ((send_cmd(CMD24, sector) == 0) /* WRITE_BLOCK */
&& xmit_datablock(buff, 0xFE))
{
count = 0;
}
#endif /* _READONLY */
}
else
{ /* Multiple sector write */
if (CardType & CT_SDC)
send_cmd(ACMD23, count); /* Predefine number of sectors */
if (send_cmd(CMD25, sector) == 0)
{ /* WRITE_MULTIPLE_BLOCK */
do
{
if (!xmit_datablock(buff, 0xFC))
break;
buff += 512;
} while (--count);
if (!xmit_datablock(0, 0xFD))
count = 1; /* STOP_TRAN token */
}
}
deselect();
return count ? RES_ERROR : RES_OK; /* Return result */
}
#endif
/*-----------------------------------------------------------------------*/
/* Miscellaneous Functions */
/* Miscellaneous drive controls other than data read/write */
/*-----------------------------------------------------------------------*/
DRESULT disk_ioctl(
BYTE drv, /* Physical drive number (0..) */
BYTE ctrl, /* Control code */
void *buff /* Buffer to send/receive control data */
BYTE drv, /* Physical drive number (0) */
BYTE cmd, /* Control command code */
void *buff /* Pointer to the conrtol data */
)
{
SD_CardInfo cardinfo;
DRESULT res;
if (drv)
return RES_PARERR;
BYTE n, csd[16];
DWORD *dp, st, ed, csize;
if (drv)
return RES_PARERR; /* Check parameter */
if (Stat & STA_NOINIT)
return RES_NOTRDY; /* Check if drive is ready */
switch (ctrl)
{
case CTRL_SYNC:
// res = ( SD_WaitReady() == SD_RESPONSE_NO_ERROR ) ? RES_OK : RES_ERROR
res = RES_OK;
break;
case GET_BLOCK_SIZE:
*(WORD *)buff = FF_MAX_SS;
res = RES_OK;
break;
case GET_SECTOR_COUNT:
if (sdcard_get_card_info(&cardinfo) != SD_RESPONSE_NO_ERROR)
res = RES_ERROR;
else
switch (cmd)
{
*(DWORD *)buff = cardinfo.CardCapacity;
res = (*(DWORD *)buff > 0) ? RES_OK : RES_PARERR;
case CTRL_SYNC: /* Wait for end of internal write process of the drive */
if (_select())
res = RES_OK;
break;
case GET_SECTOR_COUNT: /* Get drive capacity in unit of sector (DWORD) */
if ((send_cmd(CMD9, 0) == 0) && rcvr_datablock(csd, 16))
{
if ((csd[0] >> 6) == 1)
{ /* SDC ver 2.00 */
csize = csd[9] + ((WORD)csd[8] << 8) + ((DWORD)(csd[7] & 63) << 16) + 1;
*(DWORD *)buff = csize << 10;
}
else
{ /* SDC ver 1.XX or MMC ver 3 */
n = (csd[5] & 15) + ((csd[10] & 128) >> 7) + ((csd[9] & 3) << 1) + 2;
csize = (csd[8] >> 6) + ((WORD)csd[7] << 2) + ((WORD)(csd[6] & 3) << 10) + 1;
*(DWORD *)buff = csize << (n - 9);
}
res = RES_OK;
}
break;
case CTRL_TRIM:
res = (sdcard_sectors_erase(((DWORD *)buff)[0], ((DWORD *)buff)[1]) == SD_RESPONSE_NO_ERROR)
? RES_OK
: RES_PARERR;
case GET_BLOCK_SIZE: /* Get erase block size in unit of sector (DWORD) */
if (CardType & CT_SD2)
{ /* SDC ver 2.00 */
if (send_cmd(ACMD13, 0) == 0)
{ /* Read SD status */
xchg_spi(0xFF);
if (rcvr_datablock(csd, 16))
{ /* Read partial block */
for (n = 64 - 16; n; n--)
xchg_spi(0xFF); /* Purge trailing data */
*(DWORD *)buff = 16UL << (csd[10] >> 4);
res = RES_OK;
}
}
}
else
{ /* SDC ver 1.XX or MMC */
if ((send_cmd(CMD9, 0) == 0) && rcvr_datablock(csd, 16))
{ /* Read CSD */
if (CardType & CT_SD1)
{ /* SDC ver 1.XX */
*(DWORD *)buff = (((csd[10] & 63) << 1) + ((WORD)(csd[11] & 128) >> 7) + 1) << ((csd[13] >> 6) - 1);
}
else
{ /* MMC */
*(DWORD *)buff = ((WORD)((csd[10] & 124) >> 2) + 1) * (((csd[11] & 3) << 3) + ((csd[11] & 224) >> 5) + 1);
}
res = RES_OK;
}
}
break;
case CTRL_TRIM: /* Erase a block of sectors (used when _USE_ERASE == 1) */
if (!(CardType & CT_SDC))
break; /* Check if the card is SDC */
if (disk_ioctl(drv, MMC_GET_CSD, csd))
break; /* Get CSD */
if (!(csd[0] >> 6) && !(csd[10] & 0x40))
break; /* Check if sector erase can be applied to the card */
dp = buff;
st = dp[0];
ed = dp[1]; /* Load sector block */
if (!(CardType & CT_BLOCK))
{
st *= 512;
ed *= 512;
}
if (send_cmd(CMD32, st) == 0 && send_cmd(CMD33, ed) == 0 && send_cmd(CMD38, 0) == 0 && wait_ready(30000))
{ /* Erase sector block */
res = RES_OK; /* FatFs does not check result of this command */
}
break;
default:
res = RES_PARERR;
break;
}
deselect();
return res;
}

View file

@ -1,346 +0,0 @@
/*
This reads a wave file from an SD card and plays it using the I2S interface to
a MAX08357 I2S Amp Breakout board.
Circuit:
* Arduino/Genuino Zero, MKRZero or MKR1000 board
* SD breakout or shield connected
* MAX08357:
* GND connected GND
* VIN connected 5V
* LRC connected to pin 0 (Zero) or pin 3 (MKR1000, MKRZero)
* BCLK connected to pin 1 (Zero) or pin 2 (MKR1000, MKRZero)
* DIN connected to pin 9 (Zero) or pin A6 (MKR1000, MKRZero)
created 15 November 2016
by Sandeep Mistry
*/
#include <SdFat.h>
#include <ArduinoSound.h>
// filename of wave file to play
const char filename[] = "castemere_mono.wav";
// SD_FAT_TYPE = 0 for SdFat/File as defined in SdFatConfig.h,
// 1 for FAT16/FAT32, 2 for exFAT, 3 for FAT16/FAT32 and exFAT.
#define SD_FAT_TYPE 2
//
// Set DISABLE_CHIP_SELECT to disable a second SPI device.
// For example, with the Ethernet shield, set DISABLE_CHIP_SELECT
// to 10 to disable the Ethernet controller.
const int8_t DISABLE_CHIP_SELECT = -1;
//
// Test with reduced SPI speed for breadboards. SD_SCK_MHZ(4) will select
// the highest speed supported by the board that is not over 4 MHz.
// Change SPI_SPEED to SD_SCK_MHZ(50) for best performance.
#define SPI_SPEED SD_SCK_MHZ(24)
//------------------------------------------------------------------------------
SdFat sd;
// SD card chip select
int chipSelect = 28;
// variable representing the Wave File
SDWaveFile waveFile(sd, filename);
void setup() {
// Open serial communications and wait for port to open:
Serial.begin(9600);
while (!Serial) {
; // wait for serial port to connect. Needed for native USB port only
}
if (!sd.begin(chipSelect, SPI_SPEED)) {
if (sd.card()->errorCode()) {
Serial.println("SD initialization failed.");
// cout << F(
// "\nSD initialization failed.\n"
// "Do not reformat the card!\n"
// "Is the card correctly inserted?\n"
// "Is chipSelect set to the correct value?\n"
// "Does another SPI device need to be disabled?\n"
// "Is there a wiring/soldering problem?\n");
// cout << F("\nerrorCode: ") << hex << showbase;
// cout << int(sd.card()->errorCode());
// cout << F(", errorData: ") << int(sd.card()->errorData());
// cout << dec << noshowbase << endl;
return;
}
Serial.println("Card successfully initialized.");
if (sd.vol()->fatType() == 0) {
Serial.println("Can't find a valid FAT16/FAT32 partition.");
return;
}
Serial.println("Can't determine error type.");
return;
}
// check if the WaveFile is valid
if (!waveFile) {
Serial.println("wave file is invalid!");
while (1); // do nothing
}
// print out some info. about the wave file
Serial.print("Bits per sample = ");
Serial.println(waveFile.bitsPerSample());
long channels = waveFile.channels();
Serial.print("Channels = ");
Serial.println(channels);
long sampleRate = waveFile.sampleRate();
Serial.print("Sample rate = ");
Serial.print(sampleRate);
Serial.println(" Hz");
long duration = waveFile.duration();
Serial.print("Duration = ");
Serial.print(duration);
Serial.println(" seconds");
// adjust the playback volume
AudioOutI2S.volume(5);
// check if the I2S output can play the wave file
if (!AudioOutI2S.canPlay(waveFile)) {
Serial.println("unable to play wave file using I2S!");
while (1); // do nothing
}
// start playback
Serial.println("starting playback");
AudioOutI2S.play(waveFile);
}
void loop() {
// check if playback is still going on
if (!AudioOutI2S.isPlaying()) {
// playback has stopped
Serial.println("playback stopped");
while (1); // do nothing
}
}
/**
*
// ============================================ SD EXAMPLE
// Quick hardware test for SPI card access.
//
#include <SPI.h>
#include "SdFat.h"
#include "sdios.h"
// SD_FAT_TYPE = 0 for SdFat/File as defined in SdFatConfig.h,
// 1 for FAT16/FAT32, 2 for exFAT, 3 for FAT16/FAT32 and exFAT.
#define SD_FAT_TYPE 2
//
// Set DISABLE_CHIP_SELECT to disable a second SPI device.
// For example, with the Ethernet shield, set DISABLE_CHIP_SELECT
// to 10 to disable the Ethernet controller.
const int8_t DISABLE_CHIP_SELECT = -1;
//
// Test with reduced SPI speed for breadboards. SD_SCK_MHZ(4) will select
// the highest speed supported by the board that is not over 4 MHz.
// Change SPI_SPEED to SD_SCK_MHZ(50) for best performance.
#define SPI_SPEED SD_SCK_MHZ(24)
//------------------------------------------------------------------------------
#if SD_FAT_TYPE == 0
SdFat sd;
File file;
#elif SD_FAT_TYPE == 1
SdFat32 sd;
File32 file;
#elif SD_FAT_TYPE == 2
SdExFat sd;
ExFile file;
#elif SD_FAT_TYPE == 3
SdFs sd;
FsFile file;
#else // SD_FAT_TYPE
#error Invalid SD_FAT_TYPE
#endif // SD_FAT_TYPE
// Serial streams
ArduinoOutStream cout(Serial);
// input buffer for line
char cinBuf[40];
ArduinoInStream cin(Serial, cinBuf, sizeof(cinBuf));
// SD card chip select
int chipSelect = 28;
void cardOrSpeed() {
cout << F("Try another SD card or reduce the SPI bus speed.\n");
cout << F("Edit SPI_SPEED in this program to change it.\n");
}
void reformatMsg() {
cout << F("Try reformatting the card. For best results use\n");
cout << F("the SdFormatter program in SdFat/examples or download\n");
cout << F("and use SDFormatter from www.sdcard.org/downloads.\n");
}
void setup() {
Serial.begin(115200);
// Wait for USB Serial
while (!Serial) {
SysCall::yield();
}
cout << F("\nSPI pins:\n");
cout << F("MISO: ") << int(MISO) << endl;
cout << F("MOSI: ") << int(MOSI) << endl;
cout << F("SCK: ") << int(SCK) << endl;
cout << F("SS: ") << int(SS) << endl;
#ifdef SDCARD_SS_PIN
cout << F("SDCARD_SS_PIN: ") << int(SDCARD_SS_PIN) << endl;
#endif // SDCARD_SS_PIN
if (DISABLE_CHIP_SELECT < 0) {
cout << F(
"\nBe sure to edit DISABLE_CHIP_SELECT if you have\n"
"a second SPI device. For example, with the Ethernet\n"
"shield, DISABLE_CHIP_SELECT should be set to 10\n"
"to disable the Ethernet controller.\n");
}
cout << F(
"\nSD chip select is the key hardware option.\n"
"Common values are:\n"
"Arduino Ethernet shield, pin 4\n"
"Sparkfun SD shield, pin 8\n"
"Adafruit SD shields and modules, pin 10\n");
}
bool firstTry = true;
void loop() {
// Read any existing Serial data.
do {
delay(10);
} while (Serial.available() && Serial.read() >= 0);
if (!firstTry) {
cout << F("\nRestarting\n");
}
firstTry = false;
// cout << F("\nEnter the chip select pin number: ");
// while (!Serial.available()) {
// SysCall::yield();
// }
// cin.readline();
// if (cin >> chipSelect) {
// cout << chipSelect << endl;
// } else {
// cout << F("\nInvalid pin number\n");
// return;
// }
if (DISABLE_CHIP_SELECT < 0) {
cout << F(
"\nAssuming the SD is the only SPI device.\n"
"Edit DISABLE_CHIP_SELECT to disable another device.\n");
} else {
cout << F("\nDisabling SPI device on pin ");
cout << int(DISABLE_CHIP_SELECT) << endl;
pinMode(DISABLE_CHIP_SELECT, OUTPUT);
digitalWrite(DISABLE_CHIP_SELECT, HIGH);
}
if (!sd.begin(chipSelect, SPI_SPEED)) {
if (sd.card()->errorCode()) {
cout << F(
"\nSD initialization failed.\n"
"Do not reformat the card!\n"
"Is the card correctly inserted?\n"
"Is chipSelect set to the correct value?\n"
"Does another SPI device need to be disabled?\n"
"Is there a wiring/soldering problem?\n");
cout << F("\nerrorCode: ") << hex << showbase;
cout << int(sd.card()->errorCode());
cout << F(", errorData: ") << int(sd.card()->errorData());
cout << dec << noshowbase << endl;
return;
}
cout << F("\nCard successfully initialized.\n");
if (sd.vol()->fatType() == 0) {
cout << F("Can't find a valid FAT16/FAT32 partition.\n");
reformatMsg();
return;
}
cout << F("Can't determine error type\n");
return;
}
cout << F("\nCard successfully initialized.\n");
cout << endl;
uint32_t size = sd.card()->sectorCount();
if (size == 0) {
cout << F("Can't determine the card size.\n");
cardOrSpeed();
return;
}
uint32_t sizeMB = 0.000512 * size + 0.5;
cout << F("Card size: ") << sizeMB;
cout << F(" MB (MB = 1,000,000 bytes)\n");
cout << endl;
cout << F("Volume is FAT") << int(sd.vol()->fatType());
cout << F(", Cluster size (bytes): ") << sd.vol()->bytesPerCluster();
cout << endl << endl;
cout << F("Files found (date time size name):\n");
sd.ls(LS_R | LS_DATE | LS_SIZE);
if ((sizeMB > 1100 && sd.vol()->sectorsPerCluster() < 64)
|| (sizeMB < 2200 && sd.vol()->fatType() == 32)) {
cout << F("\nThis card should be reformatted for best performance.\n");
cout << F("Use a cluster size of 32 KB for cards larger than 1 GB.\n");
cout << F("Only cards larger than 2 GB should be formatted FAT32.\n");
reformatMsg();
return;
}
// Read any extra Serial data.
do {
delay(10);
} while (Serial.available() && Serial.read() >= 0);
cout << F("\nSuccess! Type any character to restart.\n");
while (!Serial.available()) {
SysCall::yield();
}
}
*/
/*
* EXEMPLE 1
#include "Arduino.h"
// the setup function runs once when you press reset or power the board
void setup() {
// initialize digital pin LED_BUILTIN as an output.
pinMode(0, OUTPUT);
SerialUSB.begin(9600);
}
// the loop function runs over and over again forever
void loop()
{
digitalWrite(0, HIGH); // turn the LED on (HIGH is the voltage level)
delay(1000); // wait for a second
digitalWrite(0, LOW); // turn the LED off by making the voltage LOW
delay(1000); // wait for a second
SerialUSB.println("Hello, Arduino!");
}
*/

View file

@ -3,7 +3,7 @@
#include "debug.h"
#include "filesystem.h"
#include "picture.h"
#include "ost_tasker.h"
#include "os.h"
#include "rotary-button.h"
#define RUN_TESTS 1
@ -14,7 +14,7 @@ int main(void)
// Low level initialization, mainly platform stuff
// After this call, debug_printf *MUST* be available
ost_system_initialize();
debug_printf("\r\n>>>>> Starting OpenStoryTeller: V%d.%d <<<<<\n", 1, 0);
debug_printf("\r\n [OST] Starting OpenStoryTeller tests: V%d.%d\r\n", 1, 0);
// File system access
filesystem_mount();
@ -38,24 +38,127 @@ int main(void)
#include "sdcard.h"
const uint16_t tones[3][8] =
{
{0xff, 131, 147, 165, 175, 196, 220, 247},
{0xff, 262, 294, 330, 349, 392, 440, 494},
{0xff, 524, 988, 660, 698, 784, 880, 988},
};
const uint8_t Happy_birthday[] =
{
6, 1, 3, 5, 1, 1, 3, 1, 2, 5, 1, 2, 1, 2, 2, 6, 1, 1, 5, 1, 1, 6, 1, 4, 3, 1, 1,
5, 1, 1, 6, 1, 1, 5, 1, 2, 3, 1, 2, 1, 1, 1, 6, 0, 1, 5, 1, 1, 3, 1, 1, 2, 1, 4,
2, 1, 3, 3, 1, 1, 5, 1, 2, 5, 1, 1, 6, 1, 1, 3, 1, 2, 2, 1, 2, 1, 1, 4, 5, 1, 4,
3, 1, 1, 2, 1, 1, 1, 1, 1, 6, 0, 1, 1, 1, 1, 5, 0, 8, 0};
#include <stdint.h>
#include <stdbool.h>
#include <stdlib.h>
#include "audio_player.h"
void ost_hal_panic()
{
}
extern void qor_sleep();
void UserTask_0(void *args)
{
// InstrumentTriggerPE11_Init();
// uint32_t count = 0;
while (1)
{
ost_hal_gpio_set(OST_GPIO_DEBUG_LED, 1);
// qor_sleep();
for (int i = 0; i < 65500; i++)
{
for (int j = 0; j < 100; j++)
;
}
// ost_system_delay_ms(500);
ost_hal_gpio_set(OST_GPIO_DEBUG_LED, 0);
// ost_system_delay_ms(500);
for (int i = 0; i < 65500; i++)
{
for (int j = 0; j < 100; j++)
;
}
}
}
void UserTask_1(void *args)
{
while (1)
{
ost_system_delay_ms(1000);
debug_printf("X\n");
ost_system_delay_ms(1000);
}
}
/*
void UserTask_2(void)
{
InstrumentTriggerPE13_Init();
uint32_t count = 0;
while (1)
{
InstrumentTriggerPE13_Toggle();
count++;
if (count % 35 == 0)
OS_Thread_Sleep(4500);
else
HAL_Delay(70);
}
}
void UserTask_3(void)
{
InstrumentTriggerPE14_Init();
while (1)
{
InstrumentTriggerPE14_Toggle();
HAL_Delay(60);
}
}
*/
#include "pico/stdlib.h"
extern size_t __StackTop;
int main()
{
ost_system_initialize();
// 1. Test the printf output
debug_printf("\r\n [OST] Starting OpenStoryTeller tests: V%d.%d\r\n", 1, 0);
/*
filesystem_mount();
// 2. Unit test the SD Card
// sdcard_init();
picture_show("example.bmp");
*/
// ost_audio_play("out2.wav");
OS_Init(THREADFREQ);
qor_create_thread(UserTask_0, 1, "UserTask_0");
// qor_create_thread(UserTask_1, 2, "UserTask_1");
// OS_Thread_Create(UserTask_2, OS_SCHEDL_PRIO_MAIN_THREAD, "UserTask_2");
// OS_Thread_Create(OnboardUserButton_Task, OS_SCHEDL_PRIO_EVENT_THREAD, "OnboardUserButton_Task");
qor_start();
for (;;)
{
ost_hal_gpio_set(OST_GPIO_DEBUG_LED, 1);
ost_system_delay_ms(1000);
ost_hal_gpio_set(OST_GPIO_DEBUG_LED, 0);
ost_system_delay_ms(1000);
// ost_hal_audio_loop();
// ost_hal_gpio_set(OST_GPIO_DEBUG_LED, 1);
// ost_system_delay_ms(1000);
// ost_hal_gpio_set(OST_GPIO_DEBUG_LED, 0);
// ost_system_delay_ms(1000);
}
return 0;
}

299
software/system/os.c Normal file
View file

@ -0,0 +1,299 @@
/**
* @brief
*
* // Quite OK RTOS scheduler is a very simple real-time, pre-emptive, tickless tasker
* Design goals:
* - Easily portable (limited assembly)
* - Tick-less
* - Preemptive
* - Only one inter-thread resource: mailboxes (no mutex, semaphore...)
*/
#include "ost_hal.h"
#include "debug.h"
#include "os.h"
#include <stdlib.h>
#include "pico/critical_section.h"
/**
* The fn OSAsm_ThreadSwitch, implemented in os_asm.s, is periodically called by the SchedlTimer (ISR).
* It preemptively switches to the next thread, that is, it stores the stack of the running
* thread and restores the stack of the next thread.
* It calls OS_Schedule to determine which thread is run next and update RunPt.
*/
extern void OSAsm_ThreadSwitch(void);
static critical_section_t acrit;
inline static void enable_irq()
{
critical_section_exit(&acrit);
}
inline static void disable_irq()
{
critical_section_enter_blocking(&acrit);
}
void timer_set_period(uint16_t i);
void ost_tasker_sleep_for(uint32_t ms)
{
timer_set_period(ms);
}
void ost_tasker_init()
{
ost_tasker_sleep_for(5000); // 5 seconds
}
static uint32_t counter = 0;
// void ost_tasker_timer_callback()
// {
// // debug_printf("%d\n", counter++);
// qor_switch_context();
// }
#define OS_DEBUG
/**
* TCBState indicates whether the TCB can be used by OS_ThreadCreate
* to create a new thread.
*/
typedef enum
{
TCBStateFree,
TCBStateActive
} TCBState_t;
void qor_sleep_ms(uint8_t svc, uint32_t ms)
{
__wfi;
}
/**
* Thread Control Block
*
* IMPORTANT!
* The fn OSAsm_Start and OSAsm_ThreadSwitch, implemented in os_asm.s, expect the stack pointer
* to be placed first in the struct. Don't shuffle it!
*/
typedef struct TCB
{
uint32_t *sp; /* Stack pointer, valid for threads not running */
struct TCB *next; /* Pointer to circular-linked-list of TCBs */
uint32_t sleep; /* Sleep duration in ms, zero means not sleeping */
TCBState_t status; /* TCB active or free */
Semaphore_t *blocked; /* Pointer to semaphore on which the thread is blocked, NULL if not blocked */
uint8_t priority; /* Thread priority, 0 is highest, 255 is lowest */
const char *name; /* Descriptive name to facilitate debugging */
uint32_t pc;
} TCB_t;
//==================================================================================================
// GLOBAL AND STATIC VARIABLES
//==================================================================================================
static TCB_t TCBs[MAXNUMTHREADS];
static uint32_t Stacks[MAXNUMTHREADS][STACKSIZE];
/* Pointer to the currently running thread */
TCB_t *RunPt;
static uint32_t global_stack[1000];
/* The variable ActiveTCBsCount tracks the number of TCBs in use by the OS */
static uint32_t ActiveTCBsCount;
static void OS_InitTCBsStatus(void)
{
for (uint32_t idx = 0; idx < MAXNUMTHREADS; idx++)
{
TCBs[idx].status = TCBStateFree;
}
}
void OS_Init(uint32_t scheduler_frequency_hz)
{
critical_section_init(&acrit);
OS_InitTCBsStatus();
}
void OS_ExitLoop()
{
for (;;)
;
}
extern void qor_go();
uint32_t *qor_initialize_stack(uint32_t *top_of_stack, thread_func_t task, void *args)
{
// ARM Calling convention: the folowwing registers are automatically saved onto the stack by the processor (in this ordoer on the stack)
// DDI0419C_arm_architecture_v6m_reference_manual-1.pdf B1.5.6 Exception entry behavior
top_of_stack--;
/* From the "STM32 Cortex-M4 Programming Manual" on page 23:
* attempting to execute instructions when the T bit is 0 results in a fault or lockup */
*top_of_stack = 0x01000000; /* Thumb Bit (PSR) */
top_of_stack--;
*top_of_stack = (uint32_t)task; // PC Program Counter (R15)
top_of_stack--;
*top_of_stack = (uint32_t)OS_ExitLoop; /* (LR) Link Register (Return address) R14 */
top_of_stack -= 5; // skip R12, R3, R2, R1
*top_of_stack = (uint32_t)args; // R0
top_of_stack -= 8; // R11 -> R4
return top_of_stack;
}
void qor_create_thread(thread_func_t task, uint8_t priority, const char *name)
{
assert_or_panic(ActiveTCBsCount >= 0 && ActiveTCBsCount < MAXNUMTHREADS);
disable_irq();
/* Find next available TCB */
int32_t new_tcb_idx = -1;
for (new_tcb_idx = 0; new_tcb_idx < MAXNUMTHREADS; new_tcb_idx++)
{
if (TCBs[new_tcb_idx].status == TCBStateFree)
{
break;
}
}
if (new_tcb_idx >= 0)
{
if (new_tcb_idx == 0)
{
RunPt = &(TCBs[0]);
}
else
{
TCBs[new_tcb_idx].next = RunPt->next;
}
TCBs[new_tcb_idx].sleep = 0;
TCBs[new_tcb_idx].status = TCBStateActive;
TCBs[new_tcb_idx].blocked = NULL;
TCBs[new_tcb_idx].priority = priority;
TCBs[new_tcb_idx].name = name;
TCBs[new_tcb_idx].sp = qor_initialize_stack(&Stacks[new_tcb_idx][STACKSIZE], task, (void *)name);
RunPt->next = &(TCBs[new_tcb_idx]);
ActiveTCBsCount++;
}
enable_irq();
}
void qor_start(void)
{
assert_or_panic(ActiveTCBsCount > 0);
/* Prevent the timer's ISR from firing before OSAsm_Start is called */
disable_irq();
qor_go();
/* This statement should not be reached */
ost_hal_panic();
}
void qor_scheduler(void)
{
TCB_t *next_pt = RunPt->next;
TCB_t *iterating_pt = next_pt;
/* Search for highest priority thread not sleeping or blocked */
uint32_t max_priority = RunPt->priority;
TCB_t *best_pt = next_pt;
do
{
if ((iterating_pt->priority > max_priority) && (iterating_pt->sleep == 0) && (iterating_pt->blocked == NULL))
{
best_pt = iterating_pt;
max_priority = best_pt->priority;
}
iterating_pt = iterating_pt->next;
} while (iterating_pt != next_pt);
RunPt = best_pt;
}
void OS_Thread_Suspend(void)
{
// SchedlTimer_ResetCounter();
}
void OS_Thread_Sleep(uint32_t sleep_duration_ms)
{
RunPt->sleep = sleep_duration_ms;
OS_Thread_Suspend();
}
void OS_DecrementTCBsSleepDuration(void)
{
for (size_t tcb_idx = 0; tcb_idx < MAXNUMTHREADS; tcb_idx++)
{
if (TCBs[tcb_idx].sleep > 0)
{
TCBs[tcb_idx].sleep -= 1;
}
}
}
void OS_Thread_Kill(void)
{
assert_or_panic(ActiveTCBsCount > 1);
disable_irq();
TCB_t *previous_tcb = RunPt;
while (1)
{
previous_tcb = previous_tcb->next;
if (previous_tcb->next == RunPt)
break;
}
TCB_t *next_tcb = RunPt->next;
previous_tcb->next = next_tcb;
RunPt->status = TCBStateFree;
ActiveTCBsCount--;
enable_irq();
OS_Thread_Suspend();
}
void OS_Semaphore_Wait(Semaphore_t *sem)
{
disable_irq();
(*sem) = (*sem) - 1;
if ((*sem) < 0)
{
RunPt->blocked = sem; /* Reason the thread is blocked */
enable_irq();
OS_Thread_Suspend();
}
enable_irq();
}
void OS_Semaphore_Signal(Semaphore_t *sem)
{
disable_irq();
(*sem) = (*sem) + 1;
if ((*sem) <= 0)
{
/* Search for a TCB blocked on this semaphore and wake it up */
TCB_t *a_tcb = RunPt->next;
while (a_tcb->blocked != sem)
{
a_tcb = a_tcb->next;
}
a_tcb->blocked = 0;
}
enable_irq();
}

62
software/system/os.h Normal file
View file

@ -0,0 +1,62 @@
#ifndef OS_H
#define OS_H
void ost_tasker_init();
extern void ost_hal_panic();
/**
* Assert, or panic.
*/
#define assert_or_panic(expr) ((expr) ? (void)0U : ost_hal_panic())
/**
* The module os encapsulates the core functionality of the operating system and
* exposes the functions for interacting with it.
*/
#include <stdint.h>
#define MAXNUMTHREADS 10 /* Maximum number of threads, allocated at compile time */
#define STACKSIZE 100 /* Number of 32-bit words in each TCB's stack */
#define THREADFREQ 1 /* Maximum time-slice, in Hz, before the scheduler is run */
#define OS_SCHEDL_PRIO_MIN 1 /* Lowest priority that can be assigned to a thread */
#define OS_SCHEDL_PRIO_MAX UINT8_MAX /* Highest priority that can be assigned to a thread */
/**
* The type Semaphore_t abstracts the semaphore's counter.
* A value of type *Semaphore_t should only be updated through the fn OS_Semaphore_Wait
* and OS_Semaphore_Signal.
*/
typedef int32_t Semaphore_t;
typedef void (*thread_func_t)(void *args);
/**
* Function descriptions are provided in os.c
*/
void OS_Init(uint32_t scheduler_frequency_hz);
// void OS_Thread_CreateFirst(thread_func_t task, uint8_t priority, const char *name);
void qor_create_thread(thread_func_t task, uint8_t priority, const char *name);
void qor_switch_context();
void qor_start(void);
void OS_Thread_Suspend(void);
void OS_Thread_Sleep(uint32_t sleep_duration_ms);
void OS_DecrementTCBsSleepDuration(void);
void OS_Thread_Kill(void);
void OS_Semaphore_Wait(Semaphore_t *sem);
void OS_Semaphore_Signal(Semaphore_t *sem);
#endif // OST_TASKER_H

View file

@ -1,42 +0,0 @@
/**
* @brief
*
* // OST scheduler is a very simple real-time, pre-emptive, tickless tasker
* Design goals:
* - Easily portable (limited assembly)
* - Tick-less
* - Preemptive
* - Everything runs in interrupts
* - The background task is calling platform specific sleep modes
*/
#include "ost_hal.h"
#include "debug.h"
typedef struct
{
uint8_t regs;
} cpu_t;
void timer_set_period(uint16_t i);
void ost_tasker_sleep_for(uint32_t ms)
{
timer_set_period(ms);
}
void ost_tasker_init()
{
ost_tasker_sleep_for(5000); // 5 seconds
}
static uint32_t counter = 0;
void ost_tasker_timer_callback()
{
debug_printf("%d\n", counter++);
}
void ost_tasker_schedule(void)
{
}

View file

@ -1,6 +0,0 @@
#ifndef OST_TASKER_H
#define OST_TASKER_H
void ost_tasker_init();
#endif // OST_TASKER_H

View file

@ -39,7 +39,8 @@ static uint8_t bmpImage[512];
static uint8_t decompressed[1024];
static uint8_t palette[16 * 4];
typedef struct {
typedef struct
{
uint16_t type; /* Magic identifier */
uint32_t size; /* File size in bytes */
uint16_t reserved1;
@ -47,7 +48,8 @@ typedef struct {
uint32_t offset; /* Offset to image data, bytes */
} bmp_header_t;
typedef struct {
typedef struct
{
uint32_t size; /* Header size in bytes */
uint32_t width;
uint32_t height; /* Width and height of image */
@ -92,7 +94,7 @@ uint8_t parse_bmp(const uint8_t *data, bmp_header_t *header, bmp_infoheader_t *i
return isBmp;
}
void decompress(const char *filename)
void picture_show(const char *filename)
{
file_t fil;
uint32_t offset;
@ -261,7 +263,7 @@ void decompress(const char *filename)
{
// enough pixels to write a line to the screen
ost_display_draw_h_line(pos.y, decompressed, palette);
debug_printf("POS Y: %d", pos.y);
// debug_printf("POS Y: %d", pos.y);
memset(decompressed, 0, sizeof(decompressed));
// ili9341_write(&pos, decompressed);
@ -282,13 +284,12 @@ void decompress(const char *filename)
{
end = true; // error
}
}
while((offset < fileSize) && !end);
} while ((offset < fileSize) && !end);
if (end)
{
debug_printf("\r\n>>>>> Decoding error !! <<<<\r\n");
}
// if (end)
// {
// debug_printf("\r\n>>>>> Decoding error !! <<<<\r\n");
// }
// Fill missing lines
if (nblines < info_header.height)
@ -308,9 +309,5 @@ void decompress(const char *filename)
fclose(fil);
#endif
debug_printf("\r\nNb lines :%d\r\nTotal pixels: %d", (uint32_t)nblines, (uint32_t)totalPixels);
}

View file

@ -3,14 +3,14 @@
#define PICTURE_H
#ifdef __cplusplus
extern "C" {
extern "C"
{
#endif
void decompress(const char *filename);
void picture_show(const char *filename);
#ifdef __cplusplus
}
#endif
#endif // PICTURE_H

View file

@ -0,0 +1,171 @@
.syntax unified
.cpu cortex-m0
.fpu softvfp
.thumb
.code 16
.thumb_func
@ The .global directive gives the symbols external linkage.
@ For clarity, the fn OSAsm_ThreadSwitch is exported as TIM2_IRQHandler, so that the vector table
@ in startup.s doesn't need to be modified.
.global qor_go
.global qor_switch_context
.global qor_sleep
.extern RunPt
.extern qor_scheduler
.extern qor_svc_call
.section .text.qor_go
.type qor_go, %function
@ The Cortex-M0 is limited on the thumb number of instructionss
@ the context restore is therefore a bit more complex that M3 or M4 CPU
@ One limitation is the POP instruction that cannot access to the HI registers (registers after R7)
@
@ | |
@ -------------
@ | |
@ -------------
@ | |
@ -------------
@ | |
@ -------------
@ | |
@ -------------
@ | |
@ -------------
@ | |
@ -------------
@ | |
@ -------------
@ | |
@ -------------
@ | |
@ -------------
@ | |
@ -------------
@ | |
@ -------------
@ | |
@ -------------
@ | |
@ -------------
@ | |
@ -------------
@ | |
@ -------------
@ | |
@ -------------
@
@
@
@
qor_go:
LDR r2, =RunPt @ R0 = &RunPt; // TCB_t** R0 = &RunPt // R0 contient l'adresse de la variable 'RunPt', qui est un pointeur vers la structure TCB courante
LDR r3, [r2] @ R1 = *R0; // TCB_t* R1 = RunPt // R1 pointe maintenant sur RunPt
LDR r0, [r3] @ R2 = *R1 // On veut la vleur pointée par RunPt (premier élément, donc même adresse) qui correspon à la variable *sp (c'est un pointeur vers la stack)
adds r0, #32 @ Discard everything up to r0.
msr psp, r0 @ SP = R2; // uint32_t SP = R2
@ now we switched to the thread's stack, which we populated before
movs r0, #2
msr CONTROL, r0 @ ensure we use PSP not MSP
isb @ throw away any prefetched instructions at this point
pop {r0-r5} @ R0 contains the argument, R1 the link register
mov lr, r5 @ Update LR
pop {r3} @ Task code
pop {r2} @ Pop and discard XPSR. */
cpsie i @ Enable interrupts before launching the
bx r3 @ /* Finally, jump to the user defined task code. */
@ .section .text.qor_sleep
@ .type qor_sleep, %function
@ qor_sleep:
@ mov r1, r0 @ copy sleep value in second argument
@ movs r0, #1 @ sleep is SVC 1
@ mov r2, lr @ remember where we are
@ bl qor_svc_call
@ wfi
@ bx lr
@ EnterCriticalSection:
@ MRS r0, PRIMASK /* Save interrupt state. */
@ CPSID i /* Turn off interrupts. */
@ BX lr /* Return. */
@ ExitCriticalSection:
@ MSR PRIMASK, r0 /* Restore interrupt states. */
@ BX lr /* Return. */
@ EXC_RETURN value to return to Thread mode, while restoring state from PSP.
.equ EXC_RETURN, 0xfffffffd
.section .text.qor_switch_context
.type qor_switch_context, %function
qor_switch_context:
.thumb
.syntax unified
@ Les registers r0-r3 r12 etc. sont sauvegardés par le processeur
mrs r0, psp @ get the current stack address ()
ldr r1, =RunPt
ldr r2, [r1]
@ Subtract room for the registers we are going to store. We have to pre-subtract
@ and use the incrementing store multiple instruction because the CM0+ doesn't
@ have the decrementing variant.
subs r0, r0, #32
str r0, [r2] @ Save the new top of stack
@ Save registers on the stack. This has to be done in two stages because
@ the stmia instruction cannot access the upper registers on the CM0+.
stmia r0!, {r4-r7}
mov r4, r8
mov r5, r9
mov r6, r10
mov r7, r11
stmia r0!, {r4-r7}
cpsid i
bl qor_scheduler
cpsie i
ldr R0, =RunPt
ldr r1, [r0]
ldr r0, [r1] @ R0 is the stack address
@ On est obligé de poper les registres haut d'abord (on n'a pas accès directement à ceux-ci via ldmia)
adds r0, r0, #16 @ move to hi regs
ldmia r0!, {r4-r7} @ pop
mov r8, r4
mov r9, r5
mov r10, r6
mov r11, r7
msr psp, r0 @ new task stack top address
subs r0, r0, #32
ldmia r0!, {r4-r7}
// Exit handler. Using a bx to the special EXC_RETURN values causes the
// processor to perform the exception return behavior.
ldr r0, =EXC_RETURN
bx r0

View file

@ -155,8 +155,8 @@ static SD_Error SD_SendCmd(uint8_t cmd, uint32_t arg, uint8_t crc)
ost_hal_sdcard_spi_transfer((uint8_t)arg); /*!< byte 5 */
ost_hal_sdcard_spi_transfer(crc | 0x01); /*!< byte 6: CRC */
/* a byte received immediately after CMD12 should be discarded... */
// if (cmd == SD_CMD_STOP_TRANSMISSION)
// ost_hal_sdcard_spi_transfer();
if (cmd == SD_CMD_STOP_TRANSMISSION)
ost_hal_sdcard_spi_transfer(0xFF);
/* SD Card responds within Ncr (response time),
which is 0-8 bytes for SDSC cards, 1-8 bytes for MMC cards */
do
@ -538,7 +538,7 @@ SD_Error sdcard_sectors_read(uint32_t readAddr, uint8_t *pBuffer, uint32_t nbSec
{
SD_Error state;
debug_printf("--> reading %lu sectors from %lu ...", nbSectors, readAddr);
// debug_printf("--> reading %lu sectors from %lu ...", nbSectors, readAddr);
/* non High Capacity cards use byte-oriented addresses */
if (cardType != SD_Card_SDHC)
@ -733,7 +733,7 @@ SD_Error sdcard_sectors_erase(uint32_t eraseAddrFrom, uint32_t eraseAddrTo)
return SD_ILLEGAL_COMMAND;
}
debug_printf("--> erasing sectors from %lu to %lu ...", eraseAddrFrom, eraseAddrTo);
// debug_printf("--> erasing sectors from %lu to %lu ...", eraseAddrFrom, eraseAddrTo);
/* non High Capacity cards use byte-oriented addresses */
if (cardType != SD_Card_SDHC)

View file

@ -1,173 +0,0 @@
/*--------------------------------------------------------------------------
IMPORTATION DES FICHIERS DE DEFINITION DE LIBRAIRIE
--------------------------------------------------------------------------*/
#include "sst_conf.h"
#include <stdint.h>
/*--------------------------------------------------------------------------
PROTOTYPE DES FONCTIONS INTERNES
--------------------------------------------------------------------------*/
/*--------------------------------------------------------------------------
VARIABLES GLOBALES
--------------------------------------------------------------------------*/
/* Public-scope objects ----------------------------------------------------*/
uint16_t SST_currPrio_ = (uint16_t)0xFF; /* current SST priority */
uint16_t SST_readySet_ = (uint16_t)0; /* SST ready-set */
typedef struct {
SSTTask task__;
SSTEvent *queue__;
uint16_t end__;
uint16_t head__;
uint16_t tail__;
uint16_t nUsed__;
uint16_t mask__;
} TaskCB;
/* Local-scope objects -----------------------------------------------------*/
static TaskCB l_taskCB[SST_MAX_PRIO];
/*==========================================================================
====================== I N T E R R U P T I O N S =========================
==========================================================================*/
/*==========================================================================
========================== F O N C T I O N S =============================
==========================================================================*/
/*..........................................................................*/
void SST_Task(SSTTask task, uint16_t prio, SSTEvent *queue, uint16_t qlen,
SSTSignal sig, SSTParam par)
{
SSTEvent ie; /* initialization event */
TaskCB *tcb = &l_taskCB[prio - 1];
tcb->task__ = task;
tcb->queue__ = queue;
tcb->end__ = qlen;
tcb->head__ = (uint16_t)0;
tcb->tail__ = (uint16_t)0;
tcb->nUsed__ = (uint16_t)0;
tcb->mask__ = (1 << (prio - 1));
ie.sig = sig;
ie.par = par;
tcb->task__(ie); /* initialize the task */
}
/*..........................................................................*/
void SST_Run(void) {
SST_Start(); /* start ISRs */
SST_INT_LOCK();
SST_currPrio_ = (uint16_t)0; /* set the priority for the SST idle loop */
SST_Schedule_(); /* process all events produced so far */
SST_INT_UNLOCK();
for (;;) { /* the SST idle loop */
SST_OnIdle(); /* invoke the on-idle callback */
}
}
/*..........................................................................*/
uint16_t SST_Post(uint16_t prio, SSTSignal sig, SSTParam par) {
TaskCB *tcb = &l_taskCB[prio - 1];
SST_INT_LOCK();
if (tcb->nUsed__ < tcb->end__) {
tcb->queue__[tcb->head__].sig = sig;/* insert the event at the head */
tcb->queue__[tcb->head__].par = par;
if ((++tcb->head__) == tcb->end__) {
tcb->head__ = (uint16_t)0; /* wrap the head */
}
if ((++tcb->nUsed__) == (uint16_t)1) { /* the first event? */
SST_readySet_ |= tcb->mask__; /* insert task to the ready set */
SST_Schedule_(); /* check for synchronous preemption */
}
SST_INT_UNLOCK();
return (uint16_t)1; /* event successfully posted */
}
else {
SST_INT_UNLOCK();
return (uint16_t)0; /* queue full, event posting failed */
}
}
/*..........................................................................*/
uint16_t SST_MutexLock(uint16_t prioCeiling) {
uint16_t p;
SST_INT_LOCK();
p = SST_currPrio_; /* the original SST priority to return */
if (prioCeiling > SST_currPrio_) {
SST_currPrio_ = prioCeiling; /* raise the SST priority */
}
SST_INT_UNLOCK();
return p;
}
/*..........................................................................*/
void SST_MutexUnlock(uint16_t orgPrio) {
SST_INT_LOCK();
if (orgPrio < SST_currPrio_) {
SST_currPrio_ = orgPrio; /* restore the saved priority to unlock */
SST_Schedule_(); /* invoke scheduler after lowering the priority */
}
SST_INT_UNLOCK();
}
/*..........................................................................*/
/* NOTE: the SST scheduler is entered and exited with interrupts LOCKED */
void SST_Schedule_(void) {
uint16_t pin = SST_currPrio_; /* save the initial priority */
uint16_t p; /* the new priority */
static const uint8_t log2Lkup[] = {
0, 1, 2, 2, 3, 3, 3, 3, 4, 4, 4, 4, 4, 4, 4, 4,
5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5,
6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6,
6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6,
7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7,
7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7,
7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7,
7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7,
8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8,
8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8,
8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8,
8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8,
8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8,
8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8,
8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8,
8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8
};
while ((p = log2Lkup[SST_readySet_]) > pin) {
/* is the new priority higher than the initial? */
// for( p=SST_MAX_PRIO; p>pin; p--) {
// if( SST_readySet_ & (1<<(p-1)) ) {
// if( p > pin ) {
// reprise de l'ancien code
TaskCB *tcb = &l_taskCB[p - 1];
/* get the event out of the queue */
SSTEvent e = tcb->queue__[tcb->tail__];
if ((++tcb->tail__) == tcb->end__) {
tcb->tail__ = (uint16_t)0;
}
if ((--tcb->nUsed__) == (uint16_t)0) {/* is the queue becoming empty?*/
SST_readySet_ &= ~tcb->mask__; /* remove from the ready set */
}
SST_currPrio_ = p; /* this becomes the current task priority */
SST_INT_UNLOCK(); /* unlock the interrupts */
(*tcb->task__)(e); /* call the SST task */
SST_INT_LOCK(); /* lock the interrupts for the next pass */
// }
// }
}
SST_currPrio_ = pin; /* restore the initial priority */
}
/*--------------------------------------------------------------------------
FIN FICHIER
--------------------------------------------------------------------------*/
/** @} */

View file

@ -1,66 +0,0 @@
#ifndef _SST_H
#define _SST_H
#include "global_defines.h"
/*--------------------------------------------------------------------------
DEFINITIONS
--------------------------------------------------------------------------*/
typedef uint16_t SSTSignal;
typedef uint16_t SSTParam;
typedef struct SSTEventTag SSTEvent;
struct SSTEventTag {
SSTSignal sig;
SSTParam par;
};
typedef void (*SSTTask)(SSTEvent e);
/* SST interrupt entry and exit */
#define SST_ISR_ENTRY(pin_, isrPrio_) do { \
(pin_) = SST_currPrio_; \
SST_currPrio_ = (isrPrio_); \
SST_INT_UNLOCK(); \
} while (0)
#define SST_ISR_EXIT(pin_) do { \
SST_INT_LOCK(); \
SST_currPrio_ = (pin_); \
SST_Schedule_(); \
} while (0)
/*--------------------------------------------------------------------------
VARIABLES EXPORTEES
--------------------------------------------------------------------------*/
/* public-scope objects */
extern uint16_t SST_currPrio_; /* current priority of the executing task */
extern uint16_t SST_readySet_; /* SST ready-set */
/*--------------------------------------------------------------------------
FONCTIONS EXPORTEES
--------------------------------------------------------------------------*/
void SST_Init(void);
void SST_Task(SSTTask task, uint16_t prio, SSTEvent *queue, uint16_t qlen,
SSTSignal sig, SSTParam par);
void SST_Start(void);
void SST_Run(void);
void SST_OnIdle(void);
void SST_Exit(void);
uint16_t SST_Post(uint16_t prio, SSTSignal sig, SSTParam par);
uint16_t SST_MutexLock(uint16_t prioCeiling);
void SST_MutexUnlock(uint16_t orgPrio);
void SST_Schedule_(void);
#endif /* _SST_H */
/*--------------------------------------------------------------------------
FIN FICHIER
--------------------------------------------------------------------------*/

View file

@ -1,127 +0,0 @@
// Scheduler
#include "sst_conf.h"
#include "board.h"
#include "app_airserenity.h"
#include "app_clock.h"
#include "esp32.h"
#include "time_server.h"
#include "uart1.h"
#include "data_storage.h"
// TCP/IP
#include "tcp_client.h"
// C library
#include <stdio.h>
#include <stdlib.h>
#include <math.h>
// Event queue, one per task
static SSTEvent TaskAppSerenityQueue[10];
static SSTEvent TaskTcpIpQueue[10];
AirParam_t AirParam;
#define CONSOLE_RCV_BUF_SIZE 1024
static unsigned char consoleRcvBuf[CONSOLE_RCV_BUF_SIZE];
static uint32_t consoleRcvSize = 0;
static uint8_t gEndOfFrameTimerId = 0U;
void HandleUart1Rx(uint8_t data)
{
if (consoleRcvSize < CONSOLE_RCV_BUF_SIZE)
{
consoleRcvBuf[consoleRcvSize] = data;
consoleRcvSize++;
TimerStart(gEndOfFrameTimerId); // restart timer from zero each time we receive data
// GpioDebug = 1;
}
}
// Called when uart data has been received
void Console_ReceiveSignal(void)
{
// GpioDebug = 0;
SST_Post(TASK_APP_SERENITY, RUN_SIG, APP_SIG_CONSOLE_DATA);
}
// =============================================================================
// FONCTIONS DU MODULE
// =============================================================================
void TASK_AppSerenity(SSTEvent e)
{
switch (e.sig) {
case INIT_SIG:
break;
// Called each second
case RUN_SIG:
if ((e.par == APP_SIG_LONG_PUSH) || (e.par == APP_SIG_SHORT_PUSH))
{
APP_GestionBoutons(e.par);
}
else if (e.par == APP_SIG_CONSOLE_DATA)
{
// On envoie la donnée reçu pour traitement
APP_ReceptionConsole(consoleRcvBuf, consoleRcvSize);
consoleRcvSize = 0U;
}
APP_SequencePrincipale();
break;
default:
break;
}
}
void TASK_Initialize(void)
{
BOARD_Initialize();
// Ok alors on va lire très très tôt les paramètres manuf
// Comme cela, on considère que AirParam est initialisé pour toutes les
// Tâches, au pire avec des valeurs par défaut
ReadAirParam(&AirParam);
APP_Initialize();
// On utilise le port série en interruption, pour la réception uniquement
UART1_EnableRxIT();
// 50ms end of receive detection
gEndOfFrameTimerId = TimerInit(50, Console_ReceiveSignal);
// Initialisation des tâches
SST_Task(&TASK_AppSerenity, TASK_APP_SERENITY, TaskAppSerenityQueue, sizeof(TaskAppSerenityQueue)/sizeof(TaskAppSerenityQueue[0]), INIT_SIG, 0);
SST_Task(&net_task, TASK_TCP_IP, TaskTcpIpQueue, sizeof(TaskTcpIpQueue)/sizeof(TaskTcpIpQueue[0]), INIT_SIG, 0);
}
void TASK_TopSecond(void)
{
CLOCK_Update();
APP_TopSecond();
BOARD_TopSecond();
SST_Post(TASK_APP_SERENITY, RUN_SIG, 0);
SST_Post(TASK_TCP_IP, RUN_SIG, 0);
}
void TASK_EmergencyStop(void)
{
// FIXME: implémenter quelque chose lorsque tout va mal (interrptions non gérées, dépassement mémoire ...)
// Idéalement:
// 1. Mettre un flag en mémoire non volatile (RAM non intialisée)
// 2. Redémarrer
// 3. Au démarrage suivant, détecter ce flag et logguer l'erreur (date, compteur, etc.)
}

View file

@ -1,52 +0,0 @@
/**
* File: sst_conf.h
*/
#ifndef _SST_CONF_h
#define _SST_CONF_h
#include "global_defines.h"
#include "sst.h"
/*--------------------------------------------------------------------------
DEFINITIONS
--------------------------------------------------------------------------*/
/* SST interrupt locking/unlocking */
#define SST_INT_LOCK() {_DISI = 1;}
#define SST_INT_UNLOCK() { _GIE = 1; }
/* maximum SST task priority */
#define SST_MAX_PRIO 8
/* the events used in the application */
enum Events {
INIT_SIG, /* initialization event */
REINIT_SIG,
RUN_SIG /* normal run */
};
/* les priorités vont dans l'ordre croissant d'importance */
enum SSTPriorities { /* the SST priorities don't need to be consecutive */
TASK_IDLE = 0,
/* task priorities from low to high */
ISR_TIMER2_PRIO,
ISR_TIMER3_PRIO,
ISR_UART1_PRIO,
ISR_UART2_PRIO,
TASK_ESP32,
TASK_TCP_IP,
TASK_APP_SERENITY,
};
/*--------------------------------------------------------------------------
FONCTIONS EXPORTEES
--------------------------------------------------------------------------*/
void TASK_EmergencyStop(void);
void TASK_TopSecond(void);
void TASK_Initialize(void);
#endif /* _SST_CONF_h */
/*--------------------------------------------------------------------------
FIN FICHIER
--------------------------------------------------------------------------*/

28
story-player/.vscode/launch.json vendored Normal file
View file

@ -0,0 +1,28 @@
{
"version": "0.2.0",
"configurations": [
{
"name": "C/C++ debug",
"cwd": "${workspaceFolder}",
"type": "cppdbg",
"request": "launch",
"program": "${workspaceFolder}/build/story-player", // Binary to exec
"args": [
"build/config.yml"
], // Arguments passed
"stopAtEntry": false,
"environment": [],
"externalConsole": false,
"MIMode": "gdb",
"setupCommands": [
{
"description": "Enable pretty-printing for gdb",
"text": "-enable-pretty-printing",
"ignoreFailures": true
}
],
"preLaunchTask": "${defaultBuildTask}",
"miDebuggerPath": "/usr/bin/gdb"
}
]
}

View file

@ -0,0 +1 @@

View file

@ -1942,7 +1942,7 @@ int GuiToggleGroup(Rectangle bounds, const char *text, int *active)
int result = 0;
float initBoundsX = bounds.x;
bool temp = false;
int temp = 0;
if (active == NULL) active = &temp;
bool toggle = false; // Required for individual toggles