2025-10-10 08:45:19 [显示全部楼层]
53浏览
查看: 53|回复: 0

[K10项目分享] 行空板 K10小智:用语音指挥会说会跑会抓的智能车

[复制链接]
本帖最后由 云天 于 2025-10-10 08:45 编辑

【项目起源】  
       前不久,我在 DFRobot 论坛发过一个“能听会说的小车”雏形(https://mc.dfrobot.com.cn/thread-398314-1-1.html),但只用了行空板k10的四个引脚。这次我把金手指引出的“引脚”通过IO扩展板接入 3个L298N(DF-MD V1.3)电机驱动器,控制小车真正做到了“说一句,动一路”——前进、后退、左转、右转、机械臂 360° 旋转、抬起放下、机械爪张合,全部一条语音指令搞定。
行空板 K10小智:用语音指挥会说会跑会抓的智能车图5
【整体架构 】

```
┌------------------------┐
│  小智 AI(LLM 语音)│ ←── 普通话/英语自然语言
└----------┬------------┘
                 │ WebSocket / MCP
┌----------┴----------------┐
│ 行空板 K10(ESP32-S3)│  ESP-IDF 5.x
│  ├─ 4×MEMS 麦克风       │  ←── “小智,前进”
│  ├─ ES8311 功放             │  →── “好的,正在前进”
│  ├─ LCD 实时表情            │
│  └─ TCA9555 16-bit IO   ├-----------┐
└----------------------------┘               │
                                                            ▼ I²C
                                ┌--------------------------------------┐
                                │                   IO 扩展板                     │
                                │             P0~P15 全部引出               │
                                └--┬---------------┬-----------┬-----┘
                                     │                      │                 │
                                L298N-底盘    L298N-臂      L298N-爪
                               ┌----------┐   ┌----------┐   ┌--------┐
                               │左轮 右轮│   │水平 俯仰│   │   张合  │
                               └----------┘   └----------┘   └--------┘
```
行空板 K10小智:用语音指挥会说会跑会抓的智能车图4

行空板 K10小智:用语音指挥会说会跑会抓的智能车图3

【电机接线对照表(TCA9555 → L298N)】

|    功能段   | P 引脚 | 8255 位 | L298N 通道 |               备注           |
|------------|--------|----------|-------------|------------------- ---|
| 左轮 ENA  |    P8    |    BIT8   |     ENA       | 与 P12(IN1) 组合      |
| 右轮 ENB  |    P9    |    BIT9   |      ENB       | 与 P13(IN2) 组合      |
| 左轮 IN1   |    P5    |    BIT12 |      IN1        |                                 |
| 右轮 IN2   |    P4    |    BIT13 |      IN2        |                                 |
| 爪 ENA     |    P3    |    BIT14 |      ENA       | 接爪电机                   |
| 爪 IN1      |    P12  |    BIT3   |      IN1        | 0张开,1闭合            |
| 臂水平      |    P2    |    BIT7   |      ENA       | 水平旋转电机            |
| 臂水平      |    P13  |    BIT4   |      IN2        | 0左旋转,1右旋转     |
| 臂俯仰      |    P11  |    BIT2   |      ENA       | 俯仰电机                   |
| 臂俯仰 M  |    P1    |   ——   |       IN1       | 直接 GPIO2 控制方向 |


行空板 K10小智:用语音指挥会说会跑会抓的智能车图1

行空板 K10小智:用语音指挥会说会跑会抓的智能车图2

【软件关键片段】

1. IO 扩展板一次初始化  
  1. uint16_t output_pins = (1<<8)|(1<<9)|(1<<12)|(1<<13)|(1<<14)|(1<<3)|(1<<4)|(1<<2)|(1<<7);
  2. esp_io_expander_set_dir(io_expander, output_pins, IO_EXPANDER_OUTPUT);
  3. esp_io_expander_set_level(io_expander, output_pins, 0); // 全部归零,防止上电乱动
复制代码


2. MCP“一句话注册”
  1. mcp_server.AddTool("self.car.action",
  2.             "可控制小车及车载机械臂、机械爪的运行动作,小车的动作是前进、后退、停止、左转、右转。机械臂的动作是左旋转、右旋转、抬起、放下。机械爪的动作是张开、闭合",
  3.             PropertyList({Property("动作", kPropertyTypeString)}),
  4.             [this,gpio_num_P1](const PropertyList& properties) -> ReturnValue {
  5.                 std::string action=properties["动作"].value<std::string>().c_str();
  6.                 if (action=="前进"){
  7.                     SetPnumLevel(8,1);
  8.                     SetPnumLevel(9,1);
  9.                     SetPnumLevel(12,1);
  10.                     SetPnumLevel(13,1);
  11.                     if (stop_timer_) {
  12.                         xTimerStop(stop_timer_, 0);
  13.                         xTimerChangePeriod(stop_timer_, pdMS_TO_TICKS(1 * 1000), 0);
  14.                         xTimerStart(stop_timer_, 0);
  15.                     }
  16.                 }else if(action=="停止"){
  17.                     SetPnumLevel(8,0);//P8引脚
  18.                     SetPnumLevel(9,0);//P9引脚
  19.                 }else if(action=="后退"){
  20.                     SetPnumLevel(8,1);//P8引脚
  21.                     SetPnumLevel(9,1);//P9引脚
  22.                     SetPnumLevel(12,0);//P5引脚
  23.                    SetPnumLevel(13,0);//P4引脚
  24.                    if (stop_timer_) {
  25.                     xTimerStop(stop_timer_, 0);
  26.                     xTimerChangePeriod(stop_timer_, pdMS_TO_TICKS(1 * 1000), 0);
  27.                     xTimerStart(stop_timer_, 0);
  28.                 }
  29.                 }else if(action=="左转"){
  30.                     
  31.                     SetPnumLevel(8,1);
  32.                     SetPnumLevel(9,1);
  33.                     SetPnumLevel(12,0);
  34.                     SetPnumLevel(13,1);
  35.                     if (stop_timer_) {
  36.                         xTimerStop(stop_timer_, 0);
  37.                         xTimerChangePeriod(stop_timer_, pdMS_TO_TICKS(1 * 1000), 0);
  38.                         xTimerStart(stop_timer_, 0);
  39.                     }
  40.                 }else if(action=="右转"){
  41.                     
  42.                     SetPnumLevel(8,1);
  43.                     SetPnumLevel(9,1);
  44.                     SetPnumLevel(12,1);
  45.                     SetPnumLevel(13,0);
  46.                     if (stop_timer_) {
  47.                         xTimerStop(stop_timer_, 0);
  48.                         xTimerChangePeriod(stop_timer_, pdMS_TO_TICKS(1 * 1000), 0);
  49.                         xTimerStart(stop_timer_, 0);
  50.                     }
  51.                 }else if(action=="左旋转"){
  52.                     //机械臂水平动作
  53.                     SetPnumLevel(7,1);//P2引脚 E
  54.                     SetPnumLevel(4,0);//P13引脚 M
  55.                     if (stop_timer_) {
  56.                         xTimerStop(stop_timer_, 0);
  57.                         xTimerChangePeriod(stop_timer_, pdMS_TO_TICKS(1 * 1000), 0);
  58.                         xTimerStart(stop_timer_, 0);
  59.                     }
  60.                 }else if(action=="右旋转"){
  61.                     //机械臂水平动作
  62.                     SetPnumLevel(7,1);//P2引脚 E
  63.                     SetPnumLevel(4,1);//P13引脚 M
  64.                     if (stop_timer_) {
  65.                         xTimerStop(stop_timer_, 0);
  66.                         xTimerChangePeriod(stop_timer_, pdMS_TO_TICKS(1 * 1000), 0);
  67.                         xTimerStart(stop_timer_, 0);
  68.                     }
  69.                 }else if(action=="张开"){
  70.                     //机械爪动作
  71.                     SetPnumLevel(14,1);//P3引脚 E
  72.                     SetPnumLevel(3,0);//P12引脚 M
  73.                     if (stop_timer_) {
  74.                         xTimerStop(stop_timer_, 0);
  75.                         xTimerChangePeriod(stop_timer_, pdMS_TO_TICKS(1.6 * 1000), 0);
  76.                         xTimerStart(stop_timer_, 0);
  77.                     }
  78.                 }else if(action=="闭合"){
  79. //机械爪动作
  80.                     SetPnumLevel(14,1);//P3引脚 E
  81.                     SetPnumLevel(3,1);//P12引脚 M
  82.                     if (stop_timer_) {
  83.                         xTimerStop(stop_timer_, 0);
  84.                         xTimerChangePeriod(stop_timer_, pdMS_TO_TICKS(1.6 * 1000), 0);
  85.                         xTimerStart(stop_timer_, 0);
  86.                     }
  87.                 }else if(action=="抬起"){
  88. //机械臂垂直运动
  89.                     SetPnumLevel(2,1);//P11引脚 E
  90.                     gpio_set_level(gpio_num_P1, 0); //M
  91.                     if (stop_timer_) {
  92.                         xTimerStop(stop_timer_, 0);
  93.                         xTimerChangePeriod(stop_timer_, pdMS_TO_TICKS(1 * 1000), 0);
  94.                         xTimerStart(stop_timer_, 0);
  95.                     }
  96.                 }else if(action=="放下"){
  97.                     //机械臂垂直运动
  98.                     SetPnumLevel(2,1);//P11引脚 E
  99.                     gpio_set_level(gpio_num_P1, 1); //M
  100.                     if (stop_timer_) {
  101.                         xTimerStop(stop_timer_, 0);
  102.                         xTimerChangePeriod(stop_timer_, pdMS_TO_TICKS(0.8 * 1000), 0);
  103.                         xTimerStart(stop_timer_, 0);
  104.                     }
  105.                 }
  106.                 return ReturnValue(action);
  107.             
  108.          });
  109.                
  110.     }
复制代码


把 12 条动作全部写进一个 Lambda,LLM 只需一次函数调用即可精准执行。

3. 停车回调函数  
  1. static void StopMotorCallbackStatic(TimerHandle_t xTimer)
  2.     {
  3.         auto* self = static_cast<Df_K10Board*>(pvTimerGetTimerID(xTimer));
  4.         self->StopMotorCallback();
  5.     }
  6.     void StopMotorCallback()
  7.     {
  8.         SetPnumLevel(8,0);
  9.         SetPnumLevel(9,0);
  10.         SetPnumLevel(12,0);
  11.         SetPnumLevel(13,0);
  12.         SetPnumLevel(14,0);
  13.         SetPnumLevel(3,0);
  14.         SetPnumLevel(2,0);
  15.         SetPnumLevel(7,0);
  16.         SetPnumLevel(4,0);
  17.     }
复制代码

每条动作都会根据实际行程重置定时器(爪 1.6 s、臂 0.8~1 s、底盘 1 s),兼顾“到位”与“安全”。

【演示视频】
【一句话总结】  
“当语音助手不再只是‘聊天’,而是能直接操作 5 路电机、11 种动作、100% 开源可二次开发,你会发现——**给 ESP32 装上‘大模型’,才是嵌入式玩家的新浪漫。**”
【完整代码】
"XIAOZHI-ESP32-MAIN/main/boards/df-k10/df_k10_board.cc"
  1. #include "wifi_board.h"
  2. #include "k10_audio_codec.h"
  3. #include "display/lcd_display.h"
  4. #include "esp_lcd_ili9341.h"
  5. #include "led_control.h"
  6. #include "application.h"
  7. #include "button.h"
  8. #include "config.h"
  9. #include "esp32_camera.h"
  10. #include "led/circular_strip.h"
  11. #include "assets/lang_config.h"
  12. #include <esp_log.h>
  13. #include <esp_lcd_panel_vendor.h>
  14. #include <driver/i2c_master.h>
  15. #include <driver/spi_common.h>
  16. #include <wifi_station.h>
  17. #include <freertos/timers.h>
  18. #include "esp_io_expander_tca95xx_16bit.h"
  19. #include <mcp_server.h>
  20. #include <freertos/timers.h>
  21. #define TAG "DF-K10"
  22. LV_FONT_DECLARE(font_puhui_20_4);
  23. LV_FONT_DECLARE(font_awesome_20_4);
  24.     TimerHandle_t stop_timer_ = nullptr;
  25. class Df_K10Board : public WifiBoard {
  26. private:
  27.     i2c_master_bus_handle_t i2c_bus_;
  28.     esp_io_expander_handle_t io_expander;
  29.     LcdDisplay *display_;
  30.     button_handle_t btn_a;
  31.     button_handle_t btn_b;
  32.     Esp32Camera* camera_;
  33.     button_driver_t* btn_a_driver_ = nullptr;
  34.     button_driver_t* btn_b_driver_ = nullptr;
  35.     CircularStrip* led_strip_;
  36.     TimerHandle_t stop_timer_ = nullptr;
  37.     static Df_K10Board* instance_;
  38.     void InitializeI2c() {
  39.         // Initialize I2C peripheral
  40.         i2c_master_bus_config_t i2c_bus_cfg = {
  41.                 .i2c_port = (i2c_port_t)1,
  42.                 .sda_io_num = AUDIO_CODEC_I2C_SDA_PIN,
  43.                 .scl_io_num = AUDIO_CODEC_I2C_SCL_PIN,
  44.                 .clk_source = I2C_CLK_SRC_DEFAULT,
  45.                 .glitch_ignore_cnt = 7,
  46.                 .intr_priority = 0,
  47.                 .trans_queue_depth = 0,
  48.                 .flags = {
  49.                                 .enable_internal_pullup = 1,
  50.                         },
  51.         };
  52.         ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_bus_cfg, &i2c_bus_));
  53.     }
  54.     void InitializeSpi() {
  55.         spi_bus_config_t buscfg = {};
  56.         buscfg.mosi_io_num = GPIO_NUM_21;
  57.         buscfg.miso_io_num = GPIO_NUM_NC;
  58.         buscfg.sclk_io_num = GPIO_NUM_12;
  59.         buscfg.quadwp_io_num = GPIO_NUM_NC;
  60.         buscfg.quadhd_io_num = GPIO_NUM_NC;
  61.         buscfg.max_transfer_sz = DISPLAY_WIDTH * DISPLAY_HEIGHT * sizeof(uint16_t);
  62.         ESP_ERROR_CHECK(spi_bus_initialize(SPI3_HOST, &buscfg, SPI_DMA_CH_AUTO));
  63.     }
  64.     esp_err_t IoExpanderSetLevel(uint16_t pin_mask, uint8_t level) {
  65.         return esp_io_expander_set_level(io_expander, pin_mask, level);
  66.     }
  67.     uint8_t IoExpanderGetLevel(uint16_t pin_mask) {
  68.         uint32_t pin_val = 0;
  69.         esp_io_expander_get_level(io_expander, DRV_IO_EXP_INPUT_MASK, &pin_val);
  70.         pin_mask &= DRV_IO_EXP_INPUT_MASK;
  71.         return (uint8_t)((pin_val & pin_mask) ? 1 : 0);
  72.     }
  73.     void InitializeIoExpander() {
  74.         esp_io_expander_new_i2c_tca95xx_16bit(
  75.                 i2c_bus_, ESP_IO_EXPANDER_I2C_TCA9555_ADDRESS_000, &io_expander);
  76.         esp_err_t ret;
  77.         ret = esp_io_expander_print_state(io_expander);
  78.         if (ret != ESP_OK) {
  79.             ESP_LOGE(TAG, "Print state failed: %s", esp_err_to_name(ret));
  80.         }
  81.         ret = esp_io_expander_set_dir(io_expander, IO_EXPANDER_PIN_NUM_0,IO_EXPANDER_OUTPUT);
  82.         if (ret != ESP_OK) {
  83.             ESP_LOGE(TAG, "Set direction failed: %s", esp_err_to_name(ret));
  84.         }
  85.         ret = esp_io_expander_set_level(io_expander, 0, 1);
  86.         if (ret != ESP_OK) {
  87.             ESP_LOGE(TAG, "Set level failed: %s", esp_err_to_name(ret));
  88.         }
  89.         ret = esp_io_expander_set_dir(
  90.                 io_expander, DRV_IO_EXP_INPUT_MASK,
  91.                 IO_EXPANDER_INPUT);
  92.         if (ret != ESP_OK) {
  93.             ESP_LOGE(TAG, "Set direction failed: %s", esp_err_to_name(ret));
  94.         }
  95.         // 设置多个引脚为输出模式
  96.         uint16_t output_pins = (1 << 8) | (1 << 9) | (1 << 12) | (1 << 13) | (1 << 14) | (1 << 3) | (1 << 4) | (1 << 2) | (1 << 7);  // 引脚 P8,P9,P5,P4,P3,P12,P13,P11,P2
  97.         ret = esp_io_expander_set_dir(io_expander, output_pins,IO_EXPANDER_OUTPUT);
  98.         if (ret != ESP_OK) {
  99.             ESP_LOGE(TAG, "Set direction failed: %s", esp_err_to_name(ret));
  100.         }
  101.         ret = esp_io_expander_set_level(io_expander, output_pins, 0);
  102.         if (ret != ESP_OK) {
  103.             ESP_LOGE(TAG, "Set level failed: %s", esp_err_to_name(ret));
  104.         }
  105.     }
  106.     void SetPnumLevel(uint16_t Pnum,uint8_t level) {
  107.         esp_err_t ret = esp_io_expander_set_level(io_expander, 1<<Pnum, level);
  108.         if (ret != ESP_OK) {
  109.             ESP_LOGE(TAG, "Set level for P failed: %s", esp_err_to_name(ret));
  110.         }
  111.     }
  112.     void InitializeButtons() {
  113.         instance_ = this;
  114.         // Button A
  115.         button_config_t btn_a_config = {
  116.             .long_press_time = 1000,
  117.             .short_press_time = 0
  118.         };
  119.         btn_a_driver_ = (button_driver_t*)calloc(1, sizeof(button_driver_t));
  120.         btn_a_driver_->enable_power_save = false;
  121.         btn_a_driver_->get_key_level = [](button_driver_t *button_driver) -> uint8_t {
  122.             return !instance_->IoExpanderGetLevel(IO_EXPANDER_PIN_NUM_2);
  123.         };
  124.         ESP_ERROR_CHECK(iot_button_create(&btn_a_config, btn_a_driver_, &btn_a));
  125.         iot_button_register_cb(btn_a, BUTTON_SINGLE_CLICK, nullptr, [](void* button_handle, void* usr_data) {
  126.             auto self = static_cast<Df_K10Board*>(usr_data);
  127.             auto& app = Application::GetInstance();
  128.             if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) {
  129.                 self->ResetWifiConfiguration();
  130.             }
  131.             app.ToggleChatState();
  132.         }, this);
  133.         iot_button_register_cb(btn_a, BUTTON_LONG_PRESS_START, nullptr, [](void* button_handle, void* usr_data) {
  134.             auto self = static_cast<Df_K10Board*>(usr_data);
  135.             auto codec = self->GetAudioCodec();
  136.             auto volume = codec->output_volume() - 10;
  137.             if (volume < 0) {
  138.                 volume = 0;
  139.             }
  140.             codec->SetOutputVolume(volume);
  141.             self->GetDisplay()->ShowNotification(Lang::Strings::VOLUME + std::to_string(volume));
  142.         }, this);
  143.         // Button B
  144.         button_config_t btn_b_config = {
  145.             .long_press_time = 1000,
  146.             .short_press_time = 0
  147.         };
  148.         btn_b_driver_ = (button_driver_t*)calloc(1, sizeof(button_driver_t));
  149.         btn_b_driver_->enable_power_save = false;
  150.         btn_b_driver_->get_key_level = [](button_driver_t *button_driver) -> uint8_t {
  151.             return !instance_->IoExpanderGetLevel(IO_EXPANDER_PIN_NUM_12);
  152.         };
  153.         ESP_ERROR_CHECK(iot_button_create(&btn_b_config, btn_b_driver_, &btn_b));
  154.         iot_button_register_cb(btn_b, BUTTON_SINGLE_CLICK, nullptr, [](void* button_handle, void* usr_data) {
  155.             auto self = static_cast<Df_K10Board*>(usr_data);
  156.             auto& app = Application::GetInstance();
  157.             if (app.GetDeviceState() == kDeviceStateStarting && !WifiStation::GetInstance().IsConnected()) {
  158.                 self->ResetWifiConfiguration();
  159.             }
  160.             app.ToggleChatState();
  161.         }, this);
  162.         iot_button_register_cb(btn_b, BUTTON_LONG_PRESS_START, nullptr, [](void* button_handle, void* usr_data) {
  163.             auto self = static_cast<Df_K10Board*>(usr_data);
  164.             auto codec = self->GetAudioCodec();
  165.             auto volume = codec->output_volume() + 10;
  166.             if (volume > 100) {
  167.                 volume = 100;
  168.             }
  169.             codec->SetOutputVolume(volume);
  170.             self->GetDisplay()->ShowNotification(Lang::Strings::VOLUME + std::to_string(volume));
  171.         }, this);
  172.     }
  173.     void InitializeCamera() {
  174.         camera_config_t config = {};
  175.         config.ledc_channel = LEDC_CHANNEL_2;   // LEDC通道选择  用于生成XCLK时钟 但是S3不用
  176.         config.ledc_timer = LEDC_TIMER_2;       // LEDC timer选择  用于生成XCLK时钟 但是S3不用
  177.         config.pin_d0 = CAMERA_PIN_D2;
  178.         config.pin_d1 = CAMERA_PIN_D3;
  179.         config.pin_d2 = CAMERA_PIN_D4;
  180.         config.pin_d3 = CAMERA_PIN_D5;
  181.         config.pin_d4 = CAMERA_PIN_D6;
  182.         config.pin_d5 = CAMERA_PIN_D7;
  183.         config.pin_d6 = CAMERA_PIN_D8;
  184.         config.pin_d7 = CAMERA_PIN_D9;
  185.         config.pin_xclk = CAMERA_PIN_XCLK;
  186.         config.pin_pclk = CAMERA_PIN_PCLK;
  187.         config.pin_vsync = CAMERA_PIN_VSYNC;
  188.         config.pin_href = CAMERA_PIN_HREF;
  189.         config.pin_sccb_sda = -1;  // 这里如果写-1 表示使用已经初始化的I2C接口
  190.         config.pin_sccb_scl = CAMERA_PIN_SIOC;
  191.         config.sccb_i2c_port = 1;               //  这里如果写1 默认使用I2C1
  192.         config.pin_pwdn = CAMERA_PIN_PWDN;
  193.         config.pin_reset = CAMERA_PIN_RESET;
  194.         config.xclk_freq_hz = XCLK_FREQ_HZ;
  195.         config.pixel_format = PIXFORMAT_RGB565;
  196.         config.frame_size = FRAMESIZE_VGA;
  197.         config.jpeg_quality = 12;
  198.         config.fb_count = 1;
  199.         config.fb_location = CAMERA_FB_IN_PSRAM;
  200.         config.grab_mode = CAMERA_GRAB_WHEN_EMPTY;
  201.         camera_ = new Esp32Camera(config);
  202.     }
  203.     void InitializeIli9341Display() {
  204.         esp_lcd_panel_io_handle_t panel_io = nullptr;
  205.         esp_lcd_panel_handle_t panel = nullptr;
  206.         // 液晶屏控制IO初始化
  207.         ESP_LOGD(TAG, "Install panel IO");
  208.         esp_lcd_panel_io_spi_config_t io_config = {};
  209.         io_config.cs_gpio_num = GPIO_NUM_14;
  210.         io_config.dc_gpio_num = GPIO_NUM_13;
  211.         io_config.spi_mode = 0;
  212.         io_config.pclk_hz = 40 * 1000 * 1000;
  213.         io_config.trans_queue_depth = 10;
  214.         io_config.lcd_cmd_bits = 8;
  215.         io_config.lcd_param_bits = 8;
  216.         ESP_ERROR_CHECK(esp_lcd_new_panel_io_spi(SPI3_HOST, &io_config, &panel_io));
  217.         // 初始化液晶屏驱动芯片
  218.         ESP_LOGD(TAG, "Install LCD driver");
  219.         esp_lcd_panel_dev_config_t panel_config = {};
  220.         panel_config.reset_gpio_num = GPIO_NUM_NC;
  221.         panel_config.bits_per_pixel = 16;
  222.         panel_config.color_space = ESP_LCD_COLOR_SPACE_BGR;
  223.         ESP_ERROR_CHECK(esp_lcd_new_panel_ili9341(panel_io, &panel_config, &panel));
  224.         ESP_ERROR_CHECK(esp_lcd_panel_reset(panel));
  225.         ESP_ERROR_CHECK(esp_lcd_panel_init(panel));
  226.         ESP_ERROR_CHECK(esp_lcd_panel_invert_color(panel, DISPLAY_BACKLIGHT_OUTPUT_INVERT));
  227.         ESP_ERROR_CHECK(esp_lcd_panel_swap_xy(panel, DISPLAY_SWAP_XY));
  228.         ESP_ERROR_CHECK(esp_lcd_panel_mirror(panel, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y));
  229.         ESP_ERROR_CHECK(esp_lcd_panel_disp_on_off(panel, true));
  230.         display_ = new SpiLcdDisplay(panel_io, panel,
  231.                                 DISPLAY_WIDTH, DISPLAY_HEIGHT, DISPLAY_OFFSET_X, DISPLAY_OFFSET_Y, DISPLAY_MIRROR_X, DISPLAY_MIRROR_Y, DISPLAY_SWAP_XY,
  232.                                 {
  233.                                         .text_font = &font_puhui_20_4,
  234.                                         .icon_font = &font_awesome_20_4,
  235.                                         .emoji_font = font_emoji_64_init(),
  236.                                 });
  237.     }
  238.     // 物联网初始化,添加对 AI 可见设备
  239.     void InitializeIot() {
  240.         gpio_num_t gpio_num_P0 = GPIO_NUM_1;
  241.         gpio_num_t gpio_num_P1 = GPIO_NUM_2;
  242.         gpio_config_t cfg = {
  243.             .pin_bit_mask = (1ULL << gpio_num_P0) | (1ULL << gpio_num_P1),
  244.             .mode = GPIO_MODE_OUTPUT,
  245.             .pull_up_en = GPIO_PULLUP_DISABLE,
  246.             .pull_down_en = GPIO_PULLDOWN_DISABLE,
  247.             .intr_type = GPIO_INTR_DISABLE,
  248.         };
  249.         ESP_ERROR_CHECK(gpio_config(&cfg));
  250.         gpio_set_level(gpio_num_P0, 0);
  251.         gpio_set_level(gpio_num_P1, 0);
  252.         stop_timer_ = xTimerCreate("StopMotorTimer",pdMS_TO_TICKS(1000),pdFALSE,this,StopMotorCallbackStatic);
  253.         auto& mcp_server = McpServer::GetInstance();
  254.    
  255.          mcp_server.AddTool("self.car.action",
  256.             "可控制小车及车载机械臂、机械爪的运行动作,小车的动作是前进、后退、停止、左转、右转。机械臂的动作是左旋转、右旋转、抬起、放下。机械爪的动作是张开、闭合",
  257.             PropertyList({Property("动作", kPropertyTypeString)}),
  258.             [this,gpio_num_P1](const PropertyList& properties) -> ReturnValue {
  259.                 std::string action=properties["动作"].value<std::string>().c_str();
  260.                 if (action=="前进"){
  261.                     SetPnumLevel(8,1);
  262.                     SetPnumLevel(9,1);
  263.                     SetPnumLevel(12,1);
  264.                     SetPnumLevel(13,1);
  265.                     if (stop_timer_) {
  266.                         xTimerStop(stop_timer_, 0);
  267.                         xTimerChangePeriod(stop_timer_, pdMS_TO_TICKS(1 * 1000), 0);
  268.                         xTimerStart(stop_timer_, 0);
  269.                     }
  270.                 }else if(action=="停止"){
  271.                     SetPnumLevel(8,0);//P8引脚
  272.                     SetPnumLevel(9,0);//P9引脚
  273.                 }else if(action=="后退"){
  274.                     SetPnumLevel(8,1);//P8引脚
  275.                     SetPnumLevel(9,1);//P9引脚
  276.                     SetPnumLevel(12,0);//P5引脚
  277.                    SetPnumLevel(13,0);//P4引脚
  278.                    if (stop_timer_) {
  279.                     xTimerStop(stop_timer_, 0);
  280.                     xTimerChangePeriod(stop_timer_, pdMS_TO_TICKS(1 * 1000), 0);
  281.                     xTimerStart(stop_timer_, 0);
  282.                 }
  283.                     //夹子
  284.                     //SetPnumLevel(14,0);//P3引脚 E
  285.                     //SetPnumLevel(3,0);//P12引脚 M
  286.                     //上下
  287.                     
  288.                     //SetPnumLevel(2,0);//P11引脚 E
  289.                     //水平
  290.                     //SetPnumLevel(7,0);//P2引脚 E
  291.                     //SetPnumLevel(4,0);//P13引脚 M
  292.                     
  293.                     //SetPnumLevel(15,0);//LED灯
  294.                     //SetPnumLevel(16,0);无对应引脚
  295.                     //SetPnumLevel(1,0);//无对应引脚
  296.                     //SetPnumLevel(5,0);//无对应引脚
  297.                     //SetPnumLevel(6,0);//无对应引脚
  298.                     //SetPnumLevel(10,0);//无对应引脚
  299.                     //SetPnumLevel(11,0);//无对应引脚
  300.                 }else if(action=="左转"){
  301.                     
  302.                     SetPnumLevel(8,1);
  303.                     SetPnumLevel(9,1);
  304.                     SetPnumLevel(12,0);
  305.                     SetPnumLevel(13,1);
  306.                     if (stop_timer_) {
  307.                         xTimerStop(stop_timer_, 0);
  308.                         xTimerChangePeriod(stop_timer_, pdMS_TO_TICKS(1 * 1000), 0);
  309.                         xTimerStart(stop_timer_, 0);
  310.                     }
  311.                 }else if(action=="右转"){
  312.                     
  313.                     SetPnumLevel(8,1);
  314.                     SetPnumLevel(9,1);
  315.                     SetPnumLevel(12,1);
  316.                     SetPnumLevel(13,0);
  317.                     if (stop_timer_) {
  318.                         xTimerStop(stop_timer_, 0);
  319.                         xTimerChangePeriod(stop_timer_, pdMS_TO_TICKS(1 * 1000), 0);
  320.                         xTimerStart(stop_timer_, 0);
  321.                     }
  322.                 }else if(action=="左旋转"){
  323.                     
  324.                     SetPnumLevel(7,1);//P2引脚 E
  325.                     SetPnumLevel(4,0);//P13引脚 M
  326.                     if (stop_timer_) {
  327.                         xTimerStop(stop_timer_, 0);
  328.                         xTimerChangePeriod(stop_timer_, pdMS_TO_TICKS(1 * 1000), 0);
  329.                         xTimerStart(stop_timer_, 0);
  330.                     }
  331.                 }else if(action=="右旋转"){
  332.                     
  333.                     SetPnumLevel(7,1);//P2引脚 E
  334.                     SetPnumLevel(4,1);//P13引脚 M
  335.                     if (stop_timer_) {
  336.                         xTimerStop(stop_timer_, 0);
  337.                         xTimerChangePeriod(stop_timer_, pdMS_TO_TICKS(1 * 1000), 0);
  338.                         xTimerStart(stop_timer_, 0);
  339.                     }
  340.                 }else if(action=="张开"){
  341.                     
  342.                     SetPnumLevel(14,1);//P3引脚 E
  343.                     SetPnumLevel(3,0);//P12引脚 M
  344.                     if (stop_timer_) {
  345.                         xTimerStop(stop_timer_, 0);
  346.                         xTimerChangePeriod(stop_timer_, pdMS_TO_TICKS(1.6 * 1000), 0);
  347.                         xTimerStart(stop_timer_, 0);
  348.                     }
  349.                 }else if(action=="闭合"){
  350.                     
  351.                     SetPnumLevel(14,1);//P3引脚 E
  352.                     SetPnumLevel(3,1);//P12引脚 M
  353.                     if (stop_timer_) {
  354.                         xTimerStop(stop_timer_, 0);
  355.                         xTimerChangePeriod(stop_timer_, pdMS_TO_TICKS(1.6 * 1000), 0);
  356.                         xTimerStart(stop_timer_, 0);
  357.                     }
  358.                 }else if(action=="抬起"){
  359.                     
  360.                     SetPnumLevel(2,1);//P11引脚 E
  361.                     gpio_set_level(gpio_num_P1, 0); //M
  362.                     if (stop_timer_) {
  363.                         xTimerStop(stop_timer_, 0);
  364.                         xTimerChangePeriod(stop_timer_, pdMS_TO_TICKS(1 * 1000), 0);
  365.                         xTimerStart(stop_timer_, 0);
  366.                     }
  367.                 }else if(action=="放下"){
  368.                     
  369.                     SetPnumLevel(2,1);//P11引脚 E
  370.                     gpio_set_level(gpio_num_P1, 1); //M
  371.                     if (stop_timer_) {
  372.                         xTimerStop(stop_timer_, 0);
  373.                         xTimerChangePeriod(stop_timer_, pdMS_TO_TICKS(0.8 * 1000), 0);
  374.                         xTimerStart(stop_timer_, 0);
  375.                     }
  376.                 }
  377.                 return ReturnValue(action);
  378.             
  379.          });
  380.                
  381.     }
  382.     static void StopMotorCallbackStatic(TimerHandle_t xTimer)
  383.     {
  384.         auto* self = static_cast<Df_K10Board*>(pvTimerGetTimerID(xTimer));
  385.         self->StopMotorCallback();
  386.     }
  387.     void StopMotorCallback()
  388.     {
  389.         SetPnumLevel(8,0);
  390.         SetPnumLevel(9,0);
  391.         SetPnumLevel(12,0);
  392.         SetPnumLevel(13,0);
  393.         SetPnumLevel(14,0);
  394.         SetPnumLevel(3,0);
  395.         SetPnumLevel(2,0);
  396.         SetPnumLevel(7,0);
  397.         SetPnumLevel(4,0);
  398.     }
  399. public:
  400.    
  401.     Df_K10Board() {
  402.         InitializeI2c();
  403.         InitializeIoExpander();
  404.         InitializeSpi();
  405.         InitializeIli9341Display();
  406.         InitializeButtons();
  407.         InitializeIot();
  408.         //InitializeCamera();
  409.     }
  410.     virtual AudioCodec *GetAudioCodec() override {
  411.         static K10AudioCodec audio_codec(
  412.                     i2c_bus_,
  413.                     AUDIO_INPUT_SAMPLE_RATE,
  414.                     AUDIO_OUTPUT_SAMPLE_RATE,
  415.                     AUDIO_I2S_GPIO_MCLK,
  416.                     AUDIO_I2S_GPIO_BCLK,
  417.                     AUDIO_I2S_GPIO_WS,
  418.                     AUDIO_I2S_GPIO_DOUT,
  419.                     AUDIO_I2S_GPIO_DIN,
  420.                     AUDIO_CODEC_PA_PIN,
  421.                     AUDIO_CODEC_ES8311_ADDR,
  422.                     AUDIO_CODEC_ES7210_ADDR,
  423.                     AUDIO_INPUT_REFERENCE);
  424.         return &audio_codec;
  425.     }
  426.     //virtual Camera* GetCamera() override {
  427.         //return camera_;
  428.     //}
  429.     virtual Display *GetDisplay() override {
  430.         return display_;
  431.     }
  432. };
  433. DECLARE_BOARD(Df_K10Board);
  434. Df_K10Board* Df_K10Board::instance_ = nullptr;
复制代码



您需要登录后才可以回帖 登录 | 立即注册

本版积分规则

为本项目制作心愿单
购买心愿单
心愿单 编辑
[[wsData.name]]

硬件清单

  • [[d.name]]
btnicon
我也要做!
点击进入购买页面
上海智位机器人股份有限公司 沪ICP备09038501号-4 备案 沪公网安备31011502402448

© 2013-2025 Comsenz Inc. Powered by Discuz! X3.4 Licensed

mail