prettyprint

2024年1月14日 星期日

Magic Wand--TinyML(Edge Impulse)&MPU6050&nRF24L01: Using Raspberry Pi Pico for gestures and machine learning

本文章介紹結合Raspberry Pi Pico和Edge Impulse實現tinyML。使用MPU6050在edge impulse下進行machine learing,將學習後model(features)在Raspberry Pi Pico下執行。

在raspberry Pi Pico偵測手勢樣態(circle, left-right, up-down and idel),透nRF25L01傳送到另一端的Raspberry Pi Pico在WS2812顯示手勢樣態。如下圖


一、擷取Training Dataset:

本實驗的開發環境為Debian Linux。
  1. 如何安裝edge-impulse-data-forwarder擷取資料到Edeg Impulse Studio請參閱下列文件說明連結:
    https://docs.edgeimpulse.com/docs/
  2. mpu6050的raspberry Pi Pico驅動程式附於文末。擷取x,y,z的加速度值,擷取的速度約為95Hz。


  3. 擷取Training Dataset分為四個型態:circle, idle, left-right and up-down,每次擷取10秒鐘。




  4. 每次擷取Testing Dataset為2秒:

二、Impulse Design:
  1. Create Impulse參數如下圖所示:


  2. spectral features:(parameters)

     
  3. Classifier:


  4. Model testing:


  5. Deployment:
    匯出C++ library壓縮檔,解壓縮後複製所有檔案到專案底下,在root 的CMakeLists.txt加入sub directory

三、使用edge impulse學習的成果

  1. #include "edge-impulse-sdk/classifier/ei_run_classifier.h"
  2. 擷取資料到features array:

  3. 進行資料分類:
    res = run_classifier(&features_signal, &result, false /* debug */);
  4. 取出分類判定值:
    程式中採取分類值大於0.8則判定是該分類。
詳細程式碼附於文末:

四、成果影片


五、程式碼

有關nRF24L01與WS2812驅動程式碼,請參閱前面幾篇文章的說明。

  • Machine Leaning Side


  • pico_mup6050_geuest.cpp

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

#include "pico/stdlib.h"
#include "nRF24L01.h"
#include "string.h"
#include "mpu6050.h"

char const *addr[5] = {"0node", "1node", "2node","3node","4node"};
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:
            printf("event_data_sent:%d\n", datapipe);
        break;
        case EVENT_MAX_RT:
        printf("event_max_rt:%d, \n", datapipe);
        break;
    }
}

void training_gesture() {
    int16_t rax, ray, raz;
    int16_t rgx, rgy, rgz;
    
    while (1) {
        mpu6050_get_accel_raw(&rax, &ray, &raz);
        mpu6050_get_gyro_raw(&rgx, &rgy, &rgz);
        //printf("%d,%d,%d, %d,%d,%d\n", rax, ray, raz, rgx, rgy, rgz);
        printf("%d,%d,%d\n",  rax, ray, raz);
        sleep_ms(10);
   }
}


static float features[EI_CLASSIFIER_DSP_INPUT_FRAME_SIZE];
    // Copy raw features here (e.g. from the 'Model testing' page)

int raw_feature_get_data(size_t offset, size_t length, float *out_ptr) {
    memcpy(out_ptr, features + offset, length * sizeof(float));
    return 0;
}

int main()
{
    stdio_init_all();
    uint32_t count=0;
    uint8_t status;
    int16_t rax, ray, raz;
    int16_t rgx, rgy, rgz;

    gpio_init(PICO_DEFAULT_LED_PIN);
    gpio_set_dir(PICO_DEFAULT_LED_PIN, true);

    mpu6050_init();
    mpu6050_config_accel(ACCEL_CONFIG_2G);
    mpu6050_config_gyro(GYRO_CONFIG_250);

    nRF24_spi_default_init(20, 21, 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);

    //training_gesture();  // uncomment when capture training dataset

    EI_IMPULSE_ERROR res;
    ei_impulse_result_t result = {nullptr};
    signal_t features_signal;
    features_signal.total_length = sizeof(features) / sizeof(features[0]);
    features_signal.get_data = &raw_feature_get_data;

    while(1) {
        gpio_put(PICO_DEFAULT_LED_PIN, true);
        for (int i=0; i < EI_CLASSIFIER_DSP_INPUT_FRAME_SIZE; i+=3) {
            mpu6050_get_accel_raw(&rax, &ray, &raz);
            mpu6050_get_gyro_raw(&rgx, &rgy, &rgz);
            features[i] = rax;
            features[i+1] = ray;
            features[i+2] = raz;
            sleep_ms(10);
        }
        gpio_put(PICO_DEFAULT_LED_PIN, false);
printf("==%d, %d, %d==\n", rax, ray,rax);
        res = run_classifier(&features_signal, &result, false /* debug */);
        if (res != EI_IMPULSE_OK) {
            ei_printf("ERR: Failed to run classifier (%d)\n", res);
        }
        for (uint16_t i = 0; i < EI_CLASSIFIER_LABEL_COUNT; i++) {
            ei_printf("  %s: ", ei_classifier_inferencing_categories[i]);
            ei_printf("%.5f\r\n", result.classification[i].value);
            if (result.classification[i].value > 0.8f) {
                nRF24_write_payload((uint8_t*)ei_classifier_inferencing_categories[i], strlen(ei_classifier_inferencing_categories[i]));
            }
        }
        sleep_ms(2000);
        

    }

    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_mpu6050_gesture.cpp )


pico_set_program_name(app "pico_mpu6050_gesture")
pico_set_program_version(app "0.1")

pico_enable_stdio_uart(app 0)
pico_enable_stdio_usb(app 1)

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

# 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 
        hardware_i2c
        )

add_subdirectory(MPU6050_drv)
target_link_libraries(app
        MPU6050_drv
)  

add_subdirectory(nRF24L01)
target_link_libraries(app 
        nRF24L01_drv
)
add_subdirectory(edge_impulse)

pico_add_extra_outputs(app)


  • mpu6050.c



#include "mpu6050.h"

static mpu6050_t mpu6050;

static float mpu6050_dps_per_digit[] = {
    .007633f,  .015267f, .030487f, .060975f
}; // 1/131 LSB/°/s, 1/65.5 LSB/°/s, 1/32.8 LSB/°/s, 1/16.4 LSB/°/s


static float mpu6050_range_per_digit[] = {
    .000061f, .000122f, .000244f, .0004882f
}; //1/16384 LSB/g(2G), 1/8192 LSB/g(4G), 1/4096 LSB/g(8G), 1/2048 LSB/g(16G)


void mpu6050_read_register(uint8_t reg, uint8_t *value, uint8_t len) {
    uint8_t buf;
    buf = reg;
    i2c_write_blocking(MPU6050_i2c, MPU6050_ADDRESS, &buf, 1, true);
    i2c_read_blocking(MPU6050_i2c, MPU6050_ADDRESS, value, len, false);
}

void mpu6050_reset() {
    uint8_t buf[] = {0x6B, 0x80};
    i2c_write_blocking(MPU6050_i2c, MPU6050_ADDRESS, buf, 2, false);
    sleep_ms(10);
    buf[1] = 0x00;
    i2c_write_blocking(MPU6050_i2c, MPU6050_ADDRESS, buf, 2, false);
}

void mpu6050_config_gyro(uint8_t gyro_config) {
    uint8_t buf[2];
    buf[0] = MPU6050_GYRO_CONFIG;
    buf[1] = gyro_config << 3;
    i2c_write_blocking(MPU6050_i2c, MPU6050_ADDRESS, buf, 2, false);
    mpu6050.gyro_config = gyro_config; 
}

void mpu6050_config_accel(uint8_t accel_config) {
    uint8_t buf[2];
    uint8_t reg;
    mpu6050_read_register(MPU6050_ACCEL_CONFIG, &reg, 1);
    reg &= 0b11100111;
    buf[0] = MPU6050_ACCEL_CONFIG;
    buf[1] = accel_config << 3 | reg;
    i2c_write_blocking(MPU6050_i2c, MPU6050_ADDRESS, buf, 2, false);
    mpu6050.accel_config = accel_config;
}

/*
0 = 260 Hz, 0 ms / 256 Hz, 0.98 ms, 8 kHz
1 = 184 Hz, 2.0 ms / 188 Hz, 1.9 ms, 1 kHz
2 = 94 Hz, 3.0 ms / 98 Hz, 2.8 1 ms, kHz
3 = 44 Hz, 4.9 ms / 42 Hz, 4.8 1 ms, kHz
4 = 21 Hz, 8.5 ms / 20 Hz, 8.3 1 ms, kHz
5 = 10 Hz, 13.8 ms / 10 Hz, 13.4 ms, 1 kHz
6 = 5 Hz, 19.0 ms / 5 Hz, 18.6 1 ms, kHz
7 = RESERVED / RESERVED, 8 kHz
3-bit unsigned value. Configures the DLPF setting
*/
void mpu6050_config_DLPF(uint8_t dlpf) {
    uint8_t buf[2];
    uint8_t reg;
    mpu6050_read_register(MPU6050_CONFIG, &reg, 1);
    reg &= 0b11111000;
    buf[0] = MPU6050_CONFIG;
    buf[1] = (dlpf&0b00000111) | reg;
    i2c_write_blocking(MPU6050_i2c, MPU6050_ADDRESS, buf, 2, false);
}

/*
0 = Reset
1 = On @ 5 Hz
2 = On @ 2.5 Hz
3 = On @ 1.25 Hz
4 = On @ 0.63 Hz
7 = Hold
*/
void mpu6050_config_DHPF(uint8_t dhpf) {
    uint8_t buf[2];
    uint8_t reg;
    mpu6050_read_register(MPU6050_ACCEL_CONFIG, &reg, 1);
    reg &= 0b11111000;
    buf[0] = MPU6050_ACCEL_CONFIG;
    buf[1] = (dhpf&0b00000111) | reg;
    i2c_write_blocking(MPU6050_i2c, MPU6050_ADDRESS, buf, 2, false);        
}

void mpu6050_init() {
    // init I2C
    i2c_init(MPU6050_i2c, 400 * 1000);
    gpio_set_function(MPU6050_SDA_PIN, GPIO_FUNC_I2C);
    gpio_set_function(MPU6050_SCL_PIN, GPIO_FUNC_I2C);
    gpio_pull_up(MPU6050_SDA_PIN);
    gpio_pull_up(MPU6050_SCL_PIN);

    mpu6050_reset();
    mpu6050_config_gyro(GYRO_CONFIG_250);
    mpu6050_config_accel(ACCEL_CONFIG_2G);

    mpu6050.gyro_cali.xg_calibration=0;
    mpu6050.gyro_cali.yg_calibration=0;
    mpu6050.gyro_cali.zg_calibration=0;
}

void mpu6050_get_accel_raw(int16_t *ax, int16_t *ay, int16_t *az) {
    uint8_t buf[6];
    buf[0]=MPU6050_ACCEL_OUT;

    i2c_write_blocking(MPU6050_i2c, MPU6050_ADDRESS, buf, 1, true);
    i2c_read_blocking(MPU6050_i2c, MPU6050_ADDRESS, buf, 6, false);

    *ax = (int16_t)(buf[0] << 8 | buf[1]);
    *ay = (int16_t)(buf[2] << 8 | buf[3]);
    *az = (int16_t)(buf[4] << 8 | buf[5]);
}

void mpu6050_get_gyro_raw(int16_t *gx, int16_t *gy, int16_t *gz) {
    uint8_t buf[6];
    buf[0]=MPU6050_GYRO_OUT;

    i2c_write_blocking(MPU6050_i2c, MPU6050_ADDRESS, buf, 1, true);
    i2c_read_blocking(MPU6050_i2c, MPU6050_ADDRESS, buf, 6, false);

    *gx = (int16_t)(buf[0] << 8 | buf[1]);
    *gy = (int16_t)(buf[2] << 8 | buf[3]);
    *gz = (int16_t)(buf[4] << 8 | buf[5]);
    
}

void mpu6050_calibration(uint8_t time) {
    int32_t x_sum=0, y_sum=0, z_sum=0;
    uint32_t cnt=0;
    int16_t gx, gy, gz;

    absolute_time_t timeout = make_timeout_time_ms(time*1000);
    while (absolute_time_diff_us(get_absolute_time(), timeout) > 0) { 
        cnt++;
        mpu6050_get_gyro_raw(&gx,&gy,&gz);
        x_sum += gx; y_sum += gy; z_sum += gz;
        sleep_ms(1);
    }
    mpu6050.gyro_cali.xg_calibration=(float)(x_sum)/cnt*mpu6050_dps_per_digit[mpu6050.gyro_config];
    mpu6050.gyro_cali.yg_calibration=(float)(y_sum)/cnt*mpu6050_dps_per_digit[mpu6050.gyro_config];
    mpu6050.gyro_cali.zg_calibration=(float)(z_sum)/cnt*mpu6050_dps_per_digit[mpu6050.gyro_config];
}

void mpu6050_init_with_calibration(uint8_t gyro_config, uint8_t accel_config, uint8_t time) {
    // init I2C
    i2c_init(MPU6050_i2c, 400 * 1000);
    gpio_set_function(MPU6050_SDA_PIN, GPIO_FUNC_I2C);
    gpio_set_function(MPU6050_SCL_PIN, GPIO_FUNC_I2C);
    gpio_pull_up(MPU6050_SDA_PIN);
    gpio_pull_up(MPU6050_SCL_PIN);

    mpu6050_reset();
    mpu6050_config_gyro(gyro_config);
    mpu6050_config_accel(accel_config);
    mpu6050_calibration(time);
}

void mpu6050_get_temp(float *temp) {
    uint8_t buf[6];
    buf[0]=MPU6050_TEMP_OUT;

    i2c_write_blocking(MPU6050_i2c, MPU6050_ADDRESS, buf, 1, true);
    i2c_read_blocking(MPU6050_i2c, MPU6050_ADDRESS, buf, 2, false);
    *temp = (int16_t)(buf[0] << 8 | buf[1])/340.0f + 36.53f;
}

void mpu6050_get_accel(float *ax, float *ay, float *az) {
    uint8_t buf[6];
    
    buf[0]=MPU6050_ACCEL_OUT;

    i2c_write_blocking(MPU6050_i2c, MPU6050_ADDRESS, buf, 1, true);
    i2c_read_blocking(MPU6050_i2c, MPU6050_ADDRESS, buf, 6, false);

    *ax = (int16_t)(buf[0] << 8 | buf[1])*mpu6050_range_per_digit[mpu6050.accel_config];
    *ay = (int16_t)(buf[2] << 8 | buf[3])*mpu6050_range_per_digit[mpu6050.accel_config];
    *az = (int16_t)(buf[4] << 8 | buf[5])*mpu6050_range_per_digit[mpu6050.accel_config];

}
void mpu6050_get_gyro(float *gx, float *gy, float *gz) {
    uint8_t buf[6];
    
    buf[0]=MPU6050_GYRO_OUT;

    i2c_write_blocking(MPU6050_i2c, MPU6050_ADDRESS, buf, 1, true);
    i2c_read_blocking(MPU6050_i2c, MPU6050_ADDRESS, buf, 6, false);

    *gx = (int16_t)(buf[0] << 8 | buf[1])*mpu6050_dps_per_digit[mpu6050.gyro_config]-mpu6050.gyro_cali.xg_calibration;
    *gy = (int16_t)(buf[2] << 8 | buf[3])*mpu6050_dps_per_digit[mpu6050.gyro_config]-mpu6050.gyro_cali.yg_calibration;
    *gz = (int16_t)(buf[4] << 8 | buf[5])*mpu6050_dps_per_digit[mpu6050.gyro_config]-mpu6050.gyro_cali.zg_calibration;
}

/*
[7] INT_LEVEL
[6] INT_OPEN
[5] LATCH_INT_EN
[4] INT_RD_CLEAR
[3] FSYNC_INT_LEVEL
[2] FSYNC_INT_EN
[1] I2C_BYPASS_EN
[0] CLKOUT_EN
INT_LEVEL:  0, the logic level for the INT pin is active high.
            1, the logic level for the INT pin is active low.
INT_OPEN:   0, the INT pin is configured as push-pull.
            1, the INT pin is configured as open drain.
LATCH_INT_EN:0, the INT pin emits a 50us long pulse.
             1, the INT pin is held high until the interrupt is cleared.
INT_RD_CLEAR:0, interrupt status bits are cleared only by reading INT_STATUS
             1, interrupt status bits are cleared on any read operation.
FSYNC_INT_LEVEL: 0, the logic level for the FSYNC pin is active high.
                 1, the logic level for the FSYNC pin is active low.
FSYNC_INT_EN: 0, this bit disables the FSYNC pin from causing an interrupt to the host processor.
              1, this bit enables the FSYNC pin to be used as an interrupt to the host processor.

I2C_BYPASS_EN: 1 and I2C_MST_EN 0, the host application processor will be able to directly access the auxiliary I2C bus of the MPU-60X0.
               0, the host application processor will not be able to directly access the auxiliary I2C bus of the MPU-60X0 regardless of the state of I2C_MST_EN (Register 106 bit[5]).
*/
void mpu6050_int_pin_config(uint8_t config) {
    uint8_t buf[2] = {MPU6050_INT_PIN_CONFIG, config};
    i2c_write_blocking(MPU6050_i2c, MPU6050_ADDRESS, buf, 2, false);
}

/*
[7] FF_EN
[6] MOT_EN
[5] ZMOT_EN
[4] FIFO_OFLOW_EN
[3] I2C_MST_INT_EN
[2] PLL_RDY_INT_EN
[1] DMP_INT_EN
[0] RATA_RDY_EN
*/
void mpu6050_int_enable(uint8_t config) {
    uint8_t buf[2] = {MPU6050_INT_ENABLE, config};
    i2c_write_blocking(MPU6050_i2c, MPU6050_ADDRESS, buf, 2, false);
}

/*
[7] FF_INT
[6] MOT_INT
[5] ZMOT_INT
[4] FIFO_OFLOW_INT
[3] I2C_MST_INT
[2] PLL_RDY_INT
[1] DMP_INT
[0] RAW_RDY_INT
Each bit will clear after the register is read.
*/
void mpu6050_read_int_status(uint8_t *status) {
    uint8_t buf;
    buf = MPU6050_INT_STATUS;
    i2c_write_blocking(MPU6050_i2c, MPU6050_ADDRESS, &buf, 1, true);
    i2c_read_blocking(MPU6050_i2c, MPU6050_ADDRESS, &buf, 1, false);
    *status = buf;
}

/*
[7] MOT_XNEG
[6] MOT_XPOS
[5] MOT_YNEG
[4] MOT_YPOS
[3] MOT_ZNEG
[2] MOT_ZPOS
[0] MOT_ZRMOT
Reading this register clears the Motion detection bits. However, the MOT_ZRMOT bit does not clear until Zero Motion is no longer detected.
*/
void mpu6050_read_mot_detect_status(uint8_t *status) {
    uint8_t buf;
    buf = MPU6050_MOT_DETECT_STATUS;
    i2c_write_blocking(MPU6050_i2c, MPU6050_ADDRESS, &buf, 1, true);
    i2c_read_blocking(MPU6050_i2c, MPU6050_ADDRESS, &buf, 1, false);
    *status = buf;
}

void mpu6050_set_motion_detection_threshold(uint8_t threshold)
{
    uint8_t buf[2] = {MPU6050_MOT_THR, threshold};
    i2c_write_blocking(MPU6050_i2c, MPU6050_ADDRESS, buf, 2, false);
}

void mpu6050_set_motion_detection_duration(uint8_t duration)
{
    uint8_t buf[2] = {MPU6050_MOT_DUR, duration};
    i2c_write_blocking(MPU6050_i2c, MPU6050_ADDRESS, buf, 2, false);
}

void mpu6050_set_zero_motion_detection_threshold(uint8_t threshold)
{
    uint8_t buf[2] = {MPU6050_ZRMOT_THR, threshold};
    i2c_write_blocking(MPU6050_i2c, MPU6050_ADDRESS, buf, 2, false);
}

void mpu6050_set_zero_motion_detection_duration(uint8_t duration)
{
    uint8_t buf[2] = {MPU6050_ZRMOT_DUR, duration};
    i2c_write_blocking(MPU6050_i2c, MPU6050_ADDRESS, buf, 2, false);
}

void mpu6050_set_free_fall_detection_threshold(uint8_t threshold)
{
    uint8_t buf[2] = {MPU6050_FF_THR, threshold};
    i2c_write_blocking(MPU6050_i2c, MPU6050_ADDRESS, buf, 2, false);
}

void mpu6050_set_free_fall_detection_duration(uint8_t duration)
{
    uint8_t buf[2] = {MPU6050_FF_DUR, duration};
    i2c_write_blocking(MPU6050_i2c, MPU6050_ADDRESS, buf, 2, false);
}

  • mpu6050.h


#ifndef __MPU6050_H_
#define __MPU6050_H_


#include "pico/stdlib.h"
#include "hardware/i2c.h"

#define MPU6050_ADDRESS         0x68
#define MPU6050_i2c             i2c0
#define MPU6050_SDA_PIN         4
#define MPU6050_SCL_PIN         5

typedef struct  {
    uint8_t gyro_config;
    uint8_t accel_config;
    struct gyro_cali_t {
        float xg_calibration;
        float yg_calibration;
        float zg_calibration;
    } gyro_cali;
}mpu6050_t;

enum {
    GYRO_CONFIG_250 =           0,
    GYRO_CONFIG_500 =           1,
    GYRO_CONFIG_1000=           2,
    GYRO_CONFIG_2000=           3,
};

enum {
    ACCEL_CONFIG_2G =           0,
    ACCEL_CONFIG_4G =           1,
    ACCEL_CONFIG_8G =           2,
    ACCEL_CONFIG_16G=           3,
};

//registers
#define MPU6050_SMPRT_DIV       0x19
#define MPU6050_CONFIG          0x1A
#define MPU6050_GYRO_CONFIG     0x1B
#define MPU6050_ACCEL_CONFIG    0x1C
#define MPU6050_ACCEL_OUT       0x3B
#define MPU6050_ACCEL_XOUT      0x3B
#define MPU6050_ACCEL_YOUT      0x3D
#define MPU6050_ACCEL_ZOUT      0x3F
#define MPU6050_TEMP_OUT        0x41
#define MPU6050_GYRO_OUT        0x43
#define MPU6050_GYRO_XOUT       0x43
#define MPU6050_GYRO_YOUT       0x45
#define MPU6050_GYRO_ZOUT       0x47

enum {
    INT_LEVEL=                  1<<7,
    INT_OPEN=                   1<<6,
    LATCH_INT_EN=               1<<5,
    INT_RD_CLEAR=               1<<4,
    FSYNC_INT_LEVEL=            1<<3,
    FSYNC_INT_EN=               1<<2,
    I2C_BYPASS_EN=              1<<1,
    CLKOUT_EN=                  1<<0,
};
#define MPU6050_INT_PIN_CONFIG  0x37

enum {
    FF_EN=                      1<<7,
    MOT_EN=                     1<<6,
    ZMOT_EN=                    1<<5,
    FIFO_OFLOW_EN=              1<<4,
    I2C_MST_INT_EN=             1<<3,
    PLL_RDY_INT_EN=             1<<2,
    DMP_INT_EN=                 1<<1,
    DATA_RDY_EN=                1<<0,
};
#define MPU6050_INT_ENABLE      0x38

enum {
    FF_INT=                     1<<7,
    MOT_INT=                    1<<6,
    ZMOT_INT=                   1<<5,
    FIFO_OFLOW_INT=             1<<4,
    I2C_MST_INT=                1<<3,
    PLL_RDY_INT=                1<<2,
    DMP_INT=                    1<<1,
    DATA_RDY_INT=                1<<0,
};
#define MPU6050_INT_STATUS      0x3A

#define MPU6050_MOT_THR         0x1F
#define MPU6050_MOT_DUR         0x20
#define MPU6050_ZRMOT_THR       0x21
#define MPU6050_ZRMOT_DUR       0x22
#define MPU6050_FF_THR          0x1D
#define MPU6050_FF_DUR          0x1E


enum {
    MOT_XNEG=                   1<<7,
    MOT_XPOS=                   1<<6,
    MOT_YNEG=                   1<<5,
    MOT_YPOS=                   1<<4,
    MOT_ZNEG=                   1<<3,
    MOT_ZPOS=                   1<<2,
    MOT_ZRMOT=                  1<<0,
};
#define MPU6050_MOT_DETECT_STATUS 0x61 

#ifdef __cplusplus
extern "C" {
#endif

void mpu6050_init();
void mpu6050_init_with_calibration(uint8_t gyro_config, uint8_t accel_config, uint8_t time);
void mpu6050_get_gyro(float *gx, float *gy, float *gz);
void mpu6050_get_accel(float *ax, float *ay, float *az);
void mpu6050_get_temp(float *temp);
void mpu6050_config_gyro(uint8_t gyro_config);
void mpu6050_config_accel(uint8_t accel_config);
void mpu6050_int_pin_config(uint8_t config);
void mpu6050_int_enable(uint8_t config);
void mpu6050_read_int_status(uint8_t *status);
void mpu6050_read_mot_detect_status(uint8_t *status);

void mpu6050_set_motion_detection_threshold(uint8_t threshold);
void mpu6050_set_motion_detection_duration(uint8_t duration);
void mpu6050_set_zero_motion_detection_threshold(uint8_t threshold);
void mpu6050_set_zero_motion_detection_duration(uint8_t duration);
void mpu6050_set_free_fall_detection_threshold(uint8_t threshold);
void mpu6050_set_free_fall_detection_duration(uint8_t duration);
void mpu6050_read_register(uint8_t reg, uint8_t *value, uint8_t len);
void mpu6050_config_DLPF(uint8_t dlpf);
void mpu6050_config_DHPF(uint8_t dhpf);

void mpu6050_get_accel_raw(int16_t *ax, int16_t *ay, int16_t *az);
void mpu6050_get_gyro_raw(int16_t *gx, int16_t *gy, int16_t *gz);

#ifdef __cplusplus
}
#endif

#endif

  • WS2812 Display Side:


  • pico_guesture_ws2812.c


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

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

enum {
    CIRCLE=1,
    LEFT_RIGHT=2,
    UP_DOWN=3,
};

uint8_t ws2812_stat = 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);
  
            //ws2812_stat=0;
            if (strcmp(data, "circle")==0) ws2812_stat=CIRCLE;
            if (strcmp(data, "left-right")==0) ws2812_stat=LEFT_RIGHT;
            if (strcmp(data, "up-down")==0) ws2812_stat=UP_DOWN;
        break;
        case EVENT_TX_DS:
            printf("event_data_sent:%d\n", datapipe);
        break;
        case EVENT_MAX_RT:
        break;
    }
}

#define NUM_PIXELS 12
void play_ws2812(uint8_t stat) {
    switch(stat) {
        case CIRCLE:
            for (int i=0; i < NUM_PIXELS; i+=2) {
                for (int j=0; j < NUM_PIXELS; j++) { 
                    if (i == j || (i+1) == j) put_grb_pixel(0x000000);
                    else  put_grb_pixel(0x00000f);
                }
                sleep_ms(100);
            }
        break;
        case LEFT_RIGHT:
            for (int i=0; i < NUM_PIXELS; i++) {
                if (i == 3) put_grb_pixel(0x000f00);
                else put_grb_pixel(0x000000);
            }
            sleep_ms(100);
            for (int i=0; i < NUM_PIXELS; i++) {
                if (i == 9) put_grb_pixel(0x000f00);
                else put_grb_pixel(0x000000);
            }
            sleep_ms(100);
        break;
        case UP_DOWN:
            for (int i=0; i < NUM_PIXELS; i++) {
                if (i == 0) put_grb_pixel(0x0f0000);
                else put_grb_pixel(0x000000);
            }
            sleep_ms(100);
            for (int i=0; i < NUM_PIXELS; i++) {
                if (i == 6) put_grb_pixel(0x0f0000);
                else put_grb_pixel(0x000000);
            }
            sleep_ms(100);
        break;
        default:
        break;
    }
}
int main()
{
    stdio_init_all();
    uint32_t count=0;
    uint8_t status;
    nRF24_spi_default_init(20, 21, 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);

    ws2812_init(pio0, 0, 15);

    while(1) {
        if (ws2812_stat == CIRCLE || ws2812_stat == LEFT_RIGHT || ws2812_stat == UP_DOWN) {
            play_ws2812(ws2812_stat);
        }
       
        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_guesture_ws2812 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_guesture_ws2812 pico_guesture_ws2812.c )

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

pico_enable_stdio_uart(pico_guesture_ws2812 0)
pico_enable_stdio_usb(pico_guesture_ws2812 1)

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

# Add the standard include files to the build
target_include_directories(pico_guesture_ws2812 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_guesture_ws2812 
        )

add_subdirectory(nRF24L01)
target_link_libraries(pico_guesture_ws2812 
        nRF24L01_drv
)

add_subdirectory(ws2812)
target_link_libraries(pico_guesture_ws2812 
      ws2812
)

pico_add_extra_outputs(pico_guesture_ws2812)


沒有留言:

張貼留言