prettyprint

2024年2月15日 星期四

TinyML(Edge Impulse) : Voice remote control car || RP2040 || Cortex-M0+

 本篇文章介紹 使用Edge Impulse 語音機器學習,在Raspberry Pi Pico(RP2040) MCU上執行 Voice recognition,用來控制一輛遙控小車。

使用元件:

一. 控制端:

  1. Raspberry Pi Pico 
  2. INMP441 I2S microphone
  3. SD card module
  4. nRF24L01


二、受控端:
  1. Raspberry Pi Pico
  2. TT馬達+65mm 車輪 X 4
  3. L298N 直流馬達驅動板
  4. nRF24L01


本專案使用7個語音來控制小車的動作:
  1. 向前進(forward)
  2. 往後退(backward)
  3. 停在原地(stop)
  4. 方向左轉(turn left)
  5. 方向右轉(turn right)
  6. 速度加快(speed up)
  7. 速度減慢(slow down)
Edge Impulse 本專案使用參數:
  • Create Impulse
  • MFCC

  • Classifier

  • Performance calibration

機器學習訓練過程請參閱成果影片的動態說明。


成果影片:





程式碼:

 控制端:


有關nRF24L01, pico_audio_recorder, storage_driver等library使用起參閱前一篇文章:MCU(RP2040) voice recognition/voice commands using TinyML(Edge Impulse)

  • pico_tinyML_voice.cpp


#include <stdlib.h>
#include <stdio.h>
#include <sttring.h>
#include "pico/stdlib.h"
#include "bsp/board.h"
#include "tusb.h"

#include "pico_storage.h"
#include "hardware/rtc.h"
#include "pico_audio_recorder.h"
#include "hardware/dma.h"
#include "nRF24L01.h"

#include "edge-impulse-sdk/classifier/ei_run_classifier.h"
#include "edge-impulse-sdk/classifier/ei_classifier_smooth.h"
extern bool new_read_data;
extern int16_t *fw_ptr;

#if DATA_ACQUISITION
#else
int raw_feature_get_data(size_t offset, size_t length, float *out_ptr) {
    numpy::int16_to_float(fw_ptr+offset, out_ptr, length);
    return 0;
}
#endif

//=== nRF24L01 irq
char const *addr[5] = {"0node", "1node", "2node","3node","4node"};
#define TX_PIN 17

void irq_callback(uint8_t event_type, uint8_t datapipe, uint8_t* data, uint8_t width) {
    static uint32_t ack_payload=0;
    uint8_t ack_buff[15];
      switch(event_type) {
        case EVENT_RX_DR:
            data[width]='\0';
            printf("RECV== pipe:%d, width:%d, %s\n", datapipe, width, data);
        break;
        case EVENT_TX_DS:
            gpio_put(TX_PIN, !gpio_get(TX_PIN));
            //printf("event_data_sent:%d\n", datapipe);
        break;
        case EVENT_MAX_RT:
        printf("event_max_rt:%d, \n", datapipe);
        break;
    }

}

/*------------- MAIN -------------*/
int main(void)
{
  stdio_init_all();
#if DATA_ACQUISITION 
      rtc_init();
      datetime_t t = {
        .year=2024, .month=02, .day=12, 
        .dotw=6,
        .hour=10, .min=32, .sec=50
      };
     
      if (!rtc_set_datetime(&t)) printf("set rtc error\n");
        
      storage_driver_init();
      
      board_init();
      // init device stack on configured roothub port
      tud_init(BOARD_TUD_RHPORT);

#else 
    gpio_init(TX_PIN);
    gpio_set_dir(TX_PIN,true);
    // == nRF24L01 init
    nRF24_spi_default_init(8, 9, irq_callback);
    nRF24_config_mode(TRANSMITTER);
    nRF24_enable_feature(FEATURE_EN_DPL, true);
    nRF24_set_TX_addr((uint8_t*)addr[0], 5);
    nRF24_set_RX_addr(0, (uint8_t*)addr[0], 5);
    nRF24_enable_data_pipe_dynamic_payload_length(0, true);
    //== edge impulse
      run_classifier_init();
    
      EI_IMPULSE_ERROR res;
      ei_impulse_result_t result = {nullptr};
      signal_t features_signal;
      features_signal.total_length = EI_CLASSIFIER_SLICE_SIZE;
      features_signal.get_data = &raw_feature_get_data;

      ei_classifier_smooth_t smooth;
      ei_classifier_smooth_init(&smooth, 4, 3, 0.9, 0.3);
#endif

  inmp441_pio_init(INMP441_pio, INMP441_SM, INMP441_SD, INMP441_SCK, INMP441_SAMPLE_RATE);

  uint8_t f_idx=0;

  while (1)
  {
#if DATA_ACQUISITION
      if (get_recorder_state() == STATE_START_RECORDING) {
        inmp441_starting_recording_to_file_wav();
      }
         
      tud_task(); // tinyusb device task
#else

    if (new_read_data) {
          new_read_data = false;
//absolute_time_t t1 = get_absolute_time();
          res = run_classifier_continuous(&features_signal, &result, false,true );

          if (res != EI_IMPULSE_OK) {
                  ei_printf("ERR: Failed to run classifier (%d)\n", res);
          }
         
        //display_results(&result); printf("\n"); // only for debug
          ei_classifier_smooth_update(&smooth, &result);
          for (uint16_t i = 0; i < EI_CLASSIFIER_LABEL_COUNT; i++) {
            //result.classification[i].value = run_moving_average_filter(&classifier_maf[ix], result.classification[i].value);
            if (result.classification[i].value > 0.9f) 
            { 
              // for debug
              //ei_printf("  %s: ", ei_classifier_inferencing_categories[i]);
              //ei_printf("%.5f\r\n", result.classification[i].value);
              // for running
              nRF24_write_payload((uint8_t*)ei_classifier_inferencing_categories[i], strlen(ei_classifier_inferencing_categories[i]));
              if (strcmp(ei_classifier_inferencing_categories[i], "noise")!=0)
                run_classifier_init();
              break;
            } 
          }

        //absolute_time_t t2 = get_absolute_time();
        //printf("time:%lld\n", absolute_time_diff_us(t1,t2));
        //printf("\n");
   
    }
   
#endif
      tight_loop_contents();
  }

  return 0;
}

受控端(小車)


  • pico_tinyML_voice_RC_CAR.c
#include <stdio.h>
#include "pico/stdlib.h"
#include "nRF24L01.h"
#include "string.h"
#include "hardware/pwm.h"
#include "ws2812.h"

#define CAR_PIN1A   16
#define CAR_PIN1B   17
#define CAR_PIN2A   18
#define CAR_PIN2B   19
#define SPEED_MAX   5
uint slice1a, slice1b, slice2a, slice2b;
uint chan_1a,chan_1b,chan_2a,chan_2b;

uint8_t addr[5][5] = {"0node", "1node", "2node","3node","4node"};

enum {
    NOISE=0,
    FORWARD,
    BACKWARD,
    STOP,
    TURN_LEFT,
    TURN_RIGHT,
    SPEED_UP,
    SLOW_DOWN,
    ACTION_MAX,
};

int8_t speed=0;
uint16_t pwm_top_count[SPEED_MAX+1] = {0, 4000,8000,12000,16000,20000};
uint32_t ws2812_color[SPEED_MAX+1] = {0x0, 0xFF0000, 0xFF0000, 0x8FFF00, 0x8FFF00, 0xFF00};
uint8_t voice_state = 0;
uint8_t current_direction=STOP;

#define NUM_PIXELS 5
void play_ws2812() {
    for (int j=0; j < speed; j++) { 
        put_grb_pixel(ws2812_color[j+1]);
    }
    for (int j=speed; j < SPEED_MAX; j++) { 
        put_grb_pixel(ws2812_color[0]);
    }
    //sleep_ms(100);
    //printf("speed:%d\n", speed);
}
//nRF24L01 irq callback
void irq_callback(uint8_t event_type, uint8_t datapipe, uint8_t* data, uint8_t width) {
    static uint32_t ack_payload=0;
    uint8_t ack_buff[15];
      switch(event_type) {
        case EVENT_RX_DR:
            data[width]='\0';
            
            if (strcmp(data, "noise")==0) voice_state=NOISE;
            if (strcmp(data, "forward")==0) voice_state=FORWARD;
            if (strcmp(data, "backward")==0) voice_state=BACKWARD;
            if (strcmp(data, "stop")==0) voice_state=STOP;
            if (strcmp(data, "turn_left")==0) voice_state=TURN_LEFT;
            if (strcmp(data, "turn_right")==0) voice_state=TURN_RIGHT;
            if (strcmp(data, "speed_up")==0) voice_state=SPEED_UP;
            if (strcmp(data, "slow_down")==0) voice_state=SLOW_DOWN;

            printf("RECV== stat:%d, width:%d, %s\n", voice_state, width, data);
        break;
        case EVENT_TX_DS:
            printf("event_data_sent:%d\n", datapipe);
        break;
        case EVENT_MAX_RT:
            printf("EVENT_MAX_RT:%d\n", datapipe);
        break;
    }
}


void voice_action(uint8_t stat) {
    switch(stat) {
        case FORWARD:
            pwm_set_chan_level(slice1a, chan_1a, pwm_top_count[speed]);
            pwm_set_chan_level(slice2a, chan_2a, pwm_top_count[speed]);
            pwm_set_chan_level(slice1b, chan_1b, 0);
            pwm_set_chan_level(slice2b, chan_2b, 0);
            current_direction = FORWARD;
        break;
        case BACKWARD:
            pwm_set_chan_level(slice1a, chan_1a, 0);
            pwm_set_chan_level(slice2a, chan_2a, 0);
            pwm_set_chan_level(slice1b, chan_1b, pwm_top_count[speed]);
            pwm_set_chan_level(slice2b, chan_2b, pwm_top_count[speed]);
            current_direction = BACKWARD;
        break;
        case STOP:
            pwm_set_chan_level(slice1a, chan_1a, 0);
            pwm_set_chan_level(slice2a, chan_2a, 0);
            pwm_set_chan_level(slice1b, chan_1b, 0);
            pwm_set_chan_level(slice2b, chan_2b, 0);
            current_direction=STOP;
        break;
        case TURN_LEFT:
            pwm_set_chan_level(slice1a, chan_1a, 0);         
            pwm_set_chan_level(slice2a, chan_2a, 0);
            pwm_set_chan_level(slice1b, chan_1b, 0);
            pwm_set_chan_level(slice2b, chan_2b, 0);
            pwm_set_chan_level(slice1a, chan_1a, pwm_top_count[speed]);
            sleep_ms(500);
        break;
        case TURN_RIGHT:
            pwm_set_chan_level(slice1a, chan_1a, 0);
            pwm_set_chan_level(slice2a, chan_2a, 0);
            pwm_set_chan_level(slice1b, chan_1b, 0);
            pwm_set_chan_level(slice2b, chan_2b, 0);
            pwm_set_chan_level(slice2a, chan_2a, pwm_top_count[speed]);
            sleep_ms(500);
        break;
        case SPEED_UP:
           speed++;
           if (speed > SPEED_MAX) speed=SPEED_MAX;   
           play_ws2812();      
        break;
        case SLOW_DOWN:
           speed--;
           if (speed < 0) speed=0; 
           play_ws2812();
        break;
        default:
        break;
    }
}

int main()
{
    
    stdio_init_all(); 

    ws2812_init(pio0, 0, 20);

    gpio_set_function(CAR_PIN1A, GPIO_FUNC_PWM);
    gpio_set_function(CAR_PIN1B, GPIO_FUNC_PWM);
    gpio_set_function(CAR_PIN2A, GPIO_FUNC_PWM);
    gpio_set_function(CAR_PIN2B, GPIO_FUNC_PWM);

    slice1a = pwm_gpio_to_slice_num(CAR_PIN1A);
    slice1b = pwm_gpio_to_slice_num(CAR_PIN1B);
    slice2a = pwm_gpio_to_slice_num(CAR_PIN2A);
    slice2b = pwm_gpio_to_slice_num(CAR_PIN2B);

    chan_1a = pwm_gpio_to_channel(CAR_PIN1A);
    chan_1b = pwm_gpio_to_channel(CAR_PIN1B);
    chan_2a = pwm_gpio_to_channel(CAR_PIN2A);
    chan_2b = pwm_gpio_to_channel(CAR_PIN2B);

    pwm_config c = pwm_get_default_config();
    pwm_config_set_clkdiv(&c, 125);  // 20ms period, steps 20000, clkdiv = 125 
    pwm_config_set_wrap(&c, 20000);
    pwm_config_set_phase_correct(&c, false);
    pwm_init(slice1a, &c, true);
    pwm_init(slice1b, &c, true);
    pwm_init(slice2a, &c, true);
    pwm_init(slice2b, &c, true);
    
    uint32_t count=0;
    uint8_t status;

    nRF24_spi_default_init(8, 9, irq_callback);
    nRF24_config_mode(RECEIVER);
    nRF24_enable_feature(FEATURE_EN_DPL, true);
    nRF24_set_RX_addr(0, addr[0], 5);
    nRF24_enable_data_pipe_dynamic_payload_length(0, true);

   
    while(1) {
        if (voice_state > 0 && voice_state < ACTION_MAX) {
            voice_action(voice_state);
            voice_action(current_direction);
            voice_state = NOISE;
        }
       
        tight_loop_contents();
    }
    
    return 0;
}

  • CMakeLists.txt


# Generated Cmake Pico project file

cmake_minimum_required(VERSION 3.13)

set(CMAKE_C_STANDARD 11)
set(CMAKE_CXX_STANDARD 17)

# Initialise pico_sdk from installed location
# (note this can come from environment, CMake cache etc)
set(PICO_SDK_PATH "/home/duser/pico/pico-sdk")

set(PICO_BOARD pico CACHE STRING "Board type")

# Pull in Raspberry Pi Pico SDK (must be before project)
include(pico_sdk_import.cmake)

if (PICO_SDK_VERSION_STRING VERSION_LESS "1.4.0")
  message(FATAL_ERROR "Raspberry Pi Pico SDK version 1.4.0 (or later) required. Your version is ${PICO_SDK_VERSION_STRING}")
endif()

project(pico_tinyML_voice_RC_CAR C CXX ASM)

# Initialise the Raspberry Pi Pico SDK
pico_sdk_init()

# Add executable. Default name is the project name, version 0.1

add_executable(pico_tinyML_voice_RC_CAR pico_tinyML_voice_RC_CAR.c )

pico_set_program_name(pico_tinyML_voice_RC_CAR "pico_guesture_ws2812")
pico_set_program_version(pico_tinyML_voice_RC_CAR "0.1")

pico_enable_stdio_uart(pico_tinyML_voice_RC_CAR 0)
pico_enable_stdio_usb(pico_tinyML_voice_RC_CAR 1)

# Add the standard library to the build
target_link_libraries(pico_tinyML_voice_RC_CAR
        pico_stdlib
        hardware_pwm)

# Add the standard include files to the build
target_include_directories(pico_tinyML_voice_RC_CAR PRIVATE
  ${CMAKE_CURRENT_LIST_DIR}
  ${CMAKE_CURRENT_LIST_DIR}/.. # for our common lwipopts or any other standard includes, if required
)

# Add any user requested libraries
add_subdirectory(nRF24L01)
target_link_libraries(pico_tinyML_voice_RC_CAR 
        nRF24L01_drv
)

add_subdirectory(ws2812)
target_link_libraries(pico_tinyML_voice_RC_CAR 
      ws2812
)

pico_add_extra_outputs(pico_tinyML_voice_RC_CAR)


ws2812:

  • ws2812.c


#include "ws2812.h"
#include "stdlib.h"
#include "string.h"

#define NUM_PIXELS 12


#define green 0x1f0000
#define red 0x001f00
#define blue 0x00001f

static inline void ws2812_program_init(PIO pio, uint sm, uint pin, float freq) {
    pio_gpio_init(pio, pin);
    pio_sm_set_consecutive_pindirs(pio, sm, pin, 1, true);

    uint offset = pio_add_program(pio, &ws2812_program);

    pio_sm_config c = ws2812_program_get_default_config(offset);
    sm_config_set_sideset_pins(&c, pin);
    sm_config_set_out_shift(&c, false, true, 24);
    sm_config_set_fifo_join(&c, PIO_FIFO_JOIN_TX);

    int cycles_per_bit = ws2812_T1 + ws2812_T2 *2;
    float div = clock_get_hz(clk_sys) / (freq * cycles_per_bit);
    sm_config_set_clkdiv(&c, div);

    pio_sm_init(pio, sm, offset, &c);
    pio_sm_set_enabled(pio, sm, true);
}

void put_grb_pixel(uint32_t pixel_grb) {
    pio_sm_put_blocking(pio0, 0, pixel_grb << 8u);
}

static inline uint32_t urgb_u32(uint8_t r, uint8_t g, uint8_t b) {
    return
            ((uint32_t) (r) << 8) |
            ((uint32_t) (g) << 16) |
            (uint32_t) (b);
}

void clear_pixel() {
    for (int i = 0; i < NUM_PIXELS; i++) put_grb_pixel(0x000000);
}

void ws2812_init(PIO pio, uint sm, uint ws2812_pin) {

    ws2812_program_init(pio, sm,  ws2812_pin, 800000);
}



  • ws2812.h



#ifndef _WS2812_H_
#define _WS2812_H_
#include <stdio.h>
#include "pico/stdlib.h"
#include "hardware/pio.h"
#include "ws2812.pio.h"
#include "hardware/clocks.h"



void ws2812_init(PIO pio, uint sm, uint ws2812_pin);
void put_grb_pixel(uint32_t pixel_grb);

#endif 

  • ws2812.pio


;
; Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
;
; SPDX-License-Identifier: BSD-3-Clause
;

.program ws2812
.side_set 1

.define public T1 2
.define public T2 2


.lang_opt python sideset_init = pico.PIO.OUT_HIGH
.lang_opt python out_init     = pico.PIO.OUT_HIGH
.lang_opt python out_shiftdir = 1

.wrap_target
bitloop:
    out x, 1       side 0 [T1 - 1] ; Side-set still takes place when instruction stalls
    jmp !x do_zero side 1 [T2 - 1] ; Branch on the bit we shifted out. Positive pulse
do_one:
    jmp  bitloop   side 1 [T2 - 1] ; Continue driving high, for a long pulse
do_zero:
    nop            side 0 [T2 - 1] ; Or drive low, for a short pulse
.wrap

% c-sdk {

%}

  • CMakeLists.txt(ws2812)


add_library(ws2812 INTERFACE)
pico_generate_pio_header(ws2812 ${CMAKE_CURRENT_LIST_DIR}/ws2812.pio)
target_sources(ws2812 INTERFACE
    ${CMAKE_CURRENT_LIST_DIR}/ws2812.c
)

target_include_directories(ws2812 INTERFACE
    ${CMAKE_CURRENT_LIST_DIR}
)

target_link_libraries(ws2812 INTERFACE
        hardware_pio
)



2024年2月1日 星期四

MCU(RP2040) voice recognition/voice commands using TinyML(Edge Impulse)

本文章介紹mcu tinyML 語音識別功能,使用Edge Impulse作機器學習,然後deployment C++ Library在Raspberry Pi Pico(RP2040, Cortex M0+)上使用。

本專案架構分成兩部份,一部分為連接INMP441 I2S microphone使用 Edge Impulse deployment的C++ Library,識別語音,另一部分接MAX98357A I2S指令說明聲音檔與連接Relay控制開關。如下圖所示。

(專案名稱:pico_tinyML_voice)

(專案名稱:pico_tinyML_voice_receiver)


本專案使用到的驅動程式,請參閱之前的文章:

  1. nRF24L01:
    [Raspberry Pi Pico] nRF24L01+ Ep. 1 : Pico-SDK C-code driver using IRQ
  2. storage driver:
    [Raspberry Pi Pico (c-sdk)] Storage: Ep 5. TinyUSB USB Mass Storage Device(USB Stick) with 2 LUNs
  3. INMP441 I2S audio recorder:
    [Raspberry Pi Pico] Audio Recorder USB device using INMP441 I2S microphone
  4. MAX98357A I2S audio player:
    [Raspberry Pi Pico (c-sdk)] PIO I2S audio player
專案pico_tinyML_voice:負責錄製訓練機器學習語音檔案與執行機器學習後推論。關於Edge Impulse匯入資料, 機器學習參數與佈署專案步驟請參閱成果影片動態說明。在專案中使用Continuous audio sampling,因此聲音擷取與推論必須平行處理,因為聲音擷取使用PIO與DMA因此不會佔用CPU,就可以達到平行運作。

專案pico_tinyML_voice_receive:透過nRF24L01接收pico_tinyML_voice聲音識別結果執行開關Relay與播放指令說明聲音檔。

成果影片



程式碼:
pico_tinyML_voice




  • pico_tinyML_voice.cpp

#include "edge-impulse-sdk/classifier/ei_run_classifier.h"

#include <stdlib.h>
#include <stdio.h>
#include <string.h>
#include "pico/stdlib.h"

#include "bsp/board.h"
#include "tusb.h"

#include "pico_storage.h"
#include "hardware/rtc.h"
#include "pico_audio_recorder.h"
#include "hardware/dma.h"
#include "nRF24L01.h"

extern bool new_read_data;
extern int16_t *fw_ptr;

#if DATA_ACQUISITION
#else
int raw_feature_get_data(size_t offset, size_t length, float *out_ptr) {
    numpy::int16_to_float(fw_ptr+offset, out_ptr, length);
    return 0;
}
#endif

//=== nRF24L01 irq
char const *addr[5] = {"0node", "1node", "2node","3node","4node"};
#define TX_PIN 17

void irq_callback(uint8_t event_type, uint8_t datapipe, uint8_t* data, uint8_t width) {
    static uint32_t ack_payload=0;
    uint8_t ack_buff[15];
      switch(event_type) {
        case EVENT_RX_DR:
            data[width]='\0';
            printf("RECV== pipe:%d, width:%d, %s\n", datapipe, width, data);
        break;
        case EVENT_TX_DS:
            gpio_put(TX_PIN, !gpio_get(TX_PIN));
            printf("event_data_sent:%d\n", datapipe);
        break;
        case EVENT_MAX_RT:
        printf("event_max_rt:%d, \n", datapipe);
        break;
    }
}

/*------------- MAIN -------------*/
int main(void)
{
  stdio_init_all();
#if DATA_ACQUISITION 
      rtc_init();
      datetime_t t = {
        .year=2024, .month=01, .day=28, 
        .dotw=6,
        .hour=10, .min=32, .sec=50
      };
     
      if (!rtc_set_datetime(&t)) printf("set rtc error\n");
        
      storage_driver_init();
      
      board_init();
      // init device stack on configured roothub port
      tud_init(BOARD_TUD_RHPORT);

#else 
    gpio_init(TX_PIN);
    gpio_set_dir(TX_PIN,true);
    // == nRF24L01 init
    nRF24_spi_default_init(8, 9, irq_callback);
    nRF24_config_mode(TRANSMITTER);
    nRF24_enable_feature(FEATURE_EN_DPL, true);
    nRF24_set_TX_addr((uint8_t*)addr[0], 5);
    nRF24_set_RX_addr(0, (uint8_t*)addr[0], 5);
    nRF24_enable_data_pipe_dynamic_payload_length(0, true);
    //== edge impulse
      run_classifier_init();
      
      EI_IMPULSE_ERROR res;
      ei_impulse_result_t result = {nullptr};
      signal_t features_signal;
      features_signal.total_length = EI_CLASSIFIER_SLICE_SIZE;
      features_signal.get_data = &raw_feature_get_data;
#endif

  inmp441_pio_init(INMP441_pio, INMP441_SM, INMP441_SD, INMP441_SCK, INMP441_SAMPLE_RATE);

  uint8_t f_idx=0;

  while (1)
  {
#if DATA_ACQUISITION
      if (get_recorder_state() == STATE_START_RECORDING) {
        inmp441_starting_recording_to_file_wav();
      }
         
      tud_task(); // tinyusb device task
#else
    if (new_read_data) {
          new_read_data = false;
          res = run_classifier_continuous(&features_signal, &result, false,true );

          if (res != EI_IMPULSE_OK) {
                  ei_printf("ERR: Failed to run classifier (%d)\n", res);
          }
          if (++f_idx >= (EI_CLASSIFIER_SLICES_PER_MODEL_WINDOW)) {
              
                for (uint16_t i = 0; i < EI_CLASSIFIER_LABEL_COUNT; i++) {
                  if (result.classification[i].value > 0.8f) 
                  { 
                    ei_printf("  %s: ", ei_classifier_inferencing_categories[i]);
                    ei_printf("%.5f\r\n", result.classification[i].value);
                    nRF24_write_payload((uint8_t*)ei_classifier_inferencing_categories[i], strlen(ei_classifier_inferencing_categories[i]));
                  } 
                }
              f_idx=0;
        }
    }
   
#endif
      tight_loop_contents();
  }

  return 0;
}

  
  • CMakeLists.txt

  # Generated Cmake Pico project file

cmake_minimum_required(VERSION 3.13)

set(CMAKE_C_STANDARD 11)
set(CMAKE_CXX_STANDARD 17)

# Initialise pico_sdk from installed location
# (note this can come from environment, CMake cache etc)
set(PICO_SDK_PATH "/home/duser/pico/pico-sdk")

set(PICO_BOARD pico CACHE STRING "Board type")

# Pull in Raspberry Pi Pico SDK (must be before project)
include(pico_sdk_import.cmake)

if (PICO_SDK_VERSION_STRING VERSION_LESS "1.4.0")
  message(FATAL_ERROR "Raspberry Pi Pico SDK version 1.4.0 (or later) required. Your version is ${PICO_SDK_VERSION_STRING}")
endif()

project(app C CXX ASM)

# Initialise the Raspberry Pi Pico SDK
pico_sdk_init()

# Add executable. Default name is the project name, version 0.1

add_executable(app 
        pico_tinyML_voice.cpp
        usb_descriptors.c)

pico_set_program_name(app "pico_tinyML_voice")
pico_set_program_version(app "0.1")

pico_enable_stdio_uart(app 1)
pico_enable_stdio_usb(app 0)

# Add the standard library to the build
target_link_libraries(app
        pico_stdlib
        hardware_adc
        hardware_dma
        )

# Add the standard include files to the build
target_include_directories(app PRIVATE
  ${CMAKE_CURRENT_LIST_DIR}
  ${CMAKE_CURRENT_LIST_DIR}/.. # for our common lwipopts or any other standard includes, if required
)

# Add any user requested libraries
target_link_libraries(app 
        )

add_subdirectory(storage_driver)
# Add any user requested libraries
target_link_libraries(app 
        tinyusb_device 
        tinyusb_board
        storage_driver
        )
add_subdirectory(pico_audio_recorder)
# Add any user requested libraries
target_link_libraries(app 
        pico_audio_recorder
        )
add_subdirectory(nRF24L01)
# Add any user requested libraries
target_link_libraries(app 
        nRF24L01_drv
        )
        
add_subdirectory(pico_voice_recognize)

pico_add_extra_outputs(app)

  

  • pico_audio_recoder.c

#include "stdio.h"
#include "pico/stdlib.h"
#include "hardware/dma.h"
#include "string.h"
#include "inttypes.h"
#include "pico_audio_recorder.pio.h"
#include "pico_audio_recorder.h"
#include "tusb.h"
#include "hardware/clocks.h"
#include "hardware/rtc.h"
#include "spi_sdmmc.h"

#if DATA_ACQUISITION
static int32_t buff1[PIO_DMA_BUFFER_SIZE/4];
static int32_t buff2[PIO_DMA_BUFFER_SIZE/4];
static int32_t *fw_ptr = buff1;
#else 
int16_t buff1[PIO_DMA_BUFFER_SIZE];
int16_t buff2[PIO_DMA_BUFFER_SIZE];
int16_t *fw_ptr = buff1;
#endif 
static int dma_read_buff1_channel;
static int dma_read_buff2_channel;

bool new_read_data=false;
static uint8_t recorder_state=STATE_STOP;

void start_stop_button_cb(uint gpio, uint32_t event_mask) {
  if (gpio == BUTTON_PIN) {
    if (event_mask == GPIO_IRQ_EDGE_RISE) { 
        gpio_acknowledge_irq(BUTTON_PIN, GPIO_IRQ_EDGE_RISE);
        switch (get_recorder_state()) {
          case STATE_STOP:
            set_recorder_state(STATE_START_RECORDING);
          break;
          case STATE_RECORDING:
            set_recorder_state(STATE_STOP);
          break;
          case STATE_START_RECORDING:
          break;
        }
     
        
        printf("press:%d\n", get_recorder_state());
    }
  
    
  }
}

void pio_irq_read_data() {
     if (pio_interrupt_get(INMP441_pio, 0)) {
        pio_interrupt_clear(INMP441_pio, 0);
        printf("irq 0:\n");
        //dma_channel_start(dma_read_buff1_channel);
     }
     if (pio_interrupt_get(INMP441_pio, 1)) {
        pio_interrupt_clear(INMP441_pio, 1);
        printf("irq:1\n");
     }
}


void dma_handler() {
//printf("dma irq1\n");
   if (dma_channel_get_irq1_status(dma_read_buff1_channel)) {
      dma_channel_acknowledge_irq1(dma_read_buff1_channel);
      dma_channel_set_write_addr(dma_read_buff1_channel, buff1, false);
      fw_ptr = buff1;
      new_read_data=true;
      
//printf("dma irq1 channel 1=======\n");
   }
   if (dma_channel_get_irq1_status(dma_read_buff2_channel)) {
      dma_channel_acknowledge_irq1(dma_read_buff2_channel);
      dma_channel_set_write_addr(dma_read_buff2_channel, buff2, false);
      fw_ptr = buff2;
      new_read_data=true;
      
//printf("=========dma irq1 channel 2\n");
   }
}

/*!
* \brief sdio memory card pio initialize
* \param pio: pio number
* \param sm state machine
* \param cmd_pin command pin
* \param clk_pin CLK pin
* \param data_pin_base data 0~4 pins(D0~D3)
* \param clk_int Integer part of the divisor
* \param clk_frac – Fractional part in 1/256ths
*/
void inmp441_pio_init(PIO pio,  uint sm, uint sd_pin, uint sideset_pin, uint32_t freq) { // sideset_pin ws_clk
  
    pio_gpio_init(pio, sd_pin);
    pio_gpio_init(pio, sideset_pin);
    pio_gpio_init(pio, sideset_pin+1);
    gpio_pull_down(sd_pin);
    //gpio_pull_up(sideset_pin);
    //gpio_pull_up(sideset_pin+1);
    
    //== INMP441 SM ==
    uint offset = pio_add_program(pio, &inmp441_program);
    pio_sm_config c = inmp441_program_get_default_config(offset);
    pio_sm_set_consecutive_pindirs(pio, sm, sd_pin, 1, false);
    pio_sm_set_consecutive_pindirs(pio, sm, sideset_pin, 2, true);
    sm_config_set_in_pins(&c, sd_pin);
    sm_config_set_set_pins(&c, sideset_pin,2);
    sm_config_set_sideset_pins(&c, sideset_pin);
    sm_config_set_in_shift(&c, false, true, INMP441_BIT_PER_SAMPLE);
    sm_config_set_fifo_join(&c, PIO_FIFO_JOIN_RX);
    float div = clock_get_hz(clk_sys)/(freq*64*2);
    sm_config_set_clkdiv(&c, div);
 
    pio_sm_init(pio, sm, offset, &c);

      // initial state machine but not run
    pio_sm_set_enabled(pio, sm, false);

    //** for test only
    uint pio_irq = pio_get_index(pio)? PIO1_IRQ_0:PIO0_IRQ_0;
    pio_set_irq0_source_enabled(pio, pis_interrupt0, true);
    //pio_set_irq0_source_enabled(pio, pis_interrupt1, true);
    irq_add_shared_handler(pio_irq, pio_irq_read_data, PICO_SHARED_IRQ_HANDLER_DEFAULT_ORDER_PRIORITY);
    irq_set_enabled(pio_irq, true);
   
    uint pio_base = (pio==pio0)?PIO0_BASE:PIO1_BASE;

    //==== READ DMA ===
    dma_read_buff1_channel = dma_claim_unused_channel(true);
    dma_read_buff2_channel = dma_claim_unused_channel(true);

    dma_channel_config dc1 = dma_channel_get_default_config(dma_read_buff1_channel);
    channel_config_set_write_increment(&dc1, true);
    channel_config_set_read_increment(&dc1, false);
    //channel_config_set_bswap(&dc1, true);
    channel_config_set_dreq(&dc1, pio_get_dreq(pio, sm, false));
    channel_config_set_chain_to(&dc1, dma_read_buff2_channel);  
    channel_config_set_transfer_data_size(&dc1, DMA_SIZE_16); //DMA_SIZE_8,16,32

#if DATA_ACQUISITION    
    dma_channel_configure(dma_read_buff1_channel,
             &dc1, buff1, (void*) (pio_base+PIO_RXF0_OFFSET),  // SDIO_DATA_READ_SM = 1
              PIO_DMA_BUFFER_SIZE>> DMA_SIZE_16, false); //DMA_SIZE_8 or 16 or 32
#else 
      dma_channel_configure(dma_read_buff1_channel,
             &dc1, buff1, (void*) (pio_base+PIO_RXF0_OFFSET),  // SDIO_DATA_READ_SM = 1
              PIO_DMA_BUFFER_SIZE, false); //DMA_SIZE_8 or 16 or 32
#endif   
   dma_channel_config dc2 = dma_channel_get_default_config(dma_read_buff2_channel);
    channel_config_set_write_increment(&dc2, true);
    channel_config_set_read_increment(&dc2, false);
    //channel_config_set_bswap(&dc2, true);
    channel_config_set_dreq(&dc2, pio_get_dreq(pio, sm, false));
    channel_config_set_chain_to(&dc2, dma_read_buff1_channel); 
    channel_config_set_transfer_data_size(&dc2, DMA_SIZE_16); //DMA_SIZE_8,16,32
#if DATA_ACQUISITION
    dma_channel_configure(dma_read_buff2_channel,
             &dc2, buff2, (void*) (pio_base+PIO_RXF0_OFFSET),  // SDIO_DATA_READ_SM = 1
              PIO_DMA_BUFFER_SIZE>> DMA_SIZE_16, false); //DMA_SIZE_8 or 16 or 32
#else 
   dma_channel_configure(dma_read_buff2_channel,
             &dc2, buff2, (void*) (pio_base+PIO_RXF0_OFFSET),  // SDIO_DATA_READ_SM = 1
              PIO_DMA_BUFFER_SIZE, false); //DMA_SIZE_8 or 16 or 32
#endif

   dma_channel_set_irq1_enabled(dma_read_buff1_channel, true);
   dma_channel_set_irq1_enabled(dma_read_buff2_channel, true);

    // Configure the processor to run dma_handler() when DMA IRQ 0 is asserted
    //irq_set_exclusive_handler(DMA_IRQ_1, dma_handler);
    irq_add_shared_handler(DMA_IRQ_1, dma_handler, PICO_SHARED_IRQ_HANDLER_DEFAULT_ORDER_PRIORITY);
    irq_set_enabled(DMA_IRQ_1, true);

   recorder_state = STATE_STOP;
   gpio_init(BUTTON_PIN);
   gpio_set_dir(BUTTON_PIN, false);
   gpio_pull_down(BUTTON_PIN);
   gpio_init(RED_PIN);
   gpio_set_dir(RED_PIN, true);
   gpio_init(GREEN_PIN);
   gpio_set_dir(GREEN_PIN, true);
   set_pin_LED(true);
  
#if DATA_ACQUISITION
   gpio_set_irq_enabled_with_callback(BUTTON_PIN, GPIO_IRQ_EDGE_RISE | GPIO_IRQ_EDGE_FALL, true, start_stop_button_cb);
#else 
   dma_channel_set_write_addr(dma_read_buff2_channel, buff2, false);
   dma_channel_set_write_addr(dma_read_buff1_channel, buff1, true);
   pio_sm_set_enabled(pio, sm, true);
#endif
}

bool write_file_wave_header(FIL *fil) {
   UINT bw;
	WAVE_HEADER wave_header;
   uint16_t channels =1;
	wave_header.riff[0] = 'R';wave_header.riff[1] = 'I';
	wave_header.riff[2] = 'F';wave_header.riff[3] = 'F';
	wave_header.size = (uint32_t)0;
	wave_header.wave[0] = 'W';wave_header.wave[1] = 'A';
	wave_header.wave[2] = 'V';wave_header.wave[3] = 'E';
	wave_header.fmt[0] = 'f';wave_header.fmt[1] = 'm';
	wave_header.fmt[2] = 't';wave_header.fmt[3] = ' ';
	wave_header.fmt_size = 16;
	wave_header.format = 1; // PCM
	wave_header.channels = channels;  // channels
	wave_header.sampleRate=INMP441_SAMPLE_RATE;  // sample rate
	wave_header.rbc = INMP441_SAMPLE_RATE*INMP441_BIT_PER_SAMPLE*channels/8;
	wave_header.bc =  INMP441_SAMPLE_RATE*channels/8;
	wave_header.bitsPerSample = INMP441_BIT_PER_SAMPLE; //bitsPerSample
	wave_header.data[0] = 'd'; wave_header.data[1] = 'a';
	wave_header.data[2] = 't'; wave_header.data[3] = 'a';
	wave_header.data_size = 0;
	if (f_write(fil, (uint8_t*)&wave_header, sizeof(wave_header), &bw)!= FR_OK) return false;
   return true;
}
bool modify_file_wave_header(FIL *fil, uint32_t data_length) {
   uint bw;
	uint32_t total_len = data_length+36;
	f_lseek(fil, 4);
	f_write(fil, (uint8_t*)&total_len, 4, &bw);
	f_lseek(fil, 40);
	f_write(fil, (uint8_t*)&data_length, 4, &bw);

   return true;
}

void set_pin_LED(bool green) {
   if (green) {
      gpio_put(GREEN_PIN, true);
      gpio_put(RED_PIN, false);
   } else {
      gpio_put(GREEN_PIN, false);
      gpio_put(RED_PIN, true);
   }
}

void inmp441_starting_recording_to_file_wav() { 
   uint32_t wav;
   uint bw;
   FIL fil;
   uint8_t filename[100];
   datetime_t t;
   FRESULT res;
   uint32_t data_length;
   FATFS fs;
   
   rtc_get_datetime(&t);
   if (tud_disconnect()) printf("disconnect tud\n");
   if (f_mount(&fs, SDMMC_PATH,1) != FR_OK) {
      tud_connect();
      return;
   }
   
   sprintf(filename, "%s/V%02d%02d%02d-%02d%02d%02d.wav", SDMMC_PATH,t.year%100,t.month,t.day,t.hour,t.min,t.sec);
   if (f_open(&fil, filename, FA_CREATE_ALWAYS|FA_WRITE) != FR_OK) {
      printf("open file error:%s\n", filename);
      
      tud_connect();
      recorder_state=STATE_STOP;
      set_pin_LED(true);
      return;
   }

   if (!write_file_wave_header(&fil)) {
      recorder_state=STATE_STOP;
      set_pin_LED(true);
      tud_connect();
      return;
   }

   recorder_state = STATE_RECORDING;
   set_pin_LED(false);
   
   pio_sm_exec(INMP441_pio, INMP441_SM, pio_encode_mov(pio_isr, pio_null)); // enpty ISR
   pio_sm_clear_fifos(INMP441_pio, INMP441_SM);
   pio_sm_exec(INMP441_pio, INMP441_SM, pio_encode_jmp(inmp441_offset_inmp441_start));
   //dma_channel_start(dma_read_buff1_channel);
   dma_channel_set_write_addr(dma_read_buff2_channel, buff2, false);
   dma_channel_set_write_addr(dma_read_buff1_channel, buff1, true);
   pio_sm_set_enabled(INMP441_pio, INMP441_SM, true);

   new_read_data=false;
   
   sleep_ms(1200);
   data_length=0;
   while (recorder_state == STATE_RECORDING) { 
      if (new_read_data) {
         new_read_data=false;
         f_write(&fil, (uint8_t*)fw_ptr, PIO_DMA_BUFFER_SIZE, &bw);
         data_length += PIO_DMA_BUFFER_SIZE;
      }
        
   } 
   modify_file_wave_header(&fil, data_length);
   f_close(&fil);
   f_unmount(SDMMC_PATH);
   
   pio_sm_set_enabled(INMP441_pio, INMP441_SM, false);
   
   
   dma_channel_abort(dma_read_buff1_channel);
   dma_channel_abort(dma_read_buff2_channel);
   
   tud_connect();
   recorder_state=STATE_STOP;
   set_pin_LED(true);
   printf("finish\n");

}

uint8_t get_recorder_state() {
   return recorder_state;
}
void    set_recorder_state(uint8_t state) {
   recorder_state = state;
}

  
  • pico_audio_recoder.h

#ifndef __PICO_AUDIO_RECORDER_
#define __PICO_AUDIO_RECORDER_
#include "hardware/pio.h"
#include "ff.h"

#define DATA_ACQUISITION   		0

#define INMP441_pio         	pio0
#define INMP441_SM          	0

#define INMP441_SCK          	18
#define INMP441_SD           	20
#define INMP441_SAMPLE_RATE  	16000
#define INMP441_BIT_PER_SAMPLE	16

#define BUTTON_PIN      		21
#define RED_PIN					16
#define GREEN_PIN				17

#if DATA_ACQUISITION
#define PIO_DMA_BUFFER_SIZE 	8192
#else 
#define PIO_DMA_BUFFER_SIZE		(16000/4)   //EI_CLASSIFIER_SLICE_SIZE
#endif

enum {
    STATE_STOP=0,
    STATE_START_RECORDING=1,
    STATE_RECORDING=2,
} RECORDER_STATE;

typedef struct _WaveHeader{
	char riff[4];
	uint32_t size;
	char wave[4];
	char fmt[4];
	uint32_t fmt_size;
	uint16_t format; //1:PCM
	uint16_t channels; // channels
	uint32_t sampleRate;  // sample rate
	uint32_t rbc;//sampleRate*bitsPerSample*channels/8
	uint16_t bc; //bitsPerSample*channels/8
	uint16_t bitsPerSample; //bitsPerSample
	char data[4];
	uint32_t data_size;
} WAVE_HEADER;

#ifdef __cplusplus
extern "C" {
#endif
void inmp441_pio_init(PIO pio,  uint sm, uint sd_pin, uint sideset_pin, uint32_t freq);
void inmp441_pio_init_no_dma(PIO pio,  uint sm, uint sd_pin, uint sideset_pin, uint32_t freq);
void inmp441_starting_recording_to_file_wav();
void inmp441_record_voice_1500ms(int16_t *features, uint32_t max_len);
uint8_t get_recorder_state();
void    set_recorder_state(uint8_t state);

void set_pin_LED(bool green);

#ifdef __cplusplus
}
#endif

#endif
  
  • pico_audio_recoder.pio

;=======  get 16 bit in 16 bit frame=======

.program inmp441
.origin 0
.side_set 2  ; ws/clk
public inmp441_start:
.wrap_target
; left channel
    set y, 2                    side 0b00  ; ignore 1+3 bit
left_idle:          
    nop                         side 0b01
    jmp y--, left_idle          side 0b00
    nop                         side 0b01  ; cycles:4

    set x, 15                   side 0b00
left_channel_loop:
    in  pins, 1                 side 0b01
    jmp x--, left_channel_loop  side 0b00

    set y, 10                    side 0b01 ; cycle:4+16+1
left_idle_1:          
    nop                         side 0b00
    jmp y--, left_idle_1        side 0b01 ;cycle:4+16+1+11=32


; right channel
    set y, 2                    side 0b10  ; ignore 1+3 bit
right_idle:          
    nop                         side 0b11
    jmp y--, right_idle         side 0b10
    nop                         side 0b11  ; cycles:4

    set x, 15                   side 0b10
right_channel_loop:
;    in  pins, 1                 side 0b11
    nop                         side 0b11
    jmp x--, right_channel_loop side 0b10

    set y, 10                    side 0b11 ; cycle:4+16+1
right_idle_1:          
    nop                         side 0b10
    jmp y--, right_idle_1       side 0b11 ;cycle:4+16+1+11=32 
.wrap


/*
;====== original =======================
.program inmp441
.origin 0
.side_set 2  ; ws/clk
public inmp441_start:
.wrap_target
; left channel
set x, 22                       side 0b00
nop                             side 0b01
nop                             side 0b00 
left_channel_loop:
    in  pins, 1                 side 0b01
    jmp x--, left_channel_loop  side 0b00
    in pins, 1                  side 0b01

    set y, 5                    side 0b00
left_idle:          
    nop                         side 0b01
    jmp y--, left_idle          side 0b00
    in NULL, 8                  side 0b01 

; right channel
set x, 22                       side 0b10
nop                             side 0b11
nop                             side 0b10 
right_channel_loop:
    in  pins, 1                 side 0b11
    jmp x--, right_channel_loop side 0b10
    in pins, 1                  side 0b11

    set y, 5                    side 0b10
right_idle:          
    nop                         side 0b11
    jmp y--, right_idle         side 0b10
    in NULL, 8                  side 0b11  
.wrap
*/

  
  • CMakeLists.txt

add_library(pico_audio_recorder INTERFACE)
pico_generate_pio_header(pico_audio_recorder ${CMAKE_CURRENT_LIST_DIR}/pico_audio_recorder.pio)
target_sources(pico_audio_recorder INTERFACE
    ${CMAKE_CURRENT_LIST_DIR}/pico_audio_recorder.c
)

target_include_directories(pico_audio_recorder INTERFACE
    ${CMAKE_CURRENT_LIST_DIR}
)

target_link_libraries(pico_audio_recorder INTERFACE
        hardware_dma
        hardware_pio
        hardware_rtc
        pico_stdlib
)
  


pico_tinyML_voce_receive


  • pico_tinyML_voice_receiver.c
#include <stdio.h>
#include "pico/stdlib.h"
#include "nRF24L01.h"
#include "string.h"

#include "ff.h"
#include "pico_storage.h"
#include "i2s_pio_dma/i2s_pio_dma.h"
#define RELAY_PIN   19


uint8_t addr[5][5] = {"0node", "1node", "2node","3node","4node"};

enum {
    NOISE=1,
    TURN_ON=2,
    TURN_OFF=3,
    HELLO=4,
};

uint8_t voice_state = 0;



void irq_callback(uint8_t event_type, uint8_t datapipe, uint8_t* data, uint8_t width) {
    static uint32_t ack_payload=0;
    uint8_t ack_buff[15];
      switch(event_type) {
        case EVENT_RX_DR:
            data[width]='\0';
            printf("RECV== pipe:%d, width:%d, %s\n", datapipe, width, data);
  
            
            if (strcmp(data, "noise")==0) voice_state=NOISE;
            if (strcmp(data, "turn_on")==0) voice_state=TURN_ON;
            if (strcmp(data, "turn_off")==0) voice_state=TURN_OFF;
            if (strcmp(data, "hello")==0) voice_state=HELLO;
        break;
        case EVENT_TX_DS:
            printf("event_data_sent:%d\n", datapipe);
        break;
        case EVENT_MAX_RT:
            printf("EVENT_MAX_RT:%d\n", datapipe);
        break;
    }
}

#define NUM_PIXELS 12
FATFS fs;
FIL fil;
char hello_wav[] = SDMMC_PATH"/inst.wav";

void voice_action(uint8_t stat) {
    switch(stat) {
        case TURN_ON:
            gpio_put(RELAY_PIN, true);
        break;
        case TURN_OFF:
            gpio_put(RELAY_PIN, false);
        break;
        case HELLO:
             
            
            i2s_playWave(hello_wav);
        break;
        default:
        break;
    }
}




int main()
{
    FRESULT res;
    UINT br;
    
    stdio_init_all(); 
    storage_driver_init();

    i2s_pio_init(pio0, 0, 16, 18);
    res = f_mount(&fs, SDMMC_PATH,1);
    if (res != FR_OK) {
        printf("mount sd error\n");
        return 0;
    }  

   


    gpio_init(RELAY_PIN);
    gpio_set_dir(RELAY_PIN, true);
    uint32_t count=0;
    uint8_t status;


    nRF24_spi_default_init(8, 9, irq_callback);

    nRF24_config_mode(RECEIVER);
    nRF24_enable_feature(FEATURE_EN_DPL, true);

    nRF24_set_RX_addr(0, addr[0], 5);
    nRF24_enable_data_pipe_dynamic_payload_length(0, true);

  

    while(1) {
        if (voice_state == TURN_ON || voice_state == TURN_OFF || voice_state == HELLO) {
            voice_action(voice_state);
        }
       
        tight_loop_contents();
    }
    
    return 0;
}

  

  • CMakeLists.txt

# Generated Cmake Pico project file

cmake_minimum_required(VERSION 3.13)

set(CMAKE_C_STANDARD 11)
set(CMAKE_CXX_STANDARD 17)

# Initialise pico_sdk from installed location
# (note this can come from environment, CMake cache etc)
set(PICO_SDK_PATH "/home/duser/pico/pico-sdk")

set(PICO_BOARD pico CACHE STRING "Board type")

# Pull in Raspberry Pi Pico SDK (must be before project)
include(pico_sdk_import.cmake)

if (PICO_SDK_VERSION_STRING VERSION_LESS "1.4.0")
  message(FATAL_ERROR "Raspberry Pi Pico SDK version 1.4.0 (or later) required. Your version is ${PICO_SDK_VERSION_STRING}")
endif()

project(pico_tinyML_voice_receiver C CXX ASM)

# Initialise the Raspberry Pi Pico SDK
pico_sdk_init()

# Add executable. Default name is the project name, version 0.1

add_executable(pico_tinyML_voice_receiver pico_tinyML_voice_receiver.c )

pico_set_program_name(pico_tinyML_voice_receiver "pico_guesture_ws2812")
pico_set_program_version(pico_tinyML_voice_receiver "0.1")

pico_enable_stdio_uart(pico_tinyML_voice_receiver 0)
pico_enable_stdio_usb(pico_tinyML_voice_receiver 1)

# Add the standard library to the build
target_link_libraries(pico_tinyML_voice_receiver
        pico_stdlib)

# Add the standard include files to the build
target_include_directories(pico_tinyML_voice_receiver PRIVATE
  ${CMAKE_CURRENT_LIST_DIR}
  ${CMAKE_CURRENT_LIST_DIR}/.. # for our common lwipopts or any other standard includes, if required
)

# Add any user requested libraries
target_link_libraries(pico_tinyML_voice_receiver 
        )

add_subdirectory(nRF24L01)
target_link_libraries(pico_tinyML_voice_receiver 
        nRF24L01_drv
)

add_subdirectory(storage_driver)
# Add any user requested libraries
target_link_libraries(pico_tinyML_voice_receiver 
        storage_driver
        )
add_subdirectory(i2s_pio_dma)
# Add any user requested libraries
target_link_libraries(pico_tinyML_voice_receiver 
        i2s_pio_dma
        )

pico_add_extra_outputs(pico_tinyML_voice_receiver)