diff --git a/.gitignore b/.gitignore index e257658..6bab1e7 100644 --- a/.gitignore +++ b/.gitignore @@ -1,34 +1,34 @@ -# ---> C++ -# Prerequisites -*.d - -# Compiled Object files -*.slo -*.lo -*.o -*.obj - -# Precompiled Headers -*.gch -*.pch - -# Compiled Dynamic libraries -*.so -*.dylib -*.dll - -# Fortran module files -*.mod -*.smod - -# Compiled Static libraries -*.lai -*.la -*.a -*.lib - -# Executables -*.exe -*.out -*.app - +# ---> C++ +# Prerequisites +*.d + +# Compiled Object files +*.slo +*.lo +*.o +*.obj + +# Precompiled Headers +*.gch +*.pch + +# Compiled Dynamic libraries +*.so +*.dylib +*.dll + +# Fortran module files +*.mod +*.smod + +# Compiled Static libraries +*.lai +*.la +*.a +*.lib + +# Executables +*.exe +*.out +*.app + diff --git a/Device_Tree/board.dts b/Device_Tree/board.dts new file mode 100644 index 0000000..38597ba --- /dev/null +++ b/Device_Tree/board.dts @@ -0,0 +1,1068 @@ +// SPDX-License-Identifier: (GPL-2.0+ or MIT) + +/dts-v1/; + +#include "sun300iw1p1.dtsi" + +/{ + board = "V821", "V821-Avaota F1"; + compatible = "allwinner,v821", "riscv,sun300iw1p1"; + aliases { + }; + + reg_vdd_cpu: vdd-cpu { + compatible = "regulator-fixed"; + regulator-name = "vdd_cpu"; + regulator-min-microvolt = <920000>; + regulator-max-microvolt = <920000>; + regulator-always-on; + regulator-boot-on; + status = "okay"; + }; + + /* used for hib & ultra standby poweron source enable mask */ + /* bit 0 ~ bit 7 - pl 0 ~pl 7 */ + /* bit 9 rtc alarm0 */ + /* bit 10 rtc alarm1 */ + /* bit 11 wakeuptimer */ + /* bit 12 wlan, keep 0 because hib has no wlan and ultra wakes up by wlan on remote core */ + poweron-source { + hib_poweron_source = <0x000007FF>; + ultra_poweron_source = <0x000007FF>; + }; + + reserved-memory { + rv_ddr_reserved: rvddrreserved@81000000 { + reg = <0x0 0x81000000 0x0 0x200000>; + no-map; + }; + /* + * The name should be "vdev%dbuffer". + * Its size should be not less than + * RPMSG_BUF_SIZE * (num of buffers in a vring) * 2 + * = 512 * (num of buffers in a vring) * 2 + */ + rv_vdev0buffer: vdev0buffer@81200000 { + compatible = "shared-dma-pool"; + reg = <0x0 0x81200000 0x0 0x40000>; + no-map; + }; + /* + * The name should be "vdev%dvring%d". + * The size of each should be not less than + * PAGE_ALIGN(vring_size(num, align)) + * = PAGE_ALIGN(16 * num + 6 + 2 * num + (pads for align) + 6 + 8 * num) + * + * (Please refer to the vring layout in include/uapi/linux/virtio_ring.h) + */ + rv_vdev0vring0: vdev0vring0@81240000 { + reg = <0x0 0x81240000 0x0 0x2000>; + no-map; + }; + + rv_vdev0vring1: vdev0vring1@81242000 { + reg = <0x0 0x81242000 0x0 0x2000>; + no-map; + }; + + e907_mem_fw: e907_mem_fw@81244000 { + /* boot0 & uboot0 load elf addr */ + reg = <0x0 0x81244000 0x0 0x00200000>; + }; + + e907_share_irq_table: share_irq_table@81644000 { + reg = <0x0 0x81644000 0x0 0x2000>; + no-map; + }; + + e907_rpbuf_reserved:e907_rpbuf@81646000 { + compatible = "shared-dma-pool"; + reg = <0x0 0x81646000 0x0 0x8000>; + no-map; + }; + + size_pool { + reg = <0 0x82000000 0 0x01400000>; + }; + + linux,cma { + size = <0x0 0x400000>; + }; + }; + + reserved-irq { + share-e907 { + arch-name = "e907"; + memory-region = <&e907_share_irq_table>; + /* defined by sun300iw1-share-irq-dt.h */ + share-irq = + <1 0x1 E907_PA_IRQ_NUM A27_PA_IRQ_NUM 0x00000000>, + <3 0x3 E907_PC_IRQ_NUM A27_PC_IRQ_NUM 0x00000000>, + <4 0x4 E907_PD_IRQ_NUM A27_PD_IRQ_NUM 0x00000000>, + <12 0xc E907_PL_IRQ_NUM A27_PL_IRQ_NUM 0x00000000>; + }; + }; + + hifbypass: hifbypass { + compatible = "allwinner,sun300wi-sip-wifi"; + interrupts-extended = <&plic0 160 IRQ_TYPE_LEVEL_HIGH>; + clocks = <&aon_ccu CLK_DCXO>; + clock-names = "hosc"; + status = "disabled"; + }; + + rpbuf_controller0: rpbuf_controller0@0 { + compatible = "allwinner,rpbuf-controller"; + remoteproc = <&e907_rproc>; + ctrl_id = <0>; + memory-region = <&e907_rpbuf_reserved>; + status = "okay"; + }; + + rpbuf_xradio: rpbuf_xradio@0 { + compatible = "allwinner,rpbuf-xradio"; + rpbuf = <&rpbuf_controller0>; + status = "okay"; + }; + + heap_size_pool@0{ + compatible = "allwinner,size_pool"; + heap-name = "size_pool"; + heap-id = <0x7>; + heap-base = <0x82000000>; + heap-size = <0x01400000>; + heap-type = "ion_size_pool"; + thrs = <100>; + sizes = <0 20480>; + fall_to_big_pool = <1>; + }; + + gpio-motor@0 { + compatible = "allwinner,gpio-motor"; + ab-pin-black = <&pio PD 12 GPIO_ACTIVE_HIGH>; + ab-pin-yellow = <&pio PD 13 GPIO_ACTIVE_HIGH>; + ab-pin-brown = <&pio PD 14 GPIO_ACTIVE_HIGH>; + ab-pin-blue = <&pio PD 15 GPIO_ACTIVE_HIGH>; + cd-pin-black = <&pio PD 16 GPIO_ACTIVE_HIGH>; + cd-pin-yellow = <&pio PD 17 GPIO_ACTIVE_HIGH>; + cd-pin-brown = <&pio PD 18 GPIO_ACTIVE_HIGH>; + cd-pin-blue = <&pio PD 19 GPIO_ACTIVE_HIGH>; + status = "disabled"; + }; + + ae350_standby_debug:ae350_standby_debug@1 { + compatible = "allwinner,sun300iw1-ae350-standby-debug"; + mboxes = <&msgbox 2>; + mbox-names = "ae350-notify"; + status = "okay"; + }; +}; + +&rtc_pio { + uart0_pins_default: uart0_pins@0 { + pins = "PL4", "PL5"; + function = "uart0"; + }; + + uart0_pins_sleep: uart0_pins@1 { + pins = "PL4", "PL5"; + function = "io_disabled"; + }; + + uart3_pins_default: uart3_pins@0 { + pins = "PL2", "PL3"; + function = "uart3"; + }; + + uart3_pins_sleep: uart3_pins@1 { + pins = "PL2", "PL3"; + function = "io_disabled"; + }; +}; + +&pio { + uart1_pins_default: uart1_pins@0 { + pins = "PD7", "PD8", "PD9", "PD10"; + function = "uart1"; + }; + + uart1_pins_sleep: uart1_pins@1 { + pins = "PD7", "PD8", "PD9", "PD10"; + function = "io_disabled"; + }; + + uart2_pins_default: uart2_pins@0 { + pins = "PA5", "PA6", "PA7", "PA8"; + function = "uart2"; + }; + + uart2_pins_sleep: uart2_pins@1 { + pins = "PA5", "PA6", "PA7", "PA8"; + function = "io_disabled"; + }; + + gmac0_pins_default: gmac_pins@0 { + pins = "PD1", "PD2", "PD3", + "PD4", "PD5", "PD6", "PD7", + "PD8", "PD9", "PD10", "PD11"; + function = "rmii"; + allwinner,drive = <3>; + bias-pull-up; + }; + + gmac0_pins_sleep: gmac_pins@1 { + pins = "PD1", "PD2", "PD3", + "PD4", "PD5", "PD6", "PD7", + "PD8", "PD9", "PD10", "PD11"; + function = "io_disabled"; + }; + + pwm8_pins_active: pwm8@0 { + pins = "PD18"; + function = "pwm0_8"; + }; + pwm8_pins_sleep: pwm8@1 { + pins = "PD18"; + function = "gpio_in"; + bias-pull-down; + }; + pwm9_pins_active: pwm9@0 { + pins = "PD19"; + function = "pwm0_9"; + }; + pwm9_pins_sleep: pwm9@1 { + pins = "PD19"; + function = "gpio_in"; + bias-pull-down; + }; + + twi0_pins_default: twi0@0 { + pins = "PA3", "PA4"; + function = "twi0"; + allwinner,drive = <0>; + bias-pull-up; + }; + + twi0_pins_sleep: twi0@1 { + pins = "PA3", "PA4"; + function = "gpio_in"; + }; + + spi0_pins_default: spi0@0 { + pins = "PC9", "PC8", "PC11"; /* clk, mosi, miso */ + function = "spi0"; + allwinner,drive = <0>; + }; + + spi0_pins_cs: spi0@1 { + pins = "PC6", "PC7", "PC10"; /* wp, hold, cs */ + function = "spi0"; + allwinner,drive = <0>; + bias-pull-up; + }; + + spi0_pins_sleep: spi0@2 { + pins = "PC6", "PC7", "PC9", "PC8", "PC11", "PC10"; + function = "io_disabled"; + }; + + sdc0_pins_a: sdc0@0 { + pins = "PC0", "PC1", "PC2", + "PC3", "PC5"; + function = "sdc0"; + allwinner,drive = <3>; + bias-pull-up; + }; + + sdc0_pins_c: sdc0@2 { + pins = "PC0", "PC1", "PC2", + "PC3", "PC4", "PC5"; + function = "gpio_in"; + }; + + sdc0_pins_d: sdc0@3 { + pins = "PC4"; + function = "sdc0"; + allwinner,drive = <3>; + bias-disable; + }; + + /* for uboot card probe */ + sdc0_pins_uboot: sdc0@4 { + allwinner,pins = "PC0", "PC1", "PC2", + "PC3", "PC4", "PC5"; + allwinner,function = "sdc0"; + allwinner,muxsel = <2>; + allwinner,drive = <3>; + allwinner,pull = <1>; + power-source = <3300>; + }; + + spif_pins_default: spif@0 { + pins = "PC9", "PC8", "PC11"; /* clk, mosi, miso */ + function = "spif"; + allwinner,drive = <1>; + }; + + spif_pins_cs: spif@1 { + pins = "PC6", "PC7", "PC10"; /* wp, hold, cs */ + function = "spif"; + allwinner,drive = <1>; + bias-pull-up; + }; + + spif_pins_sleep: spif@2 { + pins = "PC6", "PC7", "PC9", "PC8", "PC11", "PC10"; + function = "io_disabled"; + }; + + /* I2S0 individual pin definitions for MAX98357A */ + i2s0_bclk_pin: i2s0_bclk@0 { + pins = "PD12"; + function = "i2s0_bclk"; + drive-strength = <20>; + bias-disable; + }; + + i2s0_lrck_pin: i2s0_lrck@0 { + pins = "PD13"; + function = "i2s0_lrck"; + drive-strength = <20>; + bias-disable; + }; + + i2s0_dout0_pin: i2s0_dout0@0 { + pins = "PD15"; + function = "i2s0_dout0"; + drive-strength = <20>; + bias-disable; + }; + + i2s0_pins_b: i2s0_pins@1 { + pins = "PD12", "PD13", "PD15"; + function = "gpio_in"; + }; +}; + +&soc { + card0_boot_para@0 { + device_type = "card0_boot_para"; + card_ctrl = <0x0>; + card_high_speed = <0x1>; + card_line = <0x4>; + pinctrl-0 = <&sdc0_pins_uboot>; + clk_type = "typ1"; + }; + addr_mgt: addr_mgt { + compatible = "allwinner,sunxi-addr_mgt"; + type_addr_wifi = <0x0>; + type_addr_bt = <0x0>; + type_addr_eth = <0x0>; + status = "okay"; + }; +}; + +&hwspinlock { + status = "okay"; +}; + +&uart0 { + pinctrl-names = "default", "sleep"; + pinctrl-0 = <&uart0_pins_default>; + pinctrl-1 = <&uart0_pins_sleep>; + status = "okay"; +}; + +&uart1 { + pinctrl-names = "default", "sleep"; + pinctrl-0 = <&uart1_pins_default>; + pinctrl-1 = <&uart1_pins_sleep>; + status = "disabled"; +}; + +&uart2 { + pinctrl-names = "default", "sleep"; + pinctrl-0 = <&uart2_pins_default>; + pinctrl-1 = <&uart2_pins_sleep>; + status = "disabled"; +}; + +&uart3 { + pinctrl-names = "default", "sleep"; + pinctrl-0 = <&uart3_pins_default>; + pinctrl-1 = <&uart3_pins_sleep>; + status = "disabled"; +}; + +&twi0 { + clock-frequency = <400000>; + pinctrl-0 = <&twi0_pins_default>; + pinctrl-1 = <&twi0_pins_sleep>; + pinctrl-names = "default", "sleep"; + /* For stability and backwards compatibility, we recommend setting 'twi_drv_used' to 1 */ + twi_drv_used = <1>; + status = "okay"; +}; + +&soc_pmu0 { + status = "okay"; +}; + +&sdc0 { + pinctrl-names = "default", "sleep"; + pinctrl-0 = <&sdc0_pins_a &sdc0_pins_d>; + pinctrl-1 = <&sdc0_pins_c>; + bus-width = <4>; + cd-used-24M; + cd-gpios = <&pio PC 15 (GPIO_ACTIVE_LOW | GPIO_PULL_UP)>; + /*non-removable;*/ + /*broken-cd;*/ + /*cd-inverted*/ + /*data3-detect;*/ + cap-sd-highspeed; + /*sd-uhs-sdr50;*/ + /*sd-uhs-ddr50;*/ + /*sd-uhs-sdr104;*/ + no-sdio; + no-mmc; + /*sunxi-power-save-mode;*/ + sunxi-dis-signal-vol-sw; + max-frequency = <50000000>; + ctl-spec-caps = <0x8>; + status = "okay"; +}; + +&pwm0_8 { + pinctrl-names = "active", "sleep"; + pinctrl-0 = <&pwm8_pins_active>; + pinctrl-1 = <&pwm8_pins_sleep>; + status = "disabled"; +}; + +&pwm0_9 { + pinctrl-names = "active", "sleep"; + pinctrl-0 = <&pwm9_pins_active>; + pinctrl-1 = <&pwm9_pins_sleep>; + status = "disabled"; +}; + +&spi0 { + pinctrl-0 = <&spi0_pins_default &spi0_pins_cs>; + pinctrl-1 = <&spi0_pins_sleep>; + pinctrl-names = "default", "sleep"; + sunxi,spi-bus-mode = ; + sunxi,spi-cs-mode = ; + status = "disabled"; + + dmas; + dma-names; + spi_board0 { + device_type = "spi_board0"; + compatible = "spi-nor"; + spi-max-frequency = <100000000>; + m25p,fast-read = <1>; + /*individual_lock;*/ + reg = <0x0>; + spi-rx-bus-width = <4>; + spi-tx-bus-width = <4>; + status = "disabled"; + }; +}; + +&spif0 { + clock-frequency = <100000000>; + pinctrl-0 = <&spif_pins_default &spif_pins_cs>; + pinctrl-1 = <&spif_pins_sleep>; + pinctrl-names = "default", "sleep"; + spif-rx-bus-width = <0x4>; + spif-tx-bus-width = <0x4>; + //prefetch_read_mode_enabled; /* choose prefect read mode */ + dtr_mode_enabled; /* choose double edge trigger mode */ + io_mode_enabled; /* 1_x_x && x_x_x mode */ + status = "okay"; + + spif-nor { + device_type = "spi_board0"; + compatible = "spif-nor"; + spi-max-frequency = <0x5f5e100>; + reg = <0x0>; + status = "disabled"; + }; +}; + +&mdio0 { + status = "disabled"; + phy0: ethernet-phy@0 { + /* JL11x1 */ + compatible = "ethernet-phy-id937c.4024", + "ethernet-phy-ieee802.3-c22"; + reg = <0>; + max-speed = <100>; /* Max speed capability for rmii */ + reset-gpios = <&pio PC 16 GPIO_ACTIVE_LOW>; + /* PHY datasheet rst time */ + reset-assert-us = <200000>; + reset-deassert-us = <150000>; + status = "disabled"; + }; +}; + +&gmac0 { + phy-mode = "rmii"; + pinctrl-names = "default", "sleep"; + pinctrl-0 = <&gmac0_pins_default>; + pinctrl-1 = <&gmac0_pins_sleep>; + sunxi,phy-clk-type = <0>; + phy-handle = <&phy0>; + tx-delay = <0>; + rx-delay = <0>; + status = "disabled"; +}; + +&vind0 { + csi_top = <200000000>; + status = "okay"; + + csi0: csi@45820000 { + pinctrl-names = "csi_sm-default","csi_sm-sleep"; + pinctrl-0 = <>; + pinctrl-1 = <>; + }; + + csi1: csi@45821000 { + pinctrl-names = "default","sleep"; + pinctrl-0 = <&ncsi_bt656_pins_a>; + pinctrl-1 = <&ncsi_bt656_pins_b>; + status = "disabled"; + }; + + tdm0: tdm@45908000 { + work_mode = <0x0>; + }; + + isp00:isp@45900000 { + work_mode = <0x0>; + ldci_select = <0x1>; + }; + + isp01:isp@458ffffc { + status = "disabled"; + ldci_select = <0x1>; + }; + + isp10:isp@4 { + status = "disabled"; + }; + + scaler00:scaler@45910000 { + work_mode = <0x0>; + status = "okay"; + }; + + scaler01:scaler@4590fffc { + work_mode = <0xff>; + status = "disabled"; + }; + + scaler10:scaler@45910400 { + work_mode = <0x0>; + status = "okay"; + }; + + scaler11:scaler@459103fc { + work_mode = <0xff>; + status = "disabled"; + }; + + actuator0: actuator@2108180 { + device_type = "actuator0"; + actuator0_slave = <0x18>; + actuator0_af_pwdn = <>; + actuator0_afvdd = "afvcc-csi"; + actuator0_afvdd_vol = <2800000>; + status = "disabled"; + actuator0_name; + }; + + flash0: flash@2108190 { + device_type = "flash0"; + flash0_type = <2>; + flash0_en = <>; + flash0_mode = <>; + flash0_flvdd = ""; + flash0_flvdd_vol = <>; + device_id = <0>; + status = "disabled"; + }; + + sensor0: sensor@5812000 { + device_type = "sensor0"; + sensor0_mname = "gc2083_mipi"; + sensor0_twi_cci_id = <0>; + sensor0_twi_addr = <0x6e>; + sensor0_mclk_id = <0>; + sensor0_pos = "rear"; + sensor0_isp_used = <1>; + sensor0_fmt = <1>; + sensor0_stby_mode = <0>; + sensor0_vflip = <0>; + sensor0_hflip = <0>; + sensor0_iovdd-supply = <>; + sensor0_iovdd_vol = <>; + sensor0_avdd-supply = <>; + sensor0_avdd_vol = <>; + sensor0_dvdd-supply = <>; + sensor0_dvdd_vol = <>; + sensor0_power_en = <>; + sensor0_reset = <&pio PA 2 GPIO_ACTIVE_LOW>; + sensor0_pwdn = <>; + status = "okay"; + act_handle = <>; + }; + + sensor1: sensor@5812010 { + device_type = "sensor1"; + sensor1_mname = "gc1084_mipi_2"; + sensor1_twi_cci_id = <0>; + sensor1_twi_addr = <0x7e>; + sensor1_mclk_id = <1>; + sensor1_pos = "front"; + sensor1_isp_used = <1>; + sensor1_fmt = <1>; + sensor1_stby_mode = <0>; + sensor1_vflip = <0>; + sensor1_hflip = <0>; + sensor1_iovdd-supply = <>; + sensor1_iovdd_vol = <>; + sensor1_avdd-supply = <>; + sensor1_avdd_vol = <>; + sensor1_dvdd-supply = <>; + sensor1_dvdd_vol = <>; + sensor1_power_en = <>; + sensor1_reset = <&pio PD 13 GPIO_ACTIVE_LOW>; + status = "disabled"; + }; + + sensor_list0:sensor_list@200b820 { + sensor00_mname = "gc5035_mipi"; + sensor00_twi_addr = <0x6c>; + sensor00_type = <1>; + sensor00_hflip = <0>; + sensor00_vflip = <0>; + sensor00_act_used = <1>; + sensor00_act_name = "dw9714_act"; + sensor00_act_twi_addr = <0x18>; + sensor01_mname = "ov5675_mipi"; + sensor01_twi_addr = <0x6c>; + sensor01_type = <1>; + sensor01_hflip = <0>; + sensor01_vflip = <0>; + sensor01_act_used = <1>; + sensor01_act_name = "dw9714_act"; + sensor01_act_twi_addr = <0x18>; + sensor02_mname = "sp5409_mipi"; + sensor02_twi_addr = <0x78>; + sensor02_type = <1>; + sensor02_hflip = <0>; + sensor02_vflip = <0>; + sensor02_act_used = <1>; + sensor02_act_name = "dw9714_act"; + sensor02_act_twi_addr = <0x18>; + status = "disabled"; + }; + + sensor_list1:sensor_list@200b830 { + sensor10_mname = "gc02m2_mipi"; + sensor10_twi_addr = <0x20>; + sensor10_type = <1>; + sensor10_hflip = <0>; + sensor10_vflip = <0>; + sensor10_act_used = <0>; + sensor10_act_name = ""; + sensor10_act_twi_addr = <>; + sensor11_mname = "ov02a10_mipi"; + sensor11_twi_addr = <0x7a>; + sensor11_type = <1>; + sensor11_hflip = <1>; + sensor11_vflip = <0>; + sensor11_act_used = <0>; + sensor11_act_name = ""; + sensor11_act_twi_addr = <>; + sensor12_mname = "gc030a_mipi"; + sensor12_twi_addr = <0x42>; + sensor12_type = <1>; + sensor12_hflip = <0>; + sensor12_vflip = <0>; + sensor12_act_used = <0>; + sensor12_act_name = ""; + sensor12_act_twi_addr = <>; + status = "disabled"; + }; + + vinc00:vinc@45830000 { + vinc0_csi_sel = <0>; + vinc0_mipi_sel = <0>; + vinc0_isp_sel = <0>; + vinc0_isp_tx_ch = <0>; + vinc0_tdm_rx_sel = <0>; + vinc0_rear_sensor_sel = <0>; + vinc0_front_sensor_sel = <0>; + vinc0_sensor_list = <0>; + work_mode = <0x0>; + status = "okay"; + }; + + vinc01:vinc@4582fffc { + vinc1_csi_sel = <1>; + vinc1_mipi_sel = <1>; + vinc1_isp_sel = <1>; + vinc1_isp_tx_ch = <0>; + vinc1_tdm_rx_sel = <1>; + vinc1_rear_sensor_sel = <0>; + vinc1_front_sensor_sel = <0>; + vinc1_sensor_list = <0>; + status = "disabled"; + }; + + vinc10:vinc@45831000 { + vinc4_csi_sel = <0>; + vinc4_mipi_sel = <0>; + vinc4_isp_sel = <0>; + vinc4_isp_tx_ch = <0>; + vinc4_tdm_rx_sel = <0>; + vinc4_rear_sensor_sel = <0>; + vinc4_front_sensor_sel = <0>; + vinc4_sensor_list = <0>; + work_mode = <0x0>; + status = "okay"; + }; + + vinc11:vinc@45830ffc { + vinc5_csi_sel = <1>; + vinc5_mipi_sel = <1>; + vinc5_isp_sel = <1>; + vinc5_isp_tx_ch = <0>; + vinc5_tdm_rx_sel = <1>; + vinc5_rear_sensor_sel = <0>; + vinc5_front_sensor_sel = <0>; + vinc5_sensor_list = <0>; + status = "disabled"; + }; + +}; + +&msgbox { + status = "okay"; +}; + +/* audio dirver module -> audio codec */ + +&codec { + tx-hub-en; + rx-sync-en; + + dac-vol = <63>; /* default value:63 range:0->63 */ + dacl-vol = <160>; /* default value:160 range:0->255 */ + adc-vol = <160>; /* default value:160 range:0->255 */ + lineout-gain = <31>; /* default value:31 range:0->31 */ + mic-gain = <31>; /* default value:31 range:0->31 */ + adcdelaytime = <0>; /* default value:0 range:0,5,10,20,30 */ + + pa-pin-max = <1>; + pa-pin-0 = <&pio PC 15 GPIO_ACTIVE_HIGH>; + pa-pin-level-0 = <1>; + pa-pin-msleep-0 = <0>; + + rglt-max = <0>; + //rglt0-mode = "AUDIO"; + //rglt0-voltage = <1800000>; + //rglt1-mode = "PMU"; + //rglt1-voltage = <3300000>; + //rglt1-supply = <®_dldo1>; + + status = "okay"; +}; + +&codec_plat { + status = "okay"; +}; + +&codec_mach { + status = "okay"; + soundcard-mach,cpu { + sound-dai = <&codec_plat>; + }; + soundcard-mach,codec { + sound-dai = <&codec>; + }; +}; + +/* audio dirver module -> I2S/PCM */ +&i2s0_plat { + tdm-num = <0>; + + /* "tx-pin" + * 1. tx pin enable setting. + * 2. we can set it like tx_pin = <3 0> - enable tx_pin0 and tx_pin3. + * + * "rx-pin" + * 1. rx pin enable setting. + * 2. we can set it like rx_pin = <1 2> - enable rx_pin1 and rx_pin2. + * + * "tx-pin-chmap" + * 1. tx pin channel map setting. + * 2. the subscript of value corresponds to the channel number. + * 3. the value corresponds to slot number. + * 4. we can use it like tx-pin1-chmap = <1 2 ... 15> to set pin1 channel map. + * 5. if enabled the pin, but not set "tx-pin-chmap", default set <0 1 2 ...>. + * 6. if the count of value is less than 16, then missing member will be set 0. + * + * rxfifo map + * 1. "rxfifo-pinmap" - set the corresponding pin. + * 2. "rxfifo-chmap" - set the corresponding slot. + * 3. we can use it like rxfifo-pinmap = <0 1 2>; rxfifo-chmap = <1 2 14>; to set rxfifo map. + * 4. the count of value of "rxfifo-pinmap" can != the count of value of "rxfifo-pinmap", + * then missing member would be set 0. + */ + tx-pin = <0>; + rx-pin = <0>; + /* tx-pin0-chmap = <0 1 5>; */ + /* rxfifo-pinmap = <0 0>; */ + /* rxfifo-chmap = <0 1>; */ + + pinctrl-used; + pinctrl-names = "default","sleep"; + pinctrl-0 = <&i2s0_bclk_pin &i2s0_lrck_pin &i2s0_dout0_pin>; + pinctrl-1 = <&i2s0_pins_b>; + tx-hub-en; + rx-sync-en; + status = "okay"; +}; + +&i2s0_mach { + soundcard-mach,format = "i2s"; + soundcard-mach,frame-master = <&i2s0_cpu>; + soundcard-mach,bitclock-master = <&i2s0_cpu>; + /* soundcard-mach,frame-inversion; */ + /* soundcard-mach,bitclock-inversion; */ + soundcard-mach,slot-num = <2>; + soundcard-mach,slot-width = <32>; + status = "okay"; + i2s0_cpu: soundcard-mach,cpu { + sound-dai = <&i2s0_plat>; + /* note: pll freq = 24.576M or 22.5792M * pll-fs */ + soundcard-mach,pll-fs = <1>; + /* note: + * "mclk-fs" + * if not defined it or equal to 0, disable mclk. + * + * "mclk-fp" (if defined "mclk-fs") + * 1. if not defined "mclk-fp", mclk_freq = mclk-fs * sample_rate; + * 2. if defined "mclk-fp" but no value, mclk_freq = mclk-fs * 11.2896M or 12.288M; + * 3. if defined "mclk-fp" with 2 value, like: mclk-fp = ; + * it means: mclk_freq(44.1k fp) = mclk-fs * val1; + * mclk_freq(48k fp) = mclk-fs * val2. + */ + }; + i2s0_codec: soundcard-mach,codec { + sound-dai = <&max98357a>; + }; +}; + +&e907_rproc { + firmware-name = "amp_rv0.bin"; + mboxes = <&msgbox 0>; + mbox-names = "arm-kick"; + auto-boot; + skip-shutdown; + fw-region = <&e907_mem_fw>; + memory-region = <&rv_ddr_reserved>, <&rv_vdev0buffer>, <&rv_vdev0vring0>, <&rv_vdev0vring1>, <&e907_share_irq_table>; + fw-partitions = "riscv0", "riscv0-r"; + fw-partition-sectors = <2432>; + memory-mappings = + /* < DA len PA > */ + /* SRAM ISP */ + < 0x2000000 0xa800 0x2000000 >, + /* SRAM VE */ + < 0x200a800 0x17400 0x200a800 >, + /* SRAM WIFI */ + < 0x68000000 0x1000000 0x68000000 >, + /* DRAM */ + < 0x80000000 0x0fffffff 0x80000000 >; + stop-record-reg = <0x4a00020c>; + + share-irq = "e907"; + status = "okay"; + + rproc_wdt: rproc_wdt@0 { + timeout_ms = <6000>; + try_times = <1>; + reset_type = <0x2>; + panic_on_timeout = <1>; + status = "okay"; + }; +}; +/* +*usb_port_type: usb mode: 0-device, 1-host, 2-otg. +*usb_detect_type: usb hotplug detect mode. 0-none, 1-vbus/id detect, 2-id/dpdm detect. +*usb_detect_mode: 0-thread scan, 1-id gpio interrupt. +*usb_id_gpio: gpio for id detect. +*usb_det_vbus_gpio: gpio for id detect. gpio or "axp_ctrl"; +*usb_wakeup_suspend:0-SUPER_STANDBY, 1-USB_STANDBY. +*/ +&usbc0 { + device_type = "usbc0"; + usb_port_type = <0x0>; + usb_detect_type = <0x0>; + usb_detect_mode = <0x0>; + //usb_id_gpio; + //usb_det_vbus_gpio; + //usb_det_vbus_gpio = "axp_ctrl"; + //det_vbus_supply; + usb_regulator_io = "nocare"; + usb_wakeup_suspend = <0x0>; + usb_luns = <0x3>; + usb_serial_unique = <0x0>; + usb_serial_number = "20080411"; + status = "okay"; +}; + +&udc { + //det_vbus_supply = <&gpio_charger>; + status = "okay"; +}; + +&ehci0 { + //drvvbus-supply = <®_usb_vbus>; + status = "okay"; +}; + +&ohci0 { + //drvvbus-supply = <®_usb_vbus>; + status = "okay"; +}; + +&gpadc0 { + channel_num = <4>; + channel_select = <0x3>; + channel_data_select = <0x0>; + channel_compare_select = <0x0>; + channel_cld_select = <0x0>; + channel_chd_select = <0x0>; + channel0_compare_lowdata = <1700000>; + channel0_compare_higdata = <1200000>; + channel1_compare_lowdata = <460000>; + channel1_compare_higdata = <1200000>; + status = "okay"; +}; + +/*---------------------------------------------------------------------------------- +disp init configuration + +disp_mode (0:screen0) +screenx_output_type (0:none; 1:lcd; 2:tv; 3:hdmi;5:vdpo) +screenx_output_mode (used for hdmi output, 0:480i 1:576i 2:480p 3:576p 4:720p50) + (5:720p60 6:1080i50 7:1080i60 8:1080p24 9:1080p50 10:1080p60) +screenx_output_format (for hdmi, 0:RGB 1:yuv444 2:yuv422 3:yuv420) +screenx_output_bits (for hdmi, 0:8bit 1:10bit 2:12bit 2:16bit) +screenx_output_eotf (for hdmi, 0:reserve 4:SDR 16:HDR10 18:HLG) +screenx_output_cs (for hdmi, 0:undefined 257:BT709 260:BT601 263:BT2020) +screenx_output_dvi_hdmi (for hdmi, 0:undefined 1:dvi mode 2:hdmi mode) +screen0_output_range (for hdmi, 0:default 1:full 2:limited) +screen0_output_scan (for hdmi, 0:no data 1:overscan 2:underscan) +screen0_output_aspect_ratio (for hdmi, 8-same as original picture 9-4:3 10-16:9 11-14:9) +fbx format (4:RGB655 5:RGB565 6:RGB556 7:ARGB1555 8:RGBA5551 9:RGB888 10:ARGB8888 12:ARGB4444) +fbx pixel sequence (0:ARGB 1:BGRA 2:ABGR 3:RGBA) +fb0_scaler_mode_enable(scaler mode enable, used FE) +fbx_width,fbx_height (framebuffer horizontal/vertical pixels, fix to output resolution while equal 0) +lcdx_backlight (lcd init backlight,the range:[0,256],default:197 +lcdx_yy (lcd init screen bright/contrast/saturation/hue, value:0~100, default:50/50/57/50) +lcd0_contrast (LCD contrast, 0~100) +lcd0_saturation (LCD saturation, 0~100) +lcd0_hue (LCD hue, 0~100) +framebuffer software rotation setting: +disp_rotation_used: (0:disable; 1:enable,you must set fbX_width to lcd_y, +set fbX_height to lcd_x) +degreeX: (X:screen index; 0:0 degree; 1:90 degree; 3:270 degree) +degreeX_Y: (X:screen index; Y:layer index 0~15; 0:0 degree; 1:90 degree; 3:270 degree) +devX_output_type : config output type in bootGUI framework in UBOOT-2018. + (0:none; 1:lcd; 2:tv; 4:hdmi;) +devX_output_mode : config output resolution(see include/video/sunxi_display2.h) of bootGUI framework in UBOOT-2018 +devX_screen_id : config display index of bootGUI framework in UBOOT-2018 +devX_do_hpd : whether do hpd detectation or not in UBOOT-2018 +chn_cfg_mode : Hardware DE channel allocation config. 0:single display with 6 + channel, 1:dual display with 4 channel in main display and 2 channel in second + display, 2:dual display with 3 channel in main display and 3 channel in second + in display. +----------------------------------------------------------------------------------*/ +&disp { + disp_init_enable = <1>; + disp_mode = <0>; + + screen0_output_type = <7>; + screen0_output_mode = <4>; + screen0_to_lcd_index = <0>; + + screen1_output_type = <3>; + screen1_output_mode = <10>; + screen1_to_lcd_index = <2>; + + screen1_output_format = <0>; + screen1_output_bits = <0>; + screen1_output_eotf = <4>; + screen1_output_cs = <257>; + screen1_output_dvi_hdmi = <2>; + screen1_output_range = <2>; + screen1_output_scan = <0>; + screen1_output_aspect_ratio = <8>; + + fb_format = <0>; + fb_num = <1>; + fb_debug = <1>; + /**/ + fb0_map = <0 0 0 16>; + fb0_width = <320>; + fb0_height = <192>; + /**/ + fb1_map = <0 2 0 16>; + fb1_width = <300>; + fb1_height = <300>; + /**/ + fb2_map = <1 0 0 16>; + fb2_width = <1280>; + fb2_height = <720>; + /**/ + fb3_map = <1 1 0 16>; + fb3_width = <300>; + fb3_height = <300>; + + chn_cfg_mode = <1>; + disp_para_zone = <1>; +}; + +/*------------------------------------------ +ircut_pin_a : IRCUT PIN+ +ircut_pin_b : IRCUT PIN- +ircut_pin_drv : Set the driver strength for the IR cut pins +ircut_open : Define the GPIO states for opening the IR cut +hold_time : Set the hold time for the IR cut operation (in milliseconds) +--------------------------------------------*/ +&ircut { + ircut_pin_a = <&pio PD 22 GPIO_ACTIVE_HIGH>; + ircut_pin_b = <&pio PD 23 GPIO_ACTIVE_HIGH>; + ircut_pin_drv = <3>; + ircut_open = ; + hold_time = <100>; + status = "okay"; +}; + +&cpu0 { + cpu-supply = <®_vdd_cpu>; +}; + +/ { + max98357a: max98357a { + #sound-dai-cells = <0>; + compatible = "maxim,max98357a"; + status = "okay"; + }; +}; diff --git a/ESP32S3/ICM42688.cpp b/ESP32S3/ICM42688.cpp new file mode 100644 index 0000000..7d27e29 --- /dev/null +++ b/ESP32S3/ICM42688.cpp @@ -0,0 +1,95 @@ +// --- START OF ICM42688.cpp --- +#include "ICM42688.h" + +ICM42688::ICM42688(TwoWire &bus, uint8_t address) { + _bus = &bus; + _address = address; + _accelScale = 0.0f; + _gyroScale = 0.0f; +} + +int ICM42688::begin() { + uint8_t who_am_i = 0; + readRegisters(ICM42688_WHO_AM_I, 1, &who_am_i); + if(who_am_i != ICM42688_DEVICE_ID) { + return -1; // Wrong device + } + + // Reset device + writeRegister(0x4E, 0x01); + delay(100); + + // Set accel and gyro to standby + writeRegister(0x4E, 0x1F); + delay(1); + + // Set accel full scale + writeRegister(0x4F, (uint8_t)AFS::AFS_16G << 5 | (uint8_t)ODR::ODR_1KHZ); + _accelScale = 16.0f / 32768.0f; + + // Set gyro full scale + writeRegister(0x50, (uint8_t)GFS::GFS_2000DPS << 5 | (uint8_t)ODR::ODR_1KHZ); + _gyroScale = 2000.0f / 32768.0f; + + // Turn on accel and gyro + writeRegister(0x4E, 0x0F); + delay(100); + + return 0; +} + +int ICM42688::readSensor() { + uint8_t data[14]; + readRegisters(0x1D, 14, data); + + _t = (int16_t)data[0] << 8 | data[1]; + _ax = (int16_t)data[2] << 8 | data[3]; + _ay = (int16_t)data[4] << 8 | data[5]; + _az = (int16_t)data[6] << 8 | data[7]; + _gx = (int16_t)data[8] << 8 | data[9]; + _gy = (int16_t)data[10] << 8 | data[11]; + _gz = (int16_t)data[12] << 8 | data[13]; + + return 0; +} + +float ICM42688::getAccelX_mss() { return (float)_ax * _accelScale * _G; } +float ICM42688::getAccelY_mss() { return (float)_ay * _accelScale * _G; } +float ICM42688::getAccelZ_mss() { return (float)_az * _accelScale * _G; } + +float ICM42688::getGyroX_rads() { return (float)_gx * _gyroScale * _d2r; } +float ICM42688::getGyroY_rads() { return (float)_gy * _gyroScale * _d2r; } +float ICM42688::getGyroZ_rads() { return (float)_gz * _gyroScale * _d2r; } + +float ICM42688::getGyroX_dps() { return (float)_gx * _gyroScale; } +float ICM42688::getGyroY_dps() { return (float)_gy * _gyroScale; } +float ICM42688::getGyroZ_dps() { return (float)_gz * _gyroScale; } + +float ICM42688::getTemperature_C() { return ((float)_t / _tempScale) + _tempOffset; } + +void ICM42688::writeRegister(uint8_t reg, uint8_t data) { + _bus->beginTransmission(_address); + _bus->write(reg); + _bus->write(data); + _bus->endTransmission(); +} + +uint8_t ICM42688::readRegister(uint8_t reg) { + _bus->beginTransmission(_address); + _bus->write(reg); + _bus->endTransmission(false); + _bus->requestFrom(_address, (uint8_t)1); + uint8_t data = _bus->read(); + return data; +} + +void ICM42688::readRegisters(uint8_t reg, uint8_t count, uint8_t *dest) { + _bus->beginTransmission(_address); + _bus->write(reg); + _bus->endTransmission(false); + _bus->requestFrom(_address, count); + for(uint8_t i = 0; i < count; i++){ + dest[i] = _bus->read(); + } +} +// --- END OF ICM42688.cpp --- \ No newline at end of file diff --git a/ESP32S3/ICM42688.h b/ESP32S3/ICM42688.h new file mode 100644 index 0000000..6ec6429 --- /dev/null +++ b/ESP32S3/ICM42688.h @@ -0,0 +1,85 @@ +// --- START OF ICM42688.h --- +#ifndef ICM42688_H +#define ICM42688_H + +#include "Arduino.h" +#include "Wire.h" +#include "SPI.h" + +// See datasheet for details +#define ICM42688_DEVICE_ID 0x47 +#define ICM42688_WHO_AM_I 0x75 + +/* + ICM42688_I2C class definition + */ +class ICM42688 +{ + public: + enum class AFS { + AFS_16G = 0, + AFS_8G, + AFS_4G, + AFS_2G + }; + + enum class GFS { + GFS_2000DPS = 0, + GFS_1000DPS, + GFS_500DPS, + GFS_250DPS, + GFS_125DPS, + GFS_62_5DPS, + GFS_31_25DPS, + GFS_15_625DPS + }; + + enum class ODR { + ODR_32KHZ = 0x01, + ODR_16KHZ = 0x02, + ODR_8KHZ = 0x03, + ODR_4KHZ = 0x04, + ODR_2KHZ = 0x05, + ODR_1KHZ = 0x06, + ODR_200HZ = 0x07, + ODR_100HZ = 0x08, + ODR_50HZ = 0x09, + ODR_25HZ = 0x0A, + ODR_12_5HZ = 0x0B, + ODR_500HZ = 0x0F + }; + + ICM42688(TwoWire &bus, uint8_t address); + int begin(); + int readSensor(); + float getAccelX_mss(); + float getAccelY_mss(); + float getAccelZ_mss(); + float getGyroX_rads(); + float getGyroY_rads(); + float getGyroZ_rads(); + float getGyroX_dps(); + float getGyroY_dps(); + float getGyroZ_dps(); + float getTemperature_C(); + + private: + TwoWire *_bus; + uint8_t _address; + float _accelScale; + float _gyroScale; + const float _tempScale = 333.87f; + const float _tempOffset = 21.0f; + const float _G = 9.807f; + const float _d2r = 3.14159265359f/180.0f; + int16_t _ax, _ay, _az; + int16_t _gx, _gy, _gz; + int16_t _t; + + void writeRegister(uint8_t reg, uint8_t data); + uint8_t readRegister(uint8_t reg); + void readRegisters(uint8_t reg, uint8_t count, uint8_t *dest); +}; + +#endif +// --- END OF ICM42688.h --- \ No newline at end of file diff --git a/ESP32S3/camera_pins.h b/ESP32S3/camera_pins.h new file mode 100644 index 0000000..6d2e987 --- /dev/null +++ b/ESP32S3/camera_pins.h @@ -0,0 +1,60 @@ +#if defined(CAMERA_MODEL_XIAO_ESP32S3) + #define PWDN_GPIO_NUM -1 + #define RESET_GPIO_NUM -1 + #define XCLK_GPIO_NUM 10 + #define SIOD_GPIO_NUM 40 + #define SIOC_GPIO_NUM 39 + + #define Y9_GPIO_NUM 48 + #define Y8_GPIO_NUM 11 + #define Y7_GPIO_NUM 12 + #define Y6_GPIO_NUM 14 + #define Y5_GPIO_NUM 16 + #define Y4_GPIO_NUM 18 + #define Y3_GPIO_NUM 17 + #define Y2_GPIO_NUM 15 + #define VSYNC_GPIO_NUM 38 + #define HREF_GPIO_NUM 47 + #define PCLK_GPIO_NUM 13 + +#elif defined(CAMERA_MODEL_AI_THINKER) + #define PWDN_GPIO_NUM 32 + #define RESET_GPIO_NUM -1 + #define XCLK_GPIO_NUM 0 + #define SIOD_GPIO_NUM 26 + #define SIOC_GPIO_NUM 27 + + #define Y9_GPIO_NUM 35 + #define Y8_GPIO_NUM 34 + #define Y7_GPIO_NUM 39 + #define Y6_GPIO_NUM 36 + #define Y5_GPIO_NUM 21 + #define Y4_GPIO_NUM 19 + #define Y3_GPIO_NUM 18 + #define Y2_GPIO_NUM 5 + #define VSYNC_GPIO_NUM 25 + #define HREF_GPIO_NUM 23 + #define PCLK_GPIO_NUM 22 + +#elif defined(CAMERA_MODEL_M5STACK_PSRAM) + #define PWDN_GPIO_NUM -1 + #define RESET_GPIO_NUM 15 + #define XCLK_GPIO_NUM 27 + #define SIOD_GPIO_NUM 25 + #define SIOC_GPIO_NUM 23 + + #define Y9_GPIO_NUM 19 + #define Y8_GPIO_NUM 36 + #define Y7_GPIO_NUM 18 + #define Y6_GPIO_NUM 39 + #define Y5_GPIO_NUM 5 + #define Y4_GPIO_NUM 34 + #define Y3_GPIO_NUM 35 + #define Y2_GPIO_NUM 32 + #define VSYNC_GPIO_NUM 22 + #define HREF_GPIO_NUM 26 + #define PCLK_GPIO_NUM 21 + +#else + #error "Camera model not selected" +#endif \ No newline at end of file diff --git a/ESP32S3/compile.ino b/ESP32S3/compile.ino new file mode 100644 index 0000000..380d485 --- /dev/null +++ b/ESP32S3/compile.ino @@ -0,0 +1,1014 @@ +// ===== all_in_one_merged.ino — XIAO ESP32S3 Sense: Camera + Mic (PDM) + IMU (ICM42688 SPI) ===== +// ===== 版本: v2.4-SPIIMU - ICM42688 改为 SPI,避开 I2S 干扰;WAV chunked 播放保持 ===== + +#include +#include +#include +#include +#include "ESP_I2S.h" +#include "freertos/FreeRTOS.h" +#include "freertos/queue.h" +struct WavFmt; +#include // memcmp +#include +#include +#include // <<< 改成 SPI +using namespace websockets; + +// ===== WiFi / Server ===== +const char* WIFI_SSID = "aiglass"; +const char* WIFI_PASS = "xu137227"; +const char* SERVER_HOST = "47.100.161.139"; +const uint16_t SERVER_PORT = 8081; + +static const char* CAM_WS_PATH = "/ws/camera"; +static const char* AUD_WS_PATH = "/ws_audio"; + +// ===== Camera config ===== +#define CAMERA_MODEL_XIAO_ESP32S3 +#include "camera_pins.h" + +framesize_t g_frame_size = FRAMESIZE_VGA; +#define JPEG_QUALITY 17 +#define FB_COUNT 2 +volatile int g_target_fps = 0; // 新增:0=不限,>0 则按该FPS限速发送 + +// 【新增】视频传输性能监控 +volatile unsigned long frame_captured_count = 0; // 采集帧计数 +volatile unsigned long frame_sent_count = 0; // 发送帧计数 +volatile unsigned long frame_dropped_count = 0; // 丢弃帧计数 +volatile unsigned long last_stats_time = 0; // 上次统计时间 +volatile unsigned long ws_send_fail_count = 0; // WebSocket发送失败计数 + +// ===== Mic (PDM RX) ===== +#define I2S_MIC_CLOCK_PIN 42 +#define I2S_MIC_DATA_PIN 41 +const int SAMPLE_RATE = 16000; +const int CHUNK_MS = 20; +const int BYTES_PER_CHUNK = SAMPLE_RATE * CHUNK_MS / 1000 * 2; +const int AUDIO_QUEUE_DEPTH = 10; + +// ===== Speaker (I2S TX → MAX98357A) ===== +#define I2S_SPK_BCLK 7 +#define I2S_SPK_LRCK 8 +#define I2S_SPK_DIN 9 +const int TTS_RATE = 16000; + +// ===== IMU (ICM42688 over SPI) / UDP ===== +// 使用 D0~D3 作为 SPI +#define IMU_SPI_SCK 1 // D0 +#define IMU_SPI_MOSI 2 // D1 +#define IMU_SPI_MISO 3 // D2 +#define IMU_SPI_CS 4 // D3 +const char* UDP_HOST = "47.100.161.139"; +const int UDP_PORT = 12345; + +WiFiUDP udp; + +// ===== WS / Queues / I2S ===== +WebsocketsClient wsCam; +WebsocketsClient wsAud; +volatile bool cam_ws_ready = false; +volatile bool aud_ws_ready = false; +volatile bool snapshot_in_progress = false; // 抓拍期间暂停实时采集 + +typedef camera_fb_t* fb_ptr_t; +QueueHandle_t qFrames; + +typedef struct { + size_t n; + uint8_t data[BYTES_PER_CHUNK]; +} AudioChunk; +QueueHandle_t qAudio; + +#define TTS_QUEUE_DEPTH 48 +typedef struct { uint16_t n; uint8_t data[2048]; } TTSChunk; +QueueHandle_t qTTS; +volatile bool tts_playing = false; + +I2SClass i2sIn; // PDM RX (Mic) +I2SClass i2sOut; // STD TX (Speaker) +volatile bool run_audio_stream = false; + +// ==================================================================== +// Camera +// ==================================================================== +bool apply_framesize(framesize_t fs) { + sensor_t* s = esp_camera_sensor_get(); + if (!s) return false; + int r = s->set_framesize(s, fs); + if (r == 0) { g_frame_size = fs; return true; } + return false; +} + +bool init_camera() { + camera_config_t config; + config.ledc_channel = LEDC_CHANNEL_0; + config.ledc_timer = LEDC_TIMER_0; + config.pin_d0 = Y2_GPIO_NUM; config.pin_d1 = Y3_GPIO_NUM; + config.pin_d2 = Y4_GPIO_NUM; config.pin_d3 = Y5_GPIO_NUM; + config.pin_d4 = Y6_GPIO_NUM; config.pin_d5 = Y7_GPIO_NUM; + config.pin_d6 = Y8_GPIO_NUM; config.pin_d7 = Y9_GPIO_NUM; + config.pin_xclk = XCLK_GPIO_NUM; config.pin_pclk = PCLK_GPIO_NUM; + config.pin_vsync = VSYNC_GPIO_NUM; config.pin_href = HREF_GPIO_NUM; + config.pin_sscb_sda = SIOD_GPIO_NUM; config.pin_sscb_scl = SIOC_GPIO_NUM; + config.pin_pwdn = PWDN_GPIO_NUM; config.pin_reset = RESET_GPIO_NUM; + + config.xclk_freq_hz = 20000000; + config.pixel_format = PIXFORMAT_JPEG; + config.frame_size = g_frame_size; + config.jpeg_quality = JPEG_QUALITY; + config.fb_count = FB_COUNT; + config.fb_location = CAMERA_FB_IN_PSRAM; + config.grab_mode = CAMERA_GRAB_LATEST; + + esp_err_t err = esp_camera_init(&config); + if (err != ESP_OK) { Serial.printf("[CAM] init failed: 0x%x\n", err); return false; } + + sensor_t * s = esp_camera_sensor_get(); + if (s) { + + s->set_hmirror(s, 1); // ★ 新增:水平镜像,与人眼左右一致(1=开,0=关) + s->set_vflip(s, 0); // ★ 新增:垂直翻转;若镜头“倒装”,改为 1 + + s->set_brightness(s, 0); + s->set_contrast(s, 1); + s->set_saturation(s, 1); + s->set_gain_ctrl(s, 1); + s->set_exposure_ctrl(s, 0); + s->set_whitebal(s, 1); + s->set_awb_gain(s, 1); + s->set_aec2(s, 0); + s->set_aec_value(s, 40); + } + return true; +} + +inline void enqueue_frame(camera_fb_t* fb) { + if (!fb) return; + if (xQueueSend(qFrames, &fb, 0) != pdPASS) { + // 队列满,丢弃最旧的帧 + fb_ptr_t drop = nullptr; + if (xQueueReceive(qFrames, &drop, 0) == pdPASS) { + if (drop) { + esp_camera_fb_return(drop); + frame_dropped_count++; // 统计丢帧 + } + } + xQueueSend(qFrames, &fb, 0); + } +} + +void taskCamCapture(void*) { + unsigned long last_log = 0; + unsigned long capture_fail_count = 0; + + for(;;){ + if (snapshot_in_progress) { vTaskDelay(pdMS_TO_TICKS(5)); continue; } + + if (cam_ws_ready) { + camera_fb_t* fb = esp_camera_fb_get(); + if (fb) { + frame_captured_count++; + if (fb->format != PIXFORMAT_JPEG) { + esp_camera_fb_return(fb); + capture_fail_count++; + } + else { + enqueue_frame(fb); + } + } else { + capture_fail_count++; + vTaskDelay(pdMS_TO_TICKS(2)); + } + + // 每5秒打印一次采集统计 + unsigned long now = millis(); + if (now - last_log > 5000) { + int queue_waiting = uxQueueMessagesWaiting(qFrames); + Serial.printf("[CAM-CAP] captured=%lu, queue=%d, fail=%lu\n", + frame_captured_count, queue_waiting, capture_fail_count); + last_log = now; + capture_fail_count = 0; // 重置失败计数 + } + } else { + vTaskDelay(pdMS_TO_TICKS(20)); + } + } +} + +void taskCamSend(void*) { + static TickType_t lastTick = 0; + unsigned long last_log = 0; + unsigned long send_timeout_count = 0; + unsigned long last_sent_time = 0; + + for(;;){ + fb_ptr_t fb = nullptr; + if (xQueueReceive(qFrames, &fb, pdMS_TO_TICKS(100)) == pdPASS) { + if (fb && cam_ws_ready) { + // 发送节流:若设置了目标FPS,则按周期发,丢弃多余帧由 qFrames 机制承担 + if (g_target_fps > 0) { + const int period_ms = 1000 / g_target_fps; + TickType_t now = xTaskGetTickCount(); + int elapsed = (now - lastTick) * portTICK_PERIOD_MS; + if (elapsed < period_ms) vTaskDelay(pdMS_TO_TICKS(period_ms - elapsed)); + lastTick = xTaskGetTickCount(); + } + + unsigned long send_start = millis(); + bool ok = wsCam.sendBinary((const char*)fb->buf, fb->len); + unsigned long send_time = millis() - send_start; + + if (ok) { + frame_sent_count++; + last_sent_time = millis(); + + // 监控发送耗时 + if (send_time > 100) { + Serial.printf("[CAM-SEND] WARNING: send took %lu ms (size=%u)\n", send_time, fb->len); + } + } else { + ws_send_fail_count++; + Serial.println("[CAM-SEND] ERROR: WebSocket send failed, closing..."); + esp_camera_fb_return(fb); + wsCam.close(); + cam_ws_ready = false; + continue; + } + + esp_camera_fb_return(fb); + + // 每5秒打印一次发送统计 + unsigned long now = millis(); + if (now - last_log > 5000) { + unsigned long gap = now - last_sent_time; + Serial.printf("[CAM-SEND] sent=%lu, dropped=%lu, ws_fail=%lu, last_gap=%lu ms\n", + frame_sent_count, frame_dropped_count, ws_send_fail_count, gap); + last_log = now; + } + + } else if (fb) { + esp_camera_fb_return(fb); + } + } else { + // 队列接收超时,检查是否长时间没有帧 + unsigned long now = millis(); + if (cam_ws_ready && last_sent_time > 0 && (now - last_sent_time) > 3000) { + Serial.printf("[CAM-SEND] WARNING: No frame sent for %lu ms\n", now - last_sent_time); + send_timeout_count++; + } + } + } +} +// ==================================================================== +// Mic (PDM RX) +// ==================================================================== +void init_i2s_in(){ + i2sIn.setPinsPdmRx(I2S_MIC_CLOCK_PIN, I2S_MIC_DATA_PIN); + if (!i2sIn.begin(I2S_MODE_PDM_RX, SAMPLE_RATE, I2S_DATA_BIT_WIDTH_16BIT, I2S_SLOT_MODE_MONO)) { + Serial.println("[I2S IN] init failed"); + while(1) { delay(1000); } + } + Serial.println("[I2S IN] PDM RX @16kHz 16bit MONO ready"); +} + +void taskMicCapture(void*){ + const int samples_per_chunk = BYTES_PER_CHUNK / 2; // int16 + for(;;){ + if (run_audio_stream && aud_ws_ready) { + AudioChunk ch; ch.n = BYTES_PER_CHUNK; + int16_t* out = reinterpret_cast(ch.data); + int i = 0; + while (i < samples_per_chunk){ + int v = i2sIn.read(); + if (v == -1) { delay(1); continue; } + out[i++] = (int16_t)v; + } + if (xQueueSend(qAudio, &ch, 0) != pdPASS){ + AudioChunk dump; + xQueueReceive(qAudio, &dump, 0); + xQueueSend(qAudio, &ch, 0); + } + } else { + vTaskDelay(pdMS_TO_TICKS(5)); + } + } +} + +void taskMicUpload(void*){ + for(;;){ + if (run_audio_stream && aud_ws_ready){ + AudioChunk ch; + if (xQueueReceive(qAudio, &ch, pdMS_TO_TICKS(100)) == pdPASS){ + wsAud.sendBinary((const char*)ch.data, ch.n); + } + } else { + vTaskDelay(pdMS_TO_TICKS(10)); + } + } +} + +// ==================================================================== +// Speaker (I2S TX) + HTTP /stream.wav (chunked-safe) +// ==================================================================== +void init_i2s_out(){ + i2sOut.setPins(I2S_SPK_BCLK, I2S_SPK_LRCK, I2S_SPK_DIN); + if (!i2sOut.begin(I2S_MODE_STD, TTS_RATE, I2S_DATA_BIT_WIDTH_32BIT, I2S_SLOT_MODE_STEREO)) { + Serial.println("[I2S OUT] init failed"); + while(1){ delay(1000); } + } + Serial.println("[I2S OUT] STD TX @16kHz 32bit STEREO ready"); +} + +struct WavFmt { + uint16_t audioFormat; // 1=PCM + uint16_t numChannels; // 1=mono + uint32_t sampleRate; // 16000 + uint32_t byteRate; + uint16_t blockAlign; + uint16_t bitsPerSample; // 16 +}; + +static inline void mono16_to_stereo32_msb(const int16_t* in, size_t nSamp, int32_t* outLR, float gain = 0.7f) { + for (size_t i = 0; i < nSamp; ++i) { + int32_t s = (int32_t)((float)in[i] * gain); + int32_t v32 = s << 16; + outLR[i*2 + 0] = v32; + outLR[i*2 + 1] = v32; + } +} + +// === chunked 读取辅助 === +static bool read_line(WiFiClient& cli, String& line, uint32_t timeout_ms=3000){ + line = ""; + uint32_t t0 = millis(); + while (millis() - t0 < timeout_ms){ + while (cli.available()){ + char ch = (char)cli.read(); + if (ch == '\n'){ + if (line.endsWith("\r")) line.remove(line.length()-1); + return true; + } + line += ch; + } + delay(1); + } + return false; +} + +static bool readN_http_body(WiFiClient& cli, uint8_t* buf, size_t n, bool chunked, size_t& chunk_left, uint32_t timeout_ms=3000){ + size_t got = 0; + uint32_t t0 = millis(); + + while (got < n){ + if (!cli.connected()) return false; + if (!chunked){ + int avail = cli.available(); + if (avail > 0){ + int toread = (int)min((size_t)avail, n - got); + int r = cli.read(buf + got, toread); + if (r > 0) got += r; + } else { + if (millis() - t0 > timeout_ms) return false; + delay(1); + } + } else { + if (chunk_left == 0){ + String szline; + if (!read_line(cli, szline, timeout_ms)) return false; + int sc = szline.indexOf(';'); + if (sc >= 0) szline = szline.substring(0, sc); + szline.trim(); + unsigned long sz = strtoul(szline.c_str(), nullptr, 16); + if (sz == 0){ + String dummy; + read_line(cli, dummy, 500); + return false; + } + chunk_left = (size_t)sz; + } + int avail = cli.available(); + if (avail > 0){ + size_t want = min(n - got, chunk_left); + int toread = (int)min((size_t)avail, want); + int r = cli.read(buf + got, toread); + if (r > 0){ + got += r; + chunk_left -= (size_t)r; + if (chunk_left == 0){ + while (cli.available() < 2) { if (millis() - t0 > timeout_ms) return false; delay(1); } + cli.read(); cli.read(); + } + } + } else { + if (millis() - t0 > timeout_ms) return false; + delay(1); + } + } + } + return true; +} + +static bool parse_wav_header(WiFiClient& cli, WavFmt& fmt, uint32_t& dataRemaining, bool chunked, size_t& chunk_left){ + uint8_t hdr12[12]; + if (!readN_http_body(cli, hdr12, 12, chunked, chunk_left)) return false; + if (memcmp(hdr12, "RIFF", 4) != 0 || memcmp(hdr12 + 8, "WAVE", 4) != 0) return false; + + bool gotFmt = false; + dataRemaining = 0; + + while (true) { + uint8_t chdr[8]; + if (!readN_http_body(cli, chdr, 8, chunked, chunk_left)) return false; + uint32_t sz = (uint32_t)chdr[4] | ((uint32_t)chdr[5] << 8) | ((uint32_t)chdr[6] << 16) | ((uint32_t)chdr[7] << 24); + + if (memcmp(chdr, "fmt ", 4) == 0) { + if (sz < 16) return false; + uint8_t fmtbuf[32]; + size_t toread = min(sz, (uint32_t)sizeof(fmtbuf)); + if (!readN_http_body(cli, fmtbuf, toread, chunked, chunk_left)) return false; + uint32_t left = sz - (uint32_t)toread; + while (left){ + uint8_t dump[64]; + size_t d = min((uint32_t)sizeof(dump), left); + if (!readN_http_body(cli, dump, d, chunked, chunk_left)) return false; + left -= d; + } + fmt.audioFormat = (uint16_t) (fmtbuf[0] | (fmtbuf[1] << 8)); + fmt.numChannels = (uint16_t) (fmtbuf[2] | (fmtbuf[3] << 8)); + fmt.sampleRate = (uint32_t) (fmtbuf[4] | (fmtbuf[5] << 8) | (fmtbuf[6] << 16) | (fmtbuf[7] << 24)); + fmt.byteRate = (uint32_t) (fmtbuf[8] | (fmtbuf[9] << 8) | (fmtbuf[10] << 16) | (fmtbuf[11] << 24)); + fmt.blockAlign = (uint16_t) (fmtbuf[12] | (fmtbuf[13] << 8)); + fmt.bitsPerSample = (uint16_t) (fmtbuf[14] | (fmtbuf[15] << 8)); + gotFmt = true; + } + else if (memcmp(chdr, "data", 4) == 0) { + if (!gotFmt) return false; + dataRemaining = sz; + return true; + } + else { + uint32_t left = sz; + while (left){ + uint8_t dump[128]; + size_t d = min((uint32_t)sizeof(dump), left); + if (!readN_http_body(cli, dump, d, chunked, chunk_left)) return false; + left -= d; + } + } + } +} + +// ---- HTTP 播放任务 +static TaskHandle_t taskHttpPlayHandle = nullptr; +static volatile bool http_play_running = false; + +void taskHttpPlay(void*){ + http_play_running = true; + WiFiClient cli; + + auto readLine = [&](String& out, uint32_t timeout_ms)->bool { + out = ""; + uint32_t t0 = millis(); + while (millis() - t0 < timeout_ms) { + while (cli.available()) { + char c = (char)cli.read(); + if (c == '\r') continue; + if (c == '\n') return true; + out += c; + if (out.length() > 1024) return false; + } + delay(1); + } + return false; + }; + + auto readNRaw = [&](uint8_t* dst, size_t n, uint32_t timeout_ms)->bool { + size_t got = 0; + uint32_t t0 = millis(); + while (got < n) { + if (!cli.connected()) return false; + int avail = cli.available(); + if (avail > 0) { + int take = (int)min((size_t)avail, n - got); + int r = cli.read(dst + got, take); + if (r > 0) { got += r; continue; } + } + if (millis() - t0 > timeout_ms) return false; + delay(1); + } + return true; + }; + + auto makeBodyReader = [&](bool& is_chunked, uint32_t& chunk_left){ + return [&](uint8_t* dst, size_t n, uint32_t timeout_ms)->bool { + size_t filled = 0; + uint32_t t0 = millis(); + while (filled < n) { + if (!cli.connected()) return false; + if (is_chunked) { + if (chunk_left == 0) { + String szLine; + if (!readLine(szLine, timeout_ms)) return false; + int sc = szLine.indexOf(';'); + if (sc >= 0) szLine = szLine.substring(0, sc); + szLine.trim(); + uint32_t sz = 0; + if (sscanf(szLine.c_str(), "%x", &sz) != 1) return false; + if (sz == 0) { String dummy; readLine(dummy, 200); return false; } + chunk_left = sz; + } + size_t need = (size_t)min(chunk_left, (uint32_t)(n - filled)); + while (cli.available() < (int)need) { + if (millis() - t0 > timeout_ms) return false; + if (!cli.connected()) return false; + delay(1); + } + int r = cli.read(dst + filled, need); + if (r <= 0) { + if (millis() - t0 > timeout_ms) return false; + delay(1); continue; + } + filled += r; + chunk_left -= r; + if (chunk_left == 0) { + char crlf[2]; + if (!readNRaw((uint8_t*)crlf, 2, 200)) return false; + } + } else { + if (!readNRaw(dst + filled, n - filled, timeout_ms)) return false; + filled = n; + } + } + return true; + }; + }; + + static int32_t outLR[1024 * 2]; + const uint32_t BODY_TIMEOUT_MS = 1500; + + while (http_play_running) { + if (!cli.connected()) { + Serial.println("[AUDIO] HTTP connect..."); + if (!cli.connect(SERVER_HOST, SERVER_PORT)) { delay(500); continue; } + String req = + String("GET /stream.wav HTTP/1.1\r\n") + + "Host: " + SERVER_HOST + ":" + String(SERVER_PORT) + "\r\n" + + "Connection: keep-alive\r\n\r\n"; + cli.print(req); + } + + bool header_ok = false; + bool is_chunked = false; + uint32_t content_len = 0; + { + String line; uint32_t t0 = millis(); + while (millis() - t0 < 3000) { + if (!readLine(line, 1000)) { if (!cli.connected()) break; continue; } + String u = line; u.toLowerCase(); + if (u.startsWith("transfer-encoding:")) { if (u.indexOf("chunked") >= 0) is_chunked = true; } + else if (u.startsWith("content-length:")) { content_len = (uint32_t) strtoul(u.substring(strlen("content-length:")).c_str(), nullptr, 10); } + if (line.length() == 0) { header_ok = true; break; } + } + } + if (!header_ok) { cli.stop(); delay(300); continue; } + + uint32_t chunk_left = 0; + auto readBody = makeBodyReader(is_chunked, chunk_left); + + uint8_t hdr12[12]; + if (!readBody(hdr12, 12, 1000)) { cli.stop(); delay(300); continue; } + if (memcmp(hdr12, "RIFF", 4) != 0 || memcmp(hdr12 + 8, "WAVE", 4) != 0) { cli.stop(); delay(300); continue; } + + bool gotFmt = false, gotData = false; + uint8_t chdr[8]; + uint16_t audioFormat=0, numChannels=0, bitsPerSample=0; + uint32_t sampleRate=0; + + while (!gotData) { + if (!readBody(chdr, 8, 1000)) { cli.stop(); delay(300); goto reconnect; } + uint32_t sz = (uint32_t)chdr[4] | ((uint32_t)chdr[5]<<8) | ((uint32_t)chdr[6]<<16) | ((uint32_t)chdr[7]<<24); + + if (memcmp(chdr, "fmt ", 4) == 0) { + if (sz < 16) { cli.stop(); delay(300); goto reconnect; } + uint8_t fmtbuf[32]; + size_t toread = min(sz, (uint32_t)sizeof(fmtbuf)); + if (!readBody(fmtbuf, toread, 1000)) { cli.stop(); delay(300); goto reconnect; } + if (sz > toread) { + size_t left = sz - toread; + while (left) { uint8_t dump[128]; size_t d = min(left, sizeof(dump)); + if (!readBody(dump, d, 1000)) { cli.stop(); delay(300); goto reconnect; } + left -= d; + } + } + audioFormat = (uint16_t)(fmtbuf[0] | (fmtbuf[1] << 8)); + numChannels = (uint16_t)(fmtbuf[2] | (fmtbuf[3] << 8)); + sampleRate = (uint32_t)(fmtbuf[4] | (fmtbuf[5] << 8) | (fmtbuf[6] << 16) | (fmtbuf[7] << 24)); + bitsPerSample = (uint16_t)(fmtbuf[14] | (fmtbuf[15] << 8)); + gotFmt = true; + } + else if (memcmp(chdr, "data", 4) == 0) { + if (!gotFmt) { cli.stop(); delay(300); goto reconnect; } + gotData = true; + } + else { + size_t left = sz; + while (left) { uint8_t dump[128]; size_t d = min(left, sizeof(dump)); + if (!readBody(dump, d, 1000)) { cli.stop(); delay(300); goto reconnect; } + left -= d; + } + } + } + + if (!(audioFormat==1 && numChannels==1 && bitsPerSample==16 && (sampleRate==8000 || sampleRate==12000 || sampleRate==16000))) { + Serial.printf("[AUDIO] unsupported fmt: ch=%u bits=%u sr=%u af=%u\n", + numChannels, bitsPerSample, sampleRate, audioFormat); + cli.stop(); delay(300); continue; + } + Serial.printf("[AUDIO] WAV ok: %u/16bit/mono (chunked=%d)\n", sampleRate, is_chunked ? 1 : 0); + + static uint32_t current_out_rate = 0; + if (current_out_rate != sampleRate) { + // 重新配置I2S输出采样率以匹配服务端WAV + i2sOut.begin(I2S_MODE_STD, (int)sampleRate, I2S_DATA_BIT_WIDTH_32BIT, I2S_SLOT_MODE_STEREO); + current_out_rate = sampleRate; + Serial.printf("[I2S OUT] reconfig to %u Hz\n", sampleRate); + } + + while (http_play_running) { + uint8_t inbuf[2048]; + size_t filled = 0; + + // 根据采样率计算20ms字节数(mono,16bit) + uint32_t bytes20 = (sampleRate * 2 * 20) / 1000; // 16k=640,12k=480,8k=320 + if (bytes20 < 2) bytes20 = 2; + + if (!readBody(inbuf, bytes20, BODY_TIMEOUT_MS)) { break; } + filled = bytes20; + + while (filled + bytes20 <= sizeof(inbuf)) { + if (!readBody(inbuf + filled, bytes20, 2)) { break; } + filled += bytes20; + } + + if (filled & 1) filled -= 1; + if (filled == 0) { vTaskDelay(pdMS_TO_TICKS(1)); continue; } + + size_t samp = filled / 2; + mono16_to_stereo32_msb((const int16_t*)inbuf, samp, outLR, 0.8f); + + size_t bytes = samp * 2 * sizeof(int32_t); + size_t off = 0; + while (off < bytes && http_play_running) { + size_t wrote = i2sOut.write((uint8_t*)outLR + off, bytes - off); + if (wrote == 0) vTaskDelay(pdMS_TO_TICKS(1)); + else off += wrote; + } + } + + reconnect: + cli.stop(); + delay(200); + } + + cli.stop(); + vTaskDelete(nullptr); +} + +void startStreamWav(){ + if (taskHttpPlayHandle) return; + xTaskCreatePinnedToCore(taskHttpPlay, "http_wav", 8192, nullptr, 2, &taskHttpPlayHandle, 0); + Serial.println("[AUDIO] http_wav task started"); +} +void stopStreamWav(){ + if (!taskHttpPlayHandle) return; + http_play_running = false; + vTaskDelay(pdMS_TO_TICKS(50)); + taskHttpPlayHandle = nullptr; + Serial.println("[AUDIO] http_wav task stopped"); +} + +// ==================================================================== +// TTS(二进制分片)保留但默认不启用 +// ==================================================================== +void taskTTSPlay(void*){ + static int32_t stereo32Buf[1024*2]; + for(;;){ + if (!tts_playing){ vTaskDelay(pdMS_TO_TICKS(5)); continue; } + TTSChunk ch; + if (xQueueReceive(qTTS, &ch, pdMS_TO_TICKS(50)) == pdPASS){ + size_t inSamp = ch.n / 2; + int16_t* inPtr = (int16_t*)ch.data; + size_t outPairs = 0; + for (size_t i = 0; i < inSamp; ++i){ + int32_t s = (int32_t)inPtr[i]; + s = (s * 19660) / 32768; + int32_t v32 = s << 16; + stereo32Buf[outPairs*2 + 0] = v32; + stereo32Buf[outPairs*2 + 1] = v32; + outPairs++; + if (outPairs >= 1024){ + size_t bytes = outPairs * 2 * sizeof(int32_t); + size_t off = 0; + while (off < bytes){ + size_t wrote = i2sOut.write((uint8_t*)stereo32Buf + off, bytes - off); + if (wrote == 0) vTaskDelay(pdMS_TO_TICKS(1)); else off += wrote; + } + outPairs = 0; + } + } + if (outPairs){ + size_t bytes = outPairs * 2 * sizeof(int32_t); + size_t off = 0; + while (off < bytes){ + size_t wrote = i2sOut.write((uint8_t*)stereo32Buf + off, bytes - off); + if (wrote == 0) vTaskDelay(pdMS_TO_TICKS(1)); else off += wrote; + } + } + } + } +} + +inline void tts_reset_queue(){ if (qTTS) xQueueReset(qTTS); } + +// ==================================================================== +// IMU (ICM42688 over SPI) 50Hz via UDP +// ==================================================================== + +// --- ICM42688-P registers (Bank0) --- +#define REG_WHO_AM_I 0x75 // expect 0x47 +#define REG_BANK_SEL 0x76 +#define REG_PWR_MGMT0 0x4E // 0x0F => accel+gyro LN +#define REG_TEMP_H 0x1D // then ACC(1F..24), GYR(25..2A) +#define BURST_FIRST REG_TEMP_H +#define BURST_COUNT 14 + +// scale (常见默认为 ±16g / ±2000 dps) +static const float ACC_LSB_PER_G = 2048.0f; // 1 g = 2048 LSB +static const float GYR_LSB_PER_DPS = 16.4f; // 1 dps = 16.4 LSB +static const float G = 9.80665f; +static const float TEMP_SENS = 132.48f; // °C/LSB +static const float TEMP_OFFSET = 25.0f; + +static inline void imu_cs_low() { digitalWrite(IMU_SPI_CS, LOW); } +static inline void imu_cs_high() { digitalWrite(IMU_SPI_CS, HIGH); } + +uint8_t imu_read8(uint8_t reg){ + imu_cs_low(); + SPI.transfer(reg | 0x80); + uint8_t v = SPI.transfer(0x00); + imu_cs_high(); + return v; +} +void imu_write8(uint8_t reg, uint8_t val){ + imu_cs_low(); + SPI.transfer(reg & 0x7F); + SPI.transfer(val); + imu_cs_high(); +} +void imu_readn(uint8_t start_reg, uint8_t* dst, size_t n){ + imu_cs_low(); + SPI.transfer(start_reg | 0x80); + for (size_t i=0;iint16_t { + return (int16_t)((raw[idx] << 8) | raw[idx+1]); + }; + + int16_t tr = s16(0); + int16_t axr = s16(2); + int16_t ayr = s16(4); + int16_t azr = s16(6); + int16_t gxr = s16(8); + int16_t gyr = s16(10); + int16_t gzr = s16(12); + + tempC = (float)tr / TEMP_SENS + TEMP_OFFSET; + ax = ((float)axr / ACC_LSB_PER_G) * G; + ay = ((float)ayr / ACC_LSB_PER_G) * G; + az = ((float)azr / ACC_LSB_PER_G) * G; + gx = (float)gxr / GYR_LSB_PER_DPS; + gy = (float)gyr / GYR_LSB_PER_DPS; + gz = (float)gzr / GYR_LSB_PER_DPS; + + return true; +} + +// 轻微平滑,便于观察;不改变 UDP 字段名 +static const float EMA_ALPHA = 0.20f; +bool ema_inited = false; +float ax_f=0, ay_f=0, az_f=0; + +void taskImuLoop(void*){ + for(;;){ + static bool inited = false; + if (!inited){ + inited = imu_init_spi(); + if (!inited){ vTaskDelay(pdMS_TO_TICKS(500)); continue; } + Serial.println("[IMU] init OK (SPI)"); + } + + float tempC, ax, ay, az, gx, gy, gz; + if (!imu_read_once(tempC, ax, ay, az, gx, gy, gz)){ + inited = false; vTaskDelay(pdMS_TO_TICKS(50)); continue; + } + + if (!ema_inited){ ax_f=ax; ay_f=ay; az_f=az; ema_inited=true; } + else { + ax_f = EMA_ALPHA*ax + (1-EMA_ALPHA)*ax_f; + ay_f = EMA_ALPHA*ay + (1-EMA_ALPHA)*ay_f; + az_f = EMA_ALPHA*az + (1-EMA_ALPHA)*az_f; + } + + char buf[256]; + unsigned long ts = millis(); + int n = snprintf(buf, sizeof(buf), + "{\"ts\":%lu,\"temp_c\":%.2f," + "\"accel\":{\"x\":%.3f,\"y\":%.3f,\"z\":%.3f}," + "\"gyro\":{\"x\":%.3f,\"y\":%.3f,\"z\":%.3f}}", + ts, tempC, ax_f, ay_f, az_f, gx, gy, gz); + + if (n > 0) { + udp.beginPacket(UDP_HOST, UDP_PORT); + udp.write((const uint8_t*)buf, n); + udp.endPacket(); + } + vTaskDelay(pdMS_TO_TICKS(20)); // 50 Hz + } +} + +// ==================================================================== +// Setup / Loop +// ==================================================================== +void setup() { + Serial.begin(115200); + delay(300); + + WiFi.mode(WIFI_STA); + WiFi.setSleep(false); + esp_wifi_set_ps(WIFI_PS_NONE); + esp_wifi_set_protocol(WIFI_IF_STA, WIFI_PROTOCOL_11B | WIFI_PROTOCOL_11G | WIFI_PROTOCOL_11N); + WiFi.setTxPower(WIFI_POWER_19_5dBm); + + WiFi.begin(WIFI_SSID, WIFI_PASS); + Serial.print("[WiFi] connecting"); + while (WiFi.status()!=WL_CONNECTED){ delay(300); Serial.print("."); } + Serial.println(" OK " + WiFi.localIP().toString()); + + if (!init_camera()) { Serial.println("[CAM] init failed, reboot..."); delay(1500); esp_restart(); } + + udp.begin(0); + + init_i2s_in(); + init_i2s_out(); + + qFrames = xQueueCreate(3, sizeof(fb_ptr_t)); // 增加到3个缓冲,减少丢帧 + qAudio = xQueueCreate(AUDIO_QUEUE_DEPTH, sizeof(AudioChunk)); + qTTS = xQueueCreate(TTS_QUEUE_DEPTH, sizeof(TTSChunk)); + + xTaskCreatePinnedToCore(taskCamCapture, "cam_cap", 10240, NULL, 4, NULL, 1); + xTaskCreatePinnedToCore(taskCamSend, "cam_snd", 8192, NULL, 3, NULL, 1); + xTaskCreatePinnedToCore(taskMicCapture, "mic_cap", 4096, NULL, 2, NULL, 0); + xTaskCreatePinnedToCore(taskMicUpload, "mic_upl", 4096, NULL, 2, NULL, 1); + xTaskCreatePinnedToCore(taskImuLoop, "imu_loop", 4096, NULL, 2, NULL, 0); + xTaskCreatePinnedToCore(taskTTSPlay, "tts_play", 4096, NULL, 2, NULL, 0); + + wsCam.onEvent([](WebsocketsEvent ev, String){ + if (ev == WebsocketsEvent::ConnectionOpened) { + cam_ws_ready = true; + Serial.println("[WS-CAM] open"); + // 重置统计 + frame_sent_count = 0; + frame_dropped_count = 0; + ws_send_fail_count = 0; + last_stats_time = millis(); + } + if (ev == WebsocketsEvent::ConnectionClosed) { + cam_ws_ready = false; + Serial.printf("[WS-CAM] closed (sent=%lu, dropped=%lu, fail=%lu)\n", + frame_sent_count, frame_dropped_count, ws_send_fail_count); + } + }); + + wsCam.onMessage([](WebsocketsMessage msg){ + if (msg.isText()){ + String cmd = msg.data(); cmd.trim(); + if (cmd.startsWith("SET:FRAMESIZE=")) { + String v = cmd.substring(strlen("SET:FRAMESIZE=")); + v.toUpperCase(); + framesize_t fs = g_frame_size; + if (v == "SVGA") fs = FRAMESIZE_SVGA; + else if (v == "XGA") fs = FRAMESIZE_XGA; + else if (v == "VGA") fs = FRAMESIZE_VGA; + if (apply_framesize(fs)) Serial.printf("[CAM] framesize set to %s\n", v.c_str()); + else Serial.printf("[CAM] framesize set failed: %s\n", v.c_str()); + } + else if (cmd.startsWith("SET:QUALITY=")) { // 新增:动态画质 + int q = cmd.substring(strlen("SET:QUALITY=")).toInt(); + q = constrain(q, 5, 40); + sensor_t* s = esp_camera_sensor_get(); + if (s) { s->set_quality(s, q); Serial.printf("[CAM] quality=%d\n", q); } + } + else if (cmd.startsWith("SET:FPS=")) { // 新增:发送节流FPS + int f = cmd.substring(strlen("SET:FPS=")).toInt(); + g_target_fps = (f <= 0 ? 0 : constrain(f, 5, 60)); + Serial.printf("[CAM] target_fps=%d\n", g_target_fps); + } + + else if (cmd == "SNAP:HQ") { + Serial.println("[CAM] SNAP:HQ request"); + if (snapshot_in_progress) return; + snapshot_in_progress = true; + sensor_t* s = esp_camera_sensor_get(); + framesize_t old_fs = g_frame_size; + int old_q = JPEG_QUALITY; + // 目标分辨率:XGA(若需更高可改为 SXGA/UXGA,视PSRAM稳定性) + framesize_t target_fs = FRAMESIZE_SXGA; + if (s) { + s->set_framesize(s, target_fs); + s->set_quality(s, 18); // 数值越小越清晰 + } + vTaskDelay(pdMS_TO_TICKS(500)); + camera_fb_t* fb = esp_camera_fb_get(); + if (fb && fb->format == PIXFORMAT_JPEG) { + wsCam.send("SNAP:BEGIN"); + bool ok = wsCam.sendBinary((const char*)fb->buf, fb->len); + wsCam.send("SNAP:END"); + if (!ok) { Serial.println("[CAM] SNAP send failed"); } + esp_camera_fb_return(fb); + } else { + if (fb) esp_camera_fb_return(fb); + Serial.println("[CAM] SNAP: capture failed"); + } + if (s) { + s->set_framesize(s, old_fs); + s->set_quality(s, old_q); + } + snapshot_in_progress = false; + } + } + }); + + wsAud.onEvent([](WebsocketsEvent ev, String){ + if (ev == WebsocketsEvent::ConnectionOpened) { aud_ws_ready = true; Serial.println("[WS-AUD] open"); } + if (ev == WebsocketsEvent::ConnectionClosed) { + aud_ws_ready = false; + Serial.println("[WS-AUD] closed"); + stopStreamWav(); + } + }); + + wsAud.onMessage([](WebsocketsMessage msg){ + if (msg.isText()){ + String s = msg.data(); s.trim(); + if (s == "RESTART"){ + run_audio_stream = false; xQueueReset(qAudio); delay(50); + wsAud.send("START"); run_audio_stream = true; + } + } + }); +} + +void loop() { + if (!wsCam.available()) { + if (wsCam.connect(SERVER_HOST, SERVER_PORT, CAM_WS_PATH)) { + Serial.println("[WS-CAM] connected"); + } else { Serial.println("[WS-CAM] retry in 1s..."); delay(1000); } + } + + if (!wsAud.available()) { + if (wsAud.connect(SERVER_HOST, SERVER_PORT, AUD_WS_PATH)) { + Serial.println("[WS-AUD] connected"); + delay(50); + run_audio_stream = true; + wsAud.send("START"); + startStreamWav(); // /stream.wav (chunked) + } else { Serial.println("[WS-AUD] retry in 2s..."); delay(2000); } + } + + wsCam.poll(); + wsAud.poll(); + delay(2); +} diff --git a/README.md b/README.md index 8a89e51..9f457db 100644 --- a/README.md +++ b/README.md @@ -1,2 +1,346 @@ -# NaviGlassFirmware - +# Avaota F1 开发与集成 + +> 面向仓库根目录的总览文档,整合 Day1–Day9 日志、任务清单与完成总结。 + +--- + +## 1. 项目简介 + +本项目面向 **Avaota F1 AI 机器人**,基于 **全志 V821 / 32-bit RISC‑V** SoC,目标是在 Tina Linux 固件上实现一套「可量产」的机器人终端固件,集成: + +- 音频采集(板载模拟麦克风)与播放(I2S + MAX98357A) +- IMU 六轴姿态传感(ICM‑42688‑P) +- GC2083 MIPI 摄像头 JPEG 图像采集 +- UDP / HTTP / WebSocket 网络通讯 +- 多线程主程序与静态链接交叉编译流程 + +文档与代码组织按「Day1–Day9 开发日志 + 任务清单 + 完成总结」推进,可作为以后移植到其他 Tina Linux / 全志平台的模板工程。 + +目前对话的位置是本地Windows 11系统的主机,用于开发的环境是局域网中的Ubuntu服务器。 + +--- + +## 2. 硬件与开发环境 + +### 2.1 目标硬件(板端) + +- **SoC**:全志 V821,32‑bit RISC‑V 架构 +- **板载外设** + - 模拟麦克风 → 内置 Audio Codec(audiocodec) + - I2S 数字功放:MAX98357A(BCLK/LRCK/DOUT:PD12/PD13/PD15) + - 摄像头:GC2083,MIPI‑CSI2,典型输出 1280×720 @ 20fps + - IMU:ICM‑42688‑P(GPIO 模拟 SPI) +- **操作系统**:Tina Linux(基于 OpenWrt 的 Allwinner SDK) + +### 2.2 主机开发环境(PC) + +- **系统**:Ubuntu 24.04 LTS(同时也有 Windows + WSL 的混合开发) +- **工具链 & SDK** + - Tina SDK:`tina-v821-release` + - `/home/rongye/ProgramFiles/AvaotaF1/avaota_sdk/tina-v821-release` 这是SDK位置 + - 交叉编译工具链: + - **当前使用**:`prebuilt/rootfsbuilt/riscv/nds32le-linux-musl-v5d` ⭐ **musl 工具链(与开发板兼容)** + - 编译器前缀:`riscv32-linux-musl-` + - ~~已废弃~~:`out/toolchain/nds32le-linux-glibc-v5d` (glibc 工具链,与板端 musl libc 1.2.4 不兼容) + - `/home/rongye/ProgramFiles/AvaotaF1/avaota_app_demo` 这是交叉编译的位置 + - Python:通过 `python-is-python3` 或为遗留脚本装 python2 并软链到 `python` + +### 2.3 开发主机准备要点(Ubuntu 24.04) + +- 开启 i386 架构以兼容旧版 32 位库 +- 手动安装被移除的 `libncurses5` / `libtinfo5` +- 安装 bison / flex / 交叉编译依赖,修复 `lunch` / `make` 时报错 +- 注意 `make -j` 一定要限制并行度(如 `-j8`),避免 OOM + +--- + +## 3. 仓库结构建议 + +实际仓库结构可按以下思路组织(示例): + +```text +. +├── ../Docs/DevLogs/ # (位于上级目录) 每日开发日志 +│ ├── Day1.md … Day18.md +├── docs/ # 本地硬件/SDK文档 +│ ├── 1.png … 2.png +│ ├── AvaotaF1.md +│ ├── 引脚.md +│ ├── TinaSDK-Docs/ +│ ├── tina_files_clean.csv +├── ESP32S3/ # 可参考的ESP32S3固件 +├── src/ +│ ├── audio/ # AudioCapture / AudioPlayer +│ ├── camera/ # Camera 类 / MPP 封装 +│ ├── imu/ # ICM‑42688 SPI 驱动与测试 +│ ├── network/ # UDP / HTTP / WebSocket 客户端 +│ ├── utils/ +│ ├── main.cpp # 主程序入口(多线程集成) +│ ├── main_test.cpp # 本地硬件自检程序 +│ ├── Makefile # 交叉编译配置 +│ └── build_*.sh # 构建脚本(main/test/phaseX) +├── build_main.sh +├── logs.md # 编译时的日志(实时填写) +└── README.md # 本文档 +``` + +你可以直接把 Day1–Day7、任务清单与完成总结放到 `../docs/DevLogs/` 目录,并用当前 README 作为入口索引。 + +--- + +## 4. 功能模块概览 + +### 4.1 音频系统 + +**输入:板载模拟麦克风** + +- 通过 SoC 内部 **Audio Codec (audiocodec)** 采集 +- ALSA 设备:`hw:audiocodec` 或 `hw:0,0`(录音推荐 `plughw:0,0`) +- 运行时配置: + - `MIC Switch` 开启 + - `MIC Gain` 建议值 25(在音量与底噪之间平衡) + - `adc-vol` 与 `lineout-gain` 使用 DTS 默认值或适度调整 +- 采样参数: + - 16 kHz, S16_LE, Mono +- 典型链路: + - `setup_mic.sh` → `arecord` → `/tmp/test_mic.wav` → `aplay` / 上行网络 + +**输出:I2S + MAX98357A** + +- I2S0 接 MAX98357A,扬声器输出 +- Device Tree 为每个引脚创建独立 pinctrl 节点: + - `i2s0_bclk_pin`:PD12 + - `i2s0_lrck_pin`:PD13 + - `i2s0_dout0_pin`:PD15 +- I2S 平台设备 `&i2s0_plat` 绑定这些引脚,`status = "okay"` +- 通过 ALSA `aplay` / 自己的 `AudioPlayer` 类进行播放 + +### 4.2 IMU 传感器(ICM‑42688‑P) + +- 最终采用 **GPIO 模拟 SPI**: + - SCLK: PD3 + - MOSI: PD2 + - MISO: PD4 + - CS : PD5 +- SPI Mode0,软件 bit‑bang,速率约 500 kHz(可按需提升) +- 主要特性: + - WHO_AM_I = 0x47 识别验证 + - 加速度计:±16g,1 kHz ODR + - 陀螺仪:±2000 °/s,1 kHz ODR + - 温度通道:用于环境监控与漂移补偿 +- 静止状态验证: + - 合加速度 ≈ 9.8 m/s² + - 陀螺仪接近 0 °/s +- 上层封装: + - `ICM42688` 类提供采样与单位转换 + - 独立 `test_imu` 自检程序 + - 在主程序中通过 UDP 周期性上报 JSON/结构体数据 + +### 4.3 摄像头系统(GC2083 + MPP) + +- 使用 Allwinner Eyesee‑MPP 框架:SYS → VI → ISP → VENC +- 流水线: + - VI(接 MIPI 摄像头) + - ISP(自动曝光、白平衡、降噪) + - VENC(JPEG 编码) +- 关键配置: + - 分辨率:1280×720 @ 20fps(可调) + - JPEG 质量:80(在质量与码率之间折中) + - VI Buffer:5 帧 + - VBV Buffer:4 MB,避免 `VBV FULL` 错误 +- `Camera` 类职责: + - 完成 MPP 初始化 / 绑定 / 销毁 + - 按需抓拍单帧 JPEG(用于 WebSocket 发送或本地保存) + - 提供阻塞式 `capture_frame()` 接口与重试机制 +- 测试程序: + - `test_camera` 抓拍多张 JPEG 保存到 SD 卡 + - 实测成功率 100%,文件大小 20–80 KB 之间,画面曝光正常 + +### 4.4 网络通讯 + +**UDP** + +- 轻量 IMU 数据上报通道 +- 使用 POSIX socket,静态链接,无额外依赖 +- 典型用法: + - `UDPSender` 初始化目标 IP/Port + - 周期性发送 IMU/状态数据 + +**HTTP(libcurl 或轻量封装)** + +- 主要用途: + - 从服务器拉取 TTS 音频流(如 `stream.wav`) + - 拉取配置文件或诊断信息 +- 流式下载接口已预留,可边下边写入 `AudioPlayer` 播放 + +**WebSocket** + +- 早期方案:SDK 内置 `libuwsc`(后期为规避依赖,可用自实现轻量 WS 客户端) +- 主要用途: + - 上行:摄像头 JPEG 帧、音频 PCM 片段 + - 下行:控制指令 / 状态同步 +- 接口设计: + - `WSClient` 负责 TCP 连接、握手、帧收发、心跳与重连 + - 主线程中,每个子模块持有各自的 WSClient 实例或共享连接 + +--- + +## 5. 编译与构建流程 + +### 5.1 Tina SDK 环境准备(概要) + +1. 解压 SDK: + ```bash + mkdir -p ~/ProgramFiles/avaota_sdk + tar -xvf tina-v821-*.tar.xz -C ~/ProgramFiles/avaota_sdk + ``` +2. 初始化环境: + ```bash + cd ~/ProgramFiles/avaota_sdk/tina-v821-release + source build/envsetup.sh + lunch # 选择 avaota_f1 / v821 相关配置 + ``` +3. 全量编译: + ```bash + make -j8 + pack # 需要时打包固件 + ``` + +### 5.2 应用程序交叉编译 + +在 `src/` 目录中提供一个或多个构建脚本,例如: + +```bash +#!/bin/bash +set -e + +SDK_ROOT=~/ProgramFiles/AvaotaF1/avaota_sdk/tina-v821-release +# ⚠️ 使用 musl 工具链(与开发板兼容) +TOOLCHAIN=${SDK_ROOT}/prebuilt/rootfsbuilt/riscv/nds32le-linux-musl-v5d/bin + +export PATH=${TOOLCHAIN}:$PATH + +make clean +make all -j4 # 或按目标拆分:make main / make test_audio / make test_imu +``` + +Makefile 要点: + +- 使用 `riscv32-linux-musl-g++` 编译器(musl 工具链) +- 动态链接器:`/lib32/ld.so.1`(板端需创建符号链接:`ln -s /lib32/ilp32d/libc.so /lib32/ld.so.1`) +- 链接静态或最小依赖的动态库 +- 注意链接顺序:业务库 → MPP/ISP/cedarx → `-lpthread -lrt -lm -ldl -lstdc++` + +### 5.3 部署与运行 + +1. 将交叉编译好的可执行文件拷贝到 SD 卡: + ```bash + cp avaota_client /media/$USER/SDCARD/ + ``` +2. 板端挂载 SD 卡并复制到 `/tmp`: + ```bash + mount /dev/mmcblk0p1 /mnt/extsd + cp /mnt/extsd/avaota_client /tmp/ + chmod +x /tmp/avaota_client + ``` +3. 运行: + ```bash + /tmp/avaota_client + ``` + +> 推荐所有测试程序(`test_audio` / `test_imu` / `test_camera` / `avaota_test`)都统一走上述流程,避免执行权限与只读分区问题。 + +--- + +## 6. 主程序(集成)架构示意 + +主程序建议使用多线程模型,将各个模块解耦: + +```cpp +// 伪代码示例 +int main() { + init_logging(); + init_network_config(); // 服务器 IP / 端口 / 路径等 + init_signal_handler(); // Ctrl+C 安全退出 + + std::thread cam_thread(run_camera_loop); + std::thread mic_thread(run_audio_capture_loop); + std::thread spk_thread(run_audio_play_loop); + std::thread imu_thread(run_imu_udp_loop); + + // 可选:主线程处理下行指令 / 状态机 + run_main_control_loop(); + + // 等待退出 + cam_thread.join(); + mic_thread.join(); + spk_thread.join(); + imu_thread.join(); + return 0; +} +``` + +每个线程内部: + +- 初始化各自的硬件和网络客户端 +- 进入循环: + - 采集 → 编码(可选) → 通过 UDP/WS 发送 + - 或从 HTTP/WS 接收 → 解码(可选) → 播放/控制硬件 +- 捕获异常并尝试重连 / 恢复,必要时上报主线程 + +--- + +## 7. 日志与文档索引 + +可以在 README 中给出所有开发日志与计划文档的入口,方便回溯: + +- `../Docs/DevLogs/Day1.md`:SDK 编译与 32 位环境踩坑 +- `../Docs/DevLogs/Day2.md`:UDP 通信、网络库编译、libuwsc / libcurl 准备 +- `../Docs/DevLogs/Day3.md`:音频采集 & 播放模块(ALSA + I2S) +- `../Docs/DevLogs/Day4.md`:模拟麦克风配置 + IMU SPI 驱动与验证 +- `../Docs/DevLogs/Day5.md`:GC2083 摄像头 MPP 集成与 JPEG 捕获 +- `../Docs/DevLogs/Day6.md`:硬件全功能验证、本地测试程序、网络库诊断 +- `../Docs/DevLogs/Day7.md`:交叉编译 Makefile 收敛、工具链配置 +- `../Docs/DevLogs/Day8.md`:整体编译成功、Cedar 库链接完成 +- `../Docs/DevLogs/Day9.md`:⭐ **musl 工具链修复 + 板上测试通过** +- `../Docs/task_complete.md`:完整任务清单与进度条(97% 完成) +- `../Docs/implementation_plan_complete.md`:实现计划 & 各阶段目标拆解 + +--- + +## 8. 任务完成度与后续工作 + +### 8.1 当前完成度(参考任务清单与总结) + +- SDK/工具链/固件:✅ +- musl 工具链修复:✅ **(Day 9 关键突破)** +- 音频采集 & 播放:✅ +- IMU 采集:✅ **(板上测试通过)** +- 摄像头采集:✅ **(板上测试通过)** +- UDP / HTTP / WebSocket 基础:✅(库与客户端实现已完成) +- WiFi 网络配置:✅ **(192.168.110.132)** +- 板端硬件测试:✅ **(所有模块通过)** +- 网络服务器通信测试:⏳(服务器已部署,待测试) +- 性能评估与稳定性验证:⏳(待完成) + +整体项目 **97%** 完成,核心功能全部验证通过!🎉 + +### 8.2 建议的后续 TODO + +- 将服务器 IP / 端口、音频参数、帧率等抽象为配置文件(JSON / INI) +- 丰富错误日志并加上日志轮转 +- 对 WebSocket / HTTP 加入重连与指数退避策略 +- 若后续量产,考虑: + - 用硬件 SPI 替换 GPIO bit‑bang + - 对功耗与休眠策略进行优化 + - 引入简单看门狗机制,防止长期运行卡死 + +--- + +## 9. 如何使用本 README + +- **新成员上手**:从本 README 入手,结合 `../Docs/DevLogs/DayX.md` 逐步了解每个子系统的设计与坑点。 +- **以后复用到新项目**:可以直接复制「编译流程」「外设接线 + DTS 配置」「主程序多线程架构」这几部分,稍作修改即可移植到其他全志 / RISC‑V 设备。 +- **代码导航入口**:按模块查找 `src/audio`, `src/imu`, `src/camera`, `src/network` 目录,结合对应的 DayX 日志阅读。 + +祝使用愉快 🎉,也欢迎在后续开发阶段继续补充和更新本 README。 diff --git a/avaota_app_demo/MUSL_COMPILE.md b/avaota_app_demo/MUSL_COMPILE.md new file mode 100644 index 0000000..16d2412 --- /dev/null +++ b/avaota_app_demo/MUSL_COMPILE.md @@ -0,0 +1,375 @@ +# Musl 工具链编译说明 + +**更新时间**: 2025-12-04 +**问题**: 开发板使用 musl libc,但最初用 glibc 工具链编译导致无法运行 +**解决**: 切换到 musl 工具链重新编译 + +--- + +## 📋 问题诊断过程 + +### 在开发板上的错误 + +```bash +root@(none):/# ldd /tmp/avaota_client +/bin/sh: /tmp/avaota_client: not found + +root@(none):/# /lib/ld-musl-riscv32.so.1 /tmp/avaota_client +Error loading shared library ld-linux-riscv32-ilp32d.so.1: No such file or directory +Error relocating /tmp/avaota_client: __register_atfork: symbol not found +``` + +### 开发板环境确认 + +```bash +root@(none):/# /lib32/ilp32d/libc.so +musl libc (riscv32) +Version 1.2.4 +Dynamic Program Loader +``` + +**结论**: 开发板运行 **musl libc 1.2.4**,但程序用 **glibc** 编译,导致: +1. 动态链接器路径不匹配(`ld-linux-riscv32-ilp32d.so.1` vs `ld-musl-riscv32.so.1`) +2. glibc 特有符号 `__register_atfork` 在 musl 中不存在 + +--- + +## ✅ 解决方案 + +### 已修改的文件 + +修改了 `src/Makefile`,添加 musl 工具链支持: + +```makefile +# 切换工具链:设置 USE_MUSL=1 使用 musl 工具链(推荐) +USE_MUSL := 1 + +ifeq ($(USE_MUSL),1) + # musl 工具链(与开发板兼容) + TOOLCHAIN_DIR := $(SDK_ROOT)/out/toolchain/nds32le-linux-musl-v5d/bin + CROSS_COMPILE := riscv32-linux-musl- + $(info [INFO] Using musl toolchain for board compatibility) +else + # glibc 工具链(仅用于对比测试,开发板不支持) + TOOLCHAIN_DIR := $(SDK_ROOT)/out/toolchain/nds32le-linux-glibc-v5d/bin + CROSS_COMPILE := riscv32-unknown-linux- + $(warning [WARNING] Using glibc toolchain - will NOT run on board!) +endif +``` + +--- + +## 🚀 编译步骤(在 Ubuntu 服务器上) + +### 前提条件 + +确保 musl 工具链存在: + +```bash +cd ~/ProgramFiles/AvaotaF1/avaota_sdk/tina-v821-release + +# 检查 musl 工具链 +ls -la out/toolchain/nds32le-linux-musl-v5d/bin/ + +# 应该看到类似这些文件: +# riscv32-linux-musl-gcc +# riscv32-linux-musl-g++ +# riscv32-linux-musl-ar +# ... +``` + +**如果不存在**,可能需要: +1. 解压工具链压缩包(如果在 `out/toolchain/` 下有 `.tar.xz` 或 `.tar.gz` 文件) +2. 或在 `prebuilt/rootfsbuilt/riscv/` 下查找 +3. 或重新编译 SDK(会自动生成) + +--- + +### 步骤 1: 上传修改后的代码 + +将修改后的 `avaota_app_demo` 文件夹上传到 Ubuntu 服务器: + +```bash +# 在 Windows 上(使用 SCP 或 WinSCP) +# 目标路径:/home/rongye/ProgramFiles/AvaotaF1/avaota_app_demo +``` + +--- + +### 步骤 2: SSH 连接到服务器 + +```bash +ssh rongye@<服务器IP> +``` + +--- + +### 步骤 3: 验证工具链路径 + +```bash +cd ~/ProgramFiles/AvaotaF1/avaota_app_demo/src + +# 检查 Makefile 变量 +grep "TOOLCHAIN_DIR" Makefile +grep "CROSS_COMPILE" Makefile +grep "USE_MUSL" Makefile + +# 测试编译器 +SDK_ROOT=~/ProgramFiles/AvaotaF1/avaota_sdk/tina-v821-release +$SDK_ROOT/out/toolchain/nds32le-linux-musl-v5d/bin/riscv32-linux-musl-gcc --version +``` + +**预期输出**: +``` +riscv32-linux-musl-gcc (GCC) 10.x.x +``` + +--- + +### 步骤 4: 清理旧编译文件 + +```bash +cd ~/ProgramFiles/AvaotaF1/avaota_app_demo/src +make clean +``` + +--- + +### 步骤 5: 重新编译 + +```bash +cd ~/ProgramFiles/AvaotaF1/avaota_app_demo + +# 方法 1: 使用构建脚本 +./build_main.sh + +# 方法 2: 直接 make +cd src +make all -j4 +``` + +编译时应该看到: +``` +[INFO] Using musl toolchain for board compatibility +``` + +--- + +### 步骤 6: 验证编译结果 + +```bash +cd ~/ProgramFiles/AvaotaF1/avaota_app_demo + +# 查看文件信息 +ls -lh build/bin/avaota_client +file build/bin/avaota_client + +# 【关键】检查动态链接器 +strings build/bin/avaota_client | grep "/lib/ld-" +``` + +**正确结果应该是**: +``` +/lib/ld-musl-riscv32.so.1 +``` + +**如果看到这个就是错的**(说明还在用 glibc): +``` +/lib/ld-linux-riscv32-ilp32d.so.1 +``` + +--- + +### 步骤 7: 上传到开发板 + +```bash +# 从服务器上传到开发板 +cd ~/ProgramFiles/AvaotaF1/avaota_app_demo +scp build/bin/avaota_client root@<开发板IP>:/tmp/avaota_client_musl +``` + +--- + +### 步骤 8: 在开发板上测试 + +SSH 到开发板: + +```bash +ssh root@<开发板IP> + +# 添加执行权限 +chmod +x /tmp/avaota_client_musl + +# 验证依赖(现在应该正常显示) +ldd /tmp/avaota_client_musl + +# 运行程序 +/tmp/avaota_client_musl +``` + +**成功标志**: +- ✅ `ldd` 不再报 "not found" 错误 +- ✅ 能看到需要的动态库列表 +- ✅ 程序启动,打印初始化日志 +- ✅ 各模块开始工作 + +--- + +## 🔧 故障排查 + +### 问题 1: 找不到 musl 工具链 + +**错误**: +```bash +make: /home/rongye/.../nds32le-linux-musl-v5d/bin/riscv32-linux-musl-gcc: No such file or directory +``` + +**解决方案 A**: 查找并解压 + +```bash +cd ~/ProgramFiles/AvaotaF1/avaota_sdk/tina-v821-release + +# 查找压缩包 +find . -name "*musl*.tar*" 2>/dev/null + +# 如果找到,解压到 out/toolchain/ +cd out/tool chain +tar -xJf nds32le-linux-musl-v5d.tar.xz # 或 .tar.gz +``` + +**解决方案 B**: 使用其他位置的工具链 + +如果工具链在 `prebuilt/` 目录,修改 Makefile: + +```makefile +TOOLCHAIN_DIR := $(SDK_ROOT)/prebuilt/rootfsbuilt/riscv/nds32le-linux-musl-v5d/bin +``` + +**解决方案 C**: 临时切换回 glibc + +如果实在找不到 musl 工具链,可以暂时用 glibc 重新编译(虽然不推荐): + +```makefile +USE_MUSL := 0 +``` + +但这样编译的程序**无法在开发板上运行**。 + +--- + +### 问题 2: 编译器前缀不对 + +**错误**: +``` +make: riscv32-linux-musl-gcc: command not found +``` + +**解决方案**: + +检查实际的编译器名称: + +```bash +ls ~/ProgramFiles/AvaotaF1/avaota_sdk/tina-v821-release/out/toolchain/nds32le-linux-musl-v5d/bin/riscv32-*gcc +``` + +可能的前缀: +- `riscv32-linux-musl-` +- `riscv32-unknown-linux-musl-` + +修改 Makefile 中的 `CROSS_COMPILE` 变量。 + +--- + +### 问题 3: 编译时缺少头文件 + +**错误**: +``` +fatal error: xxx.h: No such file or directory +``` + +**原因**: musl 的系统头文件路径可能与 glibc 不同 + +**解决方案**: + +在 Makefile 中添加 musl 头文件路径: + +```makefile +ifeq ($(USE_MUSL),1) + CXXFLAGS += -I$(TOOLCHAIN_DIR)/../include + CXXFLAGS += -I$(TOOLCHAIN_DIR)/../riscv32-linux-musl/include +endif +``` + +--- + +### 问题 4: 链接时找不到库 + +**错误**: +``` +cannot find -lxxx +``` + +**解决方案**: + +检查库是否存在于 musl 环境: + +```bash +find ~/ProgramFiles/AvaotaF1/avaota_sdk/tina-v821-release/out/v821/avaota_f1/openwrt/staging_dir/target/usr/lib -name "libxxx.a" +``` + +如果不存在,可能需要: +1. 重新编译 SDK 以包含 musl 版本的库 +2. 或移除对该库的依赖 + +--- + +## 📊 工具链对比 + +| 项目 | glibc 工具链 | musl 工具链 | +|------|-------------|-------------| +| 路径 | `nds32le-linux-glibc-v5d` | `nds32le-linux-musl-v5d` | +| 编译器前缀 | `riscv32-unknown-linux-` | `riscv32-linux-musl-` | +| C 库 | glibc (GNU C Library) | musl libc 1.2.4 | +| 动态链接器 | `/lib/ld-linux-riscv32-ilp32d.so.1` | `/lib/ld-musl-riscv32.so.1` | +| 二进制大小 | 较大 | 较小 | +| 兼容性 | ❌ 不兼容 Avaota F1 | ✅ 完美兼容 | +| 用途 | 仅用于实验 | **生产环境必须使用** | + +--- + +## ✅ 编译验证清单 + +重新编译完成后,验证以下内容: + +- [ ] musl 工具链路径存在 +- [ ] Makefile 中 `USE_MUSL := 1` +- [ ] `make clean` 清理旧文件 +- [ ] 编译时看到 "Using musl toolchain" 提示 +- [ ] 编译成功,生成 `build/bin/avaota_client` +- [ ] `strings` 检查链接器为 `ld-musl-riscv32.so.1` +- [ ] 上传到开发板 +- [ ] `ldd` 正常显示依赖 +- [ ] 程序成功运行 + +--- + +## 📝 后续优化 + +如果后续需要调整(比如完全静态链接),可以修改: + +```makefile +# 完全静态链接(不依赖任何动态库) +LDFLAGS := -static -static-libgcc -static-libstdc++ + +# 移除 -Wl,-Bdynamic 部分 +# LDFLAGS += -Wl,-Bdynamic -lasound -lglog ... + +# 全部静态链接 +LDFLAGS += -lasound -lglog -llog -lpthread -lm -lstdc++ -lrt -ldl -lz +``` + +这样可以避免任何运行时库依赖问题,但会显著增加程序大小(可能从 3.9MB 增加到 6-8MB)。 + +--- + +**下一步**: 按照上述步骤在服务器上重新编译,然后在开发板上测试!🚀 diff --git a/avaota_app_demo/README.md b/avaota_app_demo/README.md new file mode 100644 index 0000000..0ef11f5 --- /dev/null +++ b/avaota_app_demo/README.md @@ -0,0 +1,168 @@ +# Avaota F1 应用程序编译 + +**更新时间**: 2025-12-04 +**重要**: 必须使用 **musl 工具链**编译,开发板使用 musl libc 1.2.4 + +--- + +## 🚨 重要提示 + +开发板运行的是 **musl libc 1.2.4**,不是 glibc! + +- ✅ **正确**: 使用 `nds32le-linux-musl-v5d` 工具链 +- ❌ **错误**: 使用 `nds32le-linux-glibc-v5d` 工具链(编译的程序无法运行) + +--- + +## 📋 快速编译步骤 + +### 1. 准备 Tina SDK + +将 Tina SDK 放置到以下路径: +``` +/home/rongye/ProgramFiles/AvaotaF1/avaota_sdk/tina-v821-release +``` + +> 如需修改路径,请同时更新 `src/Makefile` 和 `build_main.sh` 中的 `SDK_ROOT` 变量 + +### 2. 上传代码到服务器 + +将 `avaota_app_demo` 文件夹上传到: +``` +/home/rongye/ProgramFiles/AvaotaF1/avaota_app_demo +``` + +### 3. SSH 连接到服务器 + +```bash +ssh rongye@<服务器IP> +``` + +### 4. 验证 Makefile 配置 + +```bash +cd ~/ProgramFiles/AvaotaF1/avaota_app_demo/src +grep "USE_MUSL" Makefile +``` + +应该看到: +```makefile +USE_MUSL := 1 +``` + +### 5. 清理并编译 + +```bash +cd ~/ProgramFiles/AvaotaF1/avaota_app_demo + +# 清理 +cd src +make clean + +# 编译 +cd .. +./build_main.sh +``` + +### 5. 验证编译结果 + +```bash +# 检查动态链接器(关键!) +strings build/bin/avaota_client | grep "/lib/ld-" +``` + +**正确结果**: +``` +/lib/ld-musl-riscv32.so.1 +``` + +**错误结果**(如果看到这个说明还在用 glibc): +``` +/lib/ld-linux-riscv32-ilp32d.so.1 +``` + +### 6. 上传到开发板 + +```bash +scp build/bin/avaota_client root@<开发板IP>:/tmp/avaota_client_musl +``` + +### 7. 在开发板上运行 + +```bash +ssh root@<开发板IP> + +chmod +x /tmp/avaota_client_musl +ldd /tmp/avaota_client_musl # 应该正常显示依赖 +/tmp/avaota_client_musl # 运行程序 +``` + +--- + +## 📁 文件说明 + +``` +avaota_app_demo/ +├── src/ # 源代码目录 +│ ├── main.cpp # 主程序 +│ ├── audio/ # 音频模块 +│ ├── camera/ # 摄像头模块 +│ ├── imu/ # IMU 传感器 +│ ├── network/ # 网络通信 +│ ├── utils/ # 工具函数 +│ └── Makefile # 编译配置(已设置 USE_MUSL=1) +├── build_main.sh # 构建脚本 +├── MUSL_COMPILE.md # 详细编译指南 +└── README.md # 本文件 +``` + +--- + +## 🔧 如果遇到问题 + +### 问题 1: 找不到 musl 工具链 + +**错误**: +``` +make: /home/rongye/.../nds32le-linux-musl-v5d/bin/riscv32-linux-musl-gcc: No such file or directory +``` + +**解决**: +```bash +# 查找工具链 +cd ~/ProgramFiles/AvaotaF1/avaota_sdk/tina-v821-release +find . -name "*musl*.tar*" 2>/dev/null + +# 如果找到压缩包,解压 +cd out/toolchain +tar -xJf nds32le-linux-musl-v5d.tar.xz +``` + +详细故障排查请参考 [MUSL_COMPILE.md](MUSL_COMPILE.md) + +--- + +## 📚 相关文档 + +- **[MUSL_COMPILE.md](MUSL_COMPILE.md)** - 完整的 musl 工具链编译指南 +- **[../../docs/Day9.md](../../docs/Day9.md)** - Day 9 开发日志(问题发现过程) +- **[../../docs/board_test_checklist.md](../../docs/board_test_checklist.md)** - 板上测试清单 +- **[../../docs/musl_toolchain_fix.md](../../docs/musl_toolchain_fix.md)** - 工具链问题修复指南 + +--- + +## ✅ 编译验证清单 + +- [ ] 修改后的代码已上传到服务器 +- [ ] Makefile 中 `USE_MUSL := 1` +- [ ] musl 工具链路径存在 +- [ ] `make clean` 清理完成 +- [ ] 编译成功,生成 `build/bin/avaota_client` +- [ ] `strings` 检查链接器为 `ld-musl-riscv32.so.1` +- [ ] 程序已上传到开发板 +- [ ] `ldd` 正常显示依赖 +- [ ] 程序成功运行 + +--- + +**祝编译顺利!** 🚀 diff --git a/avaota_app_demo/build_main.sh b/avaota_app_demo/build_main.sh new file mode 100644 index 0000000..fe90c68 --- /dev/null +++ b/avaota_app_demo/build_main.sh @@ -0,0 +1,113 @@ +#!/bin/bash +# 编译 AvaotaF1 客户端主程序 +# 【开发者注意】请将 Tina SDK 放置到 SDK_ROOT 指定的路径 + +set -e # 错误时退出 + +# SDK 路径配置 +# 【开发者注意】请确保 SDK 位于此路径,或修改此变量 +SDK_ROOT="/home/rongye/ProgramFiles/TinaSDK/tina-v821-release" + +echo "=========================================" +echo "AvaotaF1 Client Build Script" +echo "=========================================" +echo "" + +# 检查 SDK 路径 +if [ ! -d "$SDK_ROOT" ]; then + echo "错误:SDK 路径不存在: $SDK_ROOT" + echo "请将 Tina SDK 放置到上述路径,或修改脚本中的 SDK_ROOT 变量" + exit 1 +fi + +# 保存项目目录(在切换到SDK前) +PROJECT_DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" && pwd)" + +# 1. 进入 SDK 目录并设置环境 +echo "1. 设置编译环境..." +cd "$SDK_ROOT" +source build/envsetup.sh 2>&1 || true # 忽略 envsetup.sh 的无害警告 + +# 2. 检查必需的库 +echo "" +echo "2. 检查依赖库..." + +STAGING_DIR="$SDK_ROOT/out/v821/avaota_f1/openwrt/staging_dir/target/usr/lib" + +check_lib() { + local lib_name=$1 + if [ -f "$STAGING_DIR/$lib_name" ]; then + echo " ✓ $lib_name 存在" + return 0 + else + echo " ✗ $lib_name 缺失" + return 1 + fi +} + +all_libs_ok=true +check_lib "libssl.so" || all_libs_ok=false +check_lib "libcrypto.so" || all_libs_ok=false +check_lib "libcurl.so" || all_libs_ok=false +check_lib "libasound.so" || all_libs_ok=false + +if [ "$all_libs_ok" = false ]; then + echo "" + echo "警告:部分库缺失,可能导致链接失败" + echo "建议在 SDK 中运行 'make menuconfig' 启用相应的库" + echo "" +fi + +# 3. 清理并编译 +echo "" +echo "3. 开始编译..." +echo "" + +echo "项目目录: $PROJECT_DIR" + +# 检查 src 目录是否存在 +if [ ! -d "$PROJECT_DIR/src" ]; then + echo "错误:找不到 src 目录" + echo "当前路径:$PROJECT_DIR" + echo "请确认脚本在项目根目录执行" + exit 1 +fi + +# 切换到项目src目录 +cd "$PROJECT_DIR/src" + +# 清理旧文件 +echo "清理旧的编译文件..." +make clean + +# 编译主程序 +echo "" +echo "编译 avaota_client..." +make all -j$(nproc) + +# 4. 检查编译结果 +echo "" +echo "=========================================" +if [ -f "../build/bin/avaota_client" ]; then + echo "✅ 编译成功!" + echo "=========================================" + echo "" + echo "输出文件:" + echo " ../build/bin/avaota_client" + echo "" + + # 文件信息 + file ../build/bin/avaota_client + ls -lh ../build/bin/avaota_client + + echo "" + echo "下一步:" + echo " 1. 将程序上传到板子:" + echo " scp ../build/bin/avaota_client root@<板子IP>:/usr/bin/" + echo " 2. 在板子上运行:" + echo " avaota_client" +else + echo "❌ 编译失败" + echo "=========================================" + exit 1 +fi diff --git a/avaota_app_demo/src/Makefile b/avaota_app_demo/src/Makefile new file mode 100644 index 0000000..fcaee5c --- /dev/null +++ b/avaota_app_demo/src/Makefile @@ -0,0 +1,267 @@ +# AvaotaF1 客户端 Makefile +# 交叉编译配置 - 32位 RISC-V + +# ===== 工具链配置 ===== +# 开发板使用 musl libc 1.2.4,必须用 musl 工具链编译 +# 【开发者注意】请将 Tina SDK 放置到以下路径,或修改此变量 +SDK_ROOT := /home/rongye/ProgramFiles/TinaSDK/tina-v821-release + +# 切换工具链:设置 USE_MUSL=1 使用 musl 工具链(推荐) +USE_MUSL := 1 + +ifeq ($(USE_MUSL),1) + # musl 工具链(与开发板兼容) + # 注意:musl 工具链在 prebuilt 目录,不是 out/toolchain + TOOLCHAIN_DIR := $(SDK_ROOT)/prebuilt/rootfsbuilt/riscv/nds32le-linux-musl-v5d/bin + CROSS_COMPILE := riscv32-linux-musl- + $(info [INFO] Using musl toolchain for board compatibility) +else + # glibc 工具链(仅用于对比测试,开发板不支持) + TOOLCHAIN_DIR := $(SDK_ROOT)/out/toolchain/nds32le-linux-glibc-v5d/bin + CROSS_COMPILE := riscv32-unknown-linux- + $(warning [WARNING] Using glibc toolchain - will NOT run on board!) +endif + +CC := $(TOOLCHAIN_DIR)/$(CROSS_COMPILE)gcc +CXX := $(TOOLCHAIN_DIR)/$(CROSS_COMPILE)g++ +AR := $(TOOLCHAIN_DIR)/$(CROSS_COMPILE)ar +STRIP := $(TOOLCHAIN_DIR)/$(CROSS_COMPILE)strip + +# ===== 目标配置 ===== +TARGET := avaota_client +SRC_DIR := . +BUILD_DIR := ../build +OBJ_DIR := $(BUILD_DIR)/obj +BIN_DIR := $(BUILD_DIR)/bin + +# ===== 源文件 ===== +SRCS := $(SRC_DIR)/main.cpp \ + $(SRC_DIR)/camera/camera.cpp \ + $(SRC_DIR)/audio/audio_capture.cpp \ + $(SRC_DIR)/audio/audio_player.cpp \ + $(SRC_DIR)/imu/icm42688.cpp \ + $(SRC_DIR)/network/ws_client.cpp \ + $(SRC_DIR)/network/udp_sender.cpp \ + $(SRC_DIR)/utils/logger.cpp +# Day 14: 移除 HTTP TTS 相关文件,改用 WebSocket TTS + +OBJS := $(patsubst $(SRC_DIR)/%.cpp, $(OBJ_DIR)/%.o, $(SRCS)) + +# ===== 编译选项 ===== +CXXFLAGS := -std=c++14 -O2 -Wall -Wextra +CXXFLAGS += -I$(SRC_DIR) + +# 系统头文件 +CXXFLAGS += -I$(SDK_ROOT)/out/v821/avaota_f1/openwrt/staging_dir/target/usr/include + +# eyesee-mpp 头文件 +CXXFLAGS += -I$(SDK_ROOT)/out/v821/avaota_f1/openwrt/staging_dir/target/usr/include/eyesee-mpp/middleware/include +CXXFLAGS += -I$(SDK_ROOT)/out/v821/avaota_f1/openwrt/staging_dir/target/usr/include/eyesee-mpp/middleware/include/media +CXXFLAGS += -I$(SDK_ROOT)/out/v821/avaota_f1/openwrt/staging_dir/target/usr/include/eyesee-mpp/middleware/include/utils +CXXFLAGS += -I$(SDK_ROOT)/out/v821/avaota_f1/openwrt/staging_dir/target/usr/include/eyesee-mpp/middleware/media/include/component +CXXFLAGS += -I$(SDK_ROOT)/out/v821/avaota_f1/openwrt/staging_dir/target/usr/include/eyesee-mpp/system/public/include + +# libisp 头文件 +CXXFLAGS += -I$(SDK_ROOT)/out/v821/avaota_f1/openwrt/staging_dir/target/usr/include/libisp +CXXFLAGS += -I$(SDK_ROOT)/out/v821/avaota_f1/openwrt/staging_dir/target/usr/include/libisp/include +CXXFLAGS += -I$(SDK_ROOT)/out/v821/avaota_f1/openwrt/staging_dir/target/usr/include/libisp/include/device +CXXFLAGS += -I$(SDK_ROOT)/out/v821/avaota_f1/openwrt/staging_dir/target/usr/include/libisp/include/V4l2Camera +CXXFLAGS += -I$(SDK_ROOT)/out/v821/avaota_f1/openwrt/staging_dir/target/usr/include/libisp/isp_dev +CXXFLAGS += -I$(SDK_ROOT)/out/v821/avaota_f1/openwrt/staging_dir/target/usr/include/libisp/isp_tuning +CXXFLAGS += -I$(SDK_ROOT)/out/v821/avaota_f1/openwrt/staging_dir/target/usr/include/libisp/isp_manage + +# libcedarc 头文件 (视频编解码器 - 添加所有子目录) +CXXFLAGS += -I$(SDK_ROOT)/out/v821/avaota_f1/openwrt/staging_dir/target/usr/include/libcedarc +CXXFLAGS += -I$(SDK_ROOT)/out/v821/avaota_f1/openwrt/staging_dir/target/usr/include/libcedarc/include +CXXFLAGS += -I$(SDK_ROOT)/out/v821/avaota_f1/openwrt/staging_dir/target/usr/include/libcedarc/base +CXXFLAGS += -I$(SDK_ROOT)/out/v821/avaota_f1/openwrt/staging_dir/target/usr/include/libcedarc/base/include + +# 定义芯片类型 +CXXFLAGS += -DAWCHIP=AW_V821 + +# ===== 库路径与链接 ===== +# 使用静态链接(与 test_camera 相同的配置) +LDFLAGS := -static +LDFLAGS += -L$(SDK_ROOT)/out/v821/avaota_f1/openwrt/staging_dir/target/usr/lib +LDFLAGS += -L$(SDK_ROOT)/out/v821/avaota_f1/openwrt/staging_dir/target/usr/lib/eyesee-mpp + +# 开始静态库组 - 顺序很重要! +LDFLAGS += -Wl,--start-group + +# 核心 MPP 库 +LDFLAGS += -law_mpp -lmedia_utils -lawion -lexpat + +# ISP 库 (摄像头图像处理) +LDFLAGS += -lISP -lisp_dev -lisp_ini -liniparser +LDFLAGS += -lisp_ae -lisp_af -lisp_afs -lisp_awb -lisp_base +LDFLAGS += -lisp_gtm -lisp_iso -lisp_math -lisp_md -lisp_pltm -lisp_rolloff + +# 视频编码器 +LDFLAGS += -lvencoder -lvenc_base -lvenc_common -lvenc_jpeg -lvenc_h264 +LDFLAGS += -lMemAdapter -lVE + +# 音频处理库 +LDFLAGS += -ladecoder -lResample -lAudioVps +LDFLAGS += -lwav -laac +LDFLAGS += -lcedarx_aencoder -laacenc +LDFLAGS += -lAgc -lAec -lAns + +# Muxer (文件封装) +LDFLAGS += -lmuxers -lmp4_muxer -lraw_muxer +LDFLAGS += -lmpeg2ts_muxer -laac_muxer -lmp3_muxer -lwav_muxer +LDFLAGS += -lffavutil -lFsWriter -lcedarxstream + +# Demuxer (文件解析) +LDFLAGS += -lcedarxdemuxer -lcdx_parser -lcdx_stream -lcdx_file_stream +LDFLAGS += -lcdx_aac_parser -lcdx_id3v2_parser -lcdx_mov_parser +LDFLAGS += -lcdx_mp3_parser -lcdx_ts_parser -lcdx_wav_parser + +# 视频解码器 (MJPEG) +LDFLAGS += -lvdecoder -lvideoengine -lawmjpegplus +LDFLAGS += -lcedarx_tencoder + +# 配置文件解析 +LDFLAGS += -lPluginMpp -lIniParserMpp -lsample_confparser + +# Cedar 核心库(包含CDC_LOG_LEVEL_NAME等符号) +LDFLAGS += -lcdc_base -lcdx_base + +# 显示库 +LDFLAGS += -lcedarxrender -lhwdisplay + +# ALSA 音频库(静态库不存在,且音频播放已禁用) +# LDFLAGS += -lasound + +# OpenSSL (用于 WebSocket 握手) +LDFLAGS += -lssl -lcrypto + +# 结束静态库组 +LDFLAGS += -Wl,--end-group + +# 系统动态库 +# 指定正确的动态链接器路径,避免开发板上需要手动创建 /lib32/ld.so.1 符号链接 +LDFLAGS += -Wl,--dynamic-linker=/lib/ld-musl-riscv32.so.1 +LDFLAGS += -Wl,-Bdynamic -lasound -lpthread -lm -lrt -ldl -lz -static-libstdc++ + +# ===== 目标规则 ===== +.PHONY: all clean install test_imu test_gpio test_camera + +all: $(BIN_DIR)/$(TARGET) + +$(BIN_DIR)/$(TARGET): $(OBJS) + @mkdir -p $(BIN_DIR) + $(CXX) $(OBJS) $(LDFLAGS) -o $@ + @echo "Build complete: $@" + @echo "Strip binary..." + $(STRIP) $@ + +$(OBJ_DIR)/%.o: $(SRC_DIR)/%.cpp + @mkdir -p $(dir $@) + $(CXX) $(CXXFLAGS) -c $< -o $@ + +clean: + rm -rf $(BUILD_DIR) + @echo "Clean complete" + +install: + @echo "Installing to target device..." + scp $(BIN_DIR)/$(TARGET) root@192.168.1.100:/usr/bin/ + @echo "Install complete" + +# ===== 测试程序 ===== + +# test_imu 只需要基本库 +TEST_IMU_LDFLAGS := -static -lpthread -lm -lstdc++ + +test_imu: $(OBJ_DIR)/test_imu.o $(OBJ_DIR)/imu/icm42688.o $(OBJ_DIR)/utils/logger.o + @mkdir -p $(BIN_DIR) + $(CXX) $^ $(TEST_IMU_LDFLAGS) -o $(BIN_DIR)/$@ + @echo "Build complete: $(BIN_DIR)/$@" + @echo "Strip binary..." + $(STRIP) $(BIN_DIR)/$@ + +# test_gpio 测试 GPIO 输出 +test_gpio: $(OBJ_DIR)/test_gpio.o + @mkdir -p $(BIN_DIR) + $(CXX) $^ $(TEST_IMU_LDFLAGS) -o $(BIN_DIR)/$@ + @echo "Build complete: $(BIN_DIR)/$@" + @echo "Strip binary..." + $(STRIP) $(BIN_DIR)/$@ + +# test_camera 测试摄像头 (需要 MPP 库) +TEST_CAMERA_LDFLAGS := -static +TEST_CAMERA_LDFLAGS += -L$(SDK_ROOT)/out/v821/avaota_f1/openwrt/staging_dir/target/usr/lib +TEST_CAMERA_LDFLAGS += -L$(SDK_ROOT)/out/v821/avaota_f1/openwrt/staging_dir/target/usr/lib/eyesee-mpp + +# 静态库组 - 顺序很重要! +TEST_CAMERA_LDFLAGS += -Wl,--start-group + +# 核心 MPP 库 +TEST_CAMERA_LDFLAGS += -law_mpp -lmedia_utils -lawion -lexpat + +# ISP 库 (摄像头图像处理) +TEST_CAMERA_LDFLAGS += -lISP -lisp_dev -lisp_ini -liniparser +TEST_CAMERA_LDFLAGS += -lisp_ae -lisp_af -lisp_afs -lisp_awb -lisp_base +TEST_CAMERA_LDFLAGS += -lisp_gtm -lisp_iso -lisp_math -lisp_md -lisp_pltm -lisp_rolloff + +# 视频编码器 +TEST_CAMERA_LDFLAGS += -lvencoder -lvenc_base -lvenc_common -lvenc_jpeg -lvenc_h264 +TEST_CAMERA_LDFLAGS += -lMemAdapter -lVE + +# 音频处理库 +TEST_CAMERA_LDFLAGS += -ladecoder -lResample -lAudioVps +TEST_CAMERA_LDFLAGS += -lwav -laac +TEST_CAMERA_LDFLAGS += -lcedarx_aencoder -laacenc +TEST_CAMERA_LDFLAGS += -lAgc -lAec -lAns + +# Muxer (文件封装) +TEST_CAMERA_LDFLAGS += -lmuxers -lmp4_muxer -lraw_muxer +TEST_CAMERA_LDFLAGS += -lmpeg2ts_muxer -laac_muxer -lmp3_muxer -lwav_muxer +TEST_CAMERA_LDFLAGS += -lffavutil -lFsWriter -lcedarxstream + +# Demuxer (文件解析) +TEST_CAMERA_LDFLAGS += -lcedarxdemuxer -lcdx_parser -lcdx_stream -lcdx_file_stream +TEST_CAMERA_LDFLAGS += -lcdx_aac_parser -lcdx_id3v2_parser -lcdx_mov_parser +TEST_CAMERA_LDFLAGS += -lcdx_mp3_parser -lcdx_ts_parser -lcdx_wav_parser + +# 视频解码器 (MJPEG) +TEST_CAMERA_LDFLAGS += -lvdecoder -lvideoengine -lawmjpegplus +TEST_CAMERA_LDFLAGS += -lcedarx_tencoder + +# 配置文件解析 +TEST_CAMERA_LDFLAGS += -lPluginMpp -lIniParserMpp -lsample_confparser + +# Cedar 核心库 +TEST_CAMERA_LDFLAGS += -lcdc_base -lcdx_base + +# 显示库 +TEST_CAMERA_LDFLAGS += -lcedarxrender -lhwdisplay + +TEST_CAMERA_LDFLAGS += -Wl,--end-group + +# 系统动态库 +TEST_CAMERA_LDFLAGS += -Wl,-Bdynamic -lasound -lglog -llog -lpthread -lm -lstdc++ -lrt -ldl -lz + +test_camera: $(OBJ_DIR)/test_camera.o $(OBJ_DIR)/camera/camera.o + @mkdir -p $(BIN_DIR) + $(CXX) $^ $(TEST_CAMERA_LDFLAGS) -o $(BIN_DIR)/$@ + @echo "Build complete: $(BIN_DIR)/$@" + @echo "Strip binary..." + $(STRIP) $(BIN_DIR)/$@ + +# ===== 帮助 ===== +help: + @echo "AvaotaF1 Client Makefile" + @echo "------------------------" + @echo "Targets:" + @echo " all - Build the application (default)" + @echo " clean - Remove build artifacts" + @echo " install - Deploy to device via SCP" + @echo " test_imu - Build IMU test program" + @echo " test_gpio - Build GPIO test program" + @echo " test_camera - Build camera test program" + @echo "" + @echo "Before build, ensure:" + @echo " 1. SDK_ROOT points to Tina SDK" + @echo " 2. Toolchain is available" + @echo " 3. SDK has been compiled" diff --git a/avaota_app_demo/src/audio/audio_capture.cpp b/avaota_app_demo/src/audio/audio_capture.cpp new file mode 100644 index 0000000..18b4d36 --- /dev/null +++ b/avaota_app_demo/src/audio/audio_capture.cpp @@ -0,0 +1,357 @@ +/** + * @file audio_capture.cpp + * @brief 音频采集实现 - 基于 ALSA + * @date 2024-11-24 + * @platform Avaota F1 (V821 / RISC-V) + */ + +#include "audio_capture.h" +#include "../utils/logger.h" +#include +#include + +/** + * @brief 构造函数 + */ +AudioCapture::AudioCapture(const std::string& device, int sample_rate, int channels) + : m_device(device) + , m_sample_rate(sample_rate) + , m_channels(channels) + , m_pcm_handle(nullptr) +{ +} + +/** + * @brief 析构函数 + */ +AudioCapture::~AudioCapture() { + if (m_pcm_handle) { + snd_pcm_drain(m_pcm_handle); + snd_pcm_close(m_pcm_handle); + m_pcm_handle = nullptr; + LOG_INFO("[AudioCapture] Device closed"); + } +} + +/** + * @brief 配置混音器以启用麦克风输入 + * @param card_name 声卡名称,如 "hw:0" + * @return true 如果成功 + */ +bool AudioCapture::setup_mixer(const char* card_name) { + snd_mixer_t *mixer = nullptr; + snd_mixer_selem_id_t *sid = nullptr; + int err; + + // 打开混音器 + err = snd_mixer_open(&mixer, 0); + if (err < 0) { + LOG_WARN("[AudioCapture] Cannot open mixer: %s", snd_strerror(err)); + return false; + } + + // 附加到声卡 + err = snd_mixer_attach(mixer, card_name); + if (err < 0) { + LOG_WARN("[AudioCapture] Cannot attach mixer to %s: %s", card_name, snd_strerror(err)); + snd_mixer_close(mixer); + return false; + } + + // 注册混音器 + err = snd_mixer_selem_register(mixer, NULL, NULL); + if (err < 0) { + LOG_WARN("[AudioCapture] Cannot register mixer: %s", snd_strerror(err)); + snd_mixer_close(mixer); + return false; + } + + // 加载混音器元素 + err = snd_mixer_load(mixer); + if (err < 0) { + LOG_WARN("[AudioCapture] Cannot load mixer: %s", snd_strerror(err)); + snd_mixer_close(mixer); + return false; + } + + LOG_INFO("[AudioCapture] Mixer opened successfully, scanning controls..."); + + // 遍历所有混音器元素并打印信息 + snd_mixer_selem_id_alloca(&sid); + snd_mixer_elem_t *elem; + int control_count = 0; + + for (elem = snd_mixer_first_elem(mixer); elem; elem = snd_mixer_elem_next(elem)) { + if (!snd_mixer_selem_is_active(elem)) continue; + + snd_mixer_selem_get_id(elem, sid); + const char *name = snd_mixer_selem_id_get_name(sid); + control_count++; + + // 检查是否有捕获能力 + bool has_capture = snd_mixer_selem_has_capture_volume(elem) || + snd_mixer_selem_has_capture_switch(elem); + + if (has_capture) { + LOG_INFO("[AudioCapture] Found capture control: '%s'", name); + + // 尝试启用捕获开关 + if (snd_mixer_selem_has_capture_switch(elem)) { + snd_mixer_selem_set_capture_switch_all(elem, 1); + LOG_INFO("[AudioCapture] Enabled capture switch for '%s'", name); + } + + // 尝试设置捕获音量到最大 + if (snd_mixer_selem_has_capture_volume(elem)) { + long min, max; + snd_mixer_selem_get_capture_volume_range(elem, &min, &max); + snd_mixer_selem_set_capture_volume_all(elem, max); + LOG_INFO("[AudioCapture] Set capture volume to max (%ld) for '%s'", max, name); + } + } + + // 尝试匹配常见的麦克风相关控制项 + if (strstr(name, "MIC") || strstr(name, "Mic") || strstr(name, "mic") || + strstr(name, "ADC") || strstr(name, "Capture") || strstr(name, "Input") || + strstr(name, "Line") || strstr(name, "LINEIN")) { + LOG_INFO("[AudioCapture] Found potential mic control: '%s'", name); + + // Day 23 fix: Restore playback volume to MAX for ADC/LINEOUT. + // On some codecs (e.g. AC108/ES8388), "Playback Volume" on ADC actually controls + // the digital gain of the ADC signal *before* it splits to capture/loopback. + // Setting it to 0 silences the capture. We will deal with echo via software if needed. + if (snd_mixer_selem_has_playback_volume(elem)) { + long min, max; + snd_mixer_selem_get_playback_volume_range(elem, &min, &max); + // Day 23: Set to 80% to balance capture signal vs loopback noise + long target = min + (max - min) * 0.8; + snd_mixer_selem_set_playback_volume_all(elem, target); + LOG_INFO("[AudioCapture] Set playback volume to 80%% (%ld/%ld) for '%s'", target, max, name); + } + + // Enable playback switch (to ensure hardware is powered/active) + if (snd_mixer_selem_has_playback_switch(elem)) { + snd_mixer_selem_set_playback_switch_all(elem, 1); // Enable + LOG_INFO("[AudioCapture] Enabled playback switch for '%s' (required for capture)", name); + } + } + } + + LOG_INFO("[AudioCapture] Scanned %d mixer controls", control_count); + + snd_mixer_close(mixer); + return true; +} + +/** + * @brief 初始化 ALSA 采集设备 + */ +bool AudioCapture::init() { + int err; + + // 0. 首先配置混音器,启用麦克风输入 + LOG_INFO("[AudioCapture] Setting up mixer for microphone..."); + setup_mixer("hw:0"); + + // 1. 打开 PCM 设备 (CAPTURE 模式,非阻塞) + // 使用 SND_PCM_NONBLOCK 避免 read 阻塞 + err = snd_pcm_open(&m_pcm_handle, m_device.c_str(), + SND_PCM_STREAM_CAPTURE, SND_PCM_NONBLOCK); + if (err < 0) { + LOG_ERROR("[AudioCapture] Cannot open device '%s': %s", + m_device.c_str(), snd_strerror(err)); + return false; + } + + LOG_INFO("[AudioCapture] Opened device: %s (non-blocking)", m_device.c_str()); + + // 2. 分配硬件参数对象 + snd_pcm_hw_params_t* hw_params; + snd_pcm_hw_params_alloca(&hw_params); + + // 3. 初始化硬件参数 + err = snd_pcm_hw_params_any(m_pcm_handle, hw_params); + if (err < 0) { + LOG_ERROR("[AudioCapture] Cannot initialize hw params: %s", snd_strerror(err)); + snd_pcm_close(m_pcm_handle); + m_pcm_handle = nullptr; + return false; + } + + // 4. 设置访问模式 (交织模式) + err = snd_pcm_hw_params_set_access(m_pcm_handle, hw_params, + SND_PCM_ACCESS_RW_INTERLEAVED); + if (err < 0) { + LOG_ERROR("[AudioCapture] Cannot set access type: %s", snd_strerror(err)); + snd_pcm_close(m_pcm_handle); + m_pcm_handle = nullptr; + return false; + } + + // 5. 设置采样格式 (16-bit signed little-endian) + err = snd_pcm_hw_params_set_format(m_pcm_handle, hw_params, + SND_PCM_FORMAT_S16_LE); + if (err < 0) { + LOG_ERROR("[AudioCapture] Cannot set sample format: %s", snd_strerror(err)); + snd_pcm_close(m_pcm_handle); + m_pcm_handle = nullptr; + return false; + } + + // 6. 设置采样率 + unsigned int actual_rate = m_sample_rate; + err = snd_pcm_hw_params_set_rate_near(m_pcm_handle, hw_params, + &actual_rate, 0); + if (err < 0) { + LOG_ERROR("[AudioCapture] Cannot set sample rate: %s", snd_strerror(err)); + snd_pcm_close(m_pcm_handle); + m_pcm_handle = nullptr; + return false; + } + + if (actual_rate != (unsigned int)m_sample_rate) { + LOG_WARN("[AudioCapture] Sample rate %d Hz not supported, using %d Hz", + m_sample_rate, actual_rate); + } + + // 7. 设置声道数 + err = snd_pcm_hw_params_set_channels(m_pcm_handle, hw_params, m_channels); + if (err < 0) { + LOG_ERROR("[AudioCapture] Cannot set channel count: %s", snd_strerror(err)); + snd_pcm_close(m_pcm_handle); + m_pcm_handle = nullptr; + return false; + } + + // 8. 设置缓冲区大小 (增大以提高稳定性) + // Period: 480 frames (30ms @ 16kHz) + // Buffer: 4800 frames (300ms @ 16kHz) + // Day 22 优化: 使用20ms包(320 samples),与服务器ASR期望一致 + snd_pcm_uframes_t period_size = 320; // 20ms @ 16kHz = 320 samples + snd_pcm_uframes_t buffer_size = 4800; + + err = snd_pcm_hw_params_set_period_size_near(m_pcm_handle, hw_params, + &period_size, 0); + if (err < 0) { + LOG_WARN("[AudioCapture] Cannot set period size: %s", snd_strerror(err)); + } + + err = snd_pcm_hw_params_set_buffer_size_near(m_pcm_handle, hw_params, + &buffer_size); + if (err < 0) { + LOG_WARN("[AudioCapture] Cannot set buffer size: %s", snd_strerror(err)); + } + + // 9. 应用硬件参数 + err = snd_pcm_hw_params(m_pcm_handle, hw_params); + if (err < 0) { + LOG_ERROR("[AudioCapture] Cannot apply hw params: %s", snd_strerror(err)); + snd_pcm_close(m_pcm_handle); + m_pcm_handle = nullptr; + return false; + } + + // 10. 准备设备 + err = snd_pcm_prepare(m_pcm_handle); + if (err < 0) { + LOG_ERROR("[AudioCapture] Cannot prepare device: %s", snd_strerror(err)); + snd_pcm_close(m_pcm_handle); + m_pcm_handle = nullptr; + return false; + } + + // 11. 启动捕获流 (非阻塞模式必须显式启动) + err = snd_pcm_start(m_pcm_handle); + if (err < 0) { + LOG_ERROR("[AudioCapture] Cannot start capture: %s", snd_strerror(err)); + snd_pcm_close(m_pcm_handle); + m_pcm_handle = nullptr; + return false; + } + + LOG_INFO("[AudioCapture] Initialized: %d Hz, %d channels, S16_LE", + actual_rate, m_channels); + LOG_INFO("[AudioCapture] Period: %lu frames, Buffer: %lu frames", + period_size, buffer_size); + LOG_INFO("[AudioCapture] Capture stream started"); + + return true; +} + +/** + * @brief 读取 PCM 数据 + * @param buffer 输出缓冲区 (int16_t 数组) + * @param frames 需要读取的帧数 + * @return 实际读取的帧数,<0 表示错误 + */ +snd_pcm_sframes_t AudioCapture::read(int16_t* buffer, snd_pcm_uframes_t frames) { + if (!m_pcm_handle) { + LOG_ERROR("[AudioCapture] Device not initialized"); + return -1; + } + + snd_pcm_sframes_t frames_read = snd_pcm_readi(m_pcm_handle, buffer, frames); + + if (frames_read < 0) { + // 错误处理 + if (frames_read == -EAGAIN) { + // 非阻塞模式:没有可用数据,返回 0 让调用者等待 + return 0; + } else if (frames_read == -EPIPE) { + // Overrun (缓冲区溢出) + LOG_WARN("[AudioCapture] Overrun occurred, recovering..."); + snd_pcm_prepare(m_pcm_handle); + return 0; // 本次读取失败,下次重试 + } else if (frames_read == -ESTRPIPE) { + // Suspend (设备挂起) + LOG_WARN("[AudioCapture] Device suspended, resuming..."); + while ((frames_read = snd_pcm_resume(m_pcm_handle)) == -EAGAIN) { + usleep(100000); // 等待 100ms + } + if (frames_read < 0) { + // 恢复失败,重新准备 + frames_read = snd_pcm_prepare(m_pcm_handle); + if (frames_read < 0) { + LOG_ERROR("[AudioCapture] Cannot recover from suspend: %s", + snd_strerror(frames_read)); + return frames_read; + } + } + return 0; + } else { + // 其他错误 + LOG_ERROR("[AudioCapture] Read error: %s", snd_strerror(frames_read)); + + // 尝试自动恢复 + int err = snd_pcm_recover(m_pcm_handle, frames_read, 0); + if (err < 0) { + LOG_ERROR("[AudioCapture] Cannot recover: %s, attempting to reinitialize...", snd_strerror(err)); + + // 关闭设备 + snd_pcm_close(m_pcm_handle); + m_pcm_handle = nullptr; + + // 等待一下再重新初始化 + usleep(500000); // 500ms + + // 重新初始化 + if (!init()) { + LOG_ERROR("[AudioCapture] Failed to reinitialize device"); + return -1; // 彻底失败 + } + + LOG_INFO("[AudioCapture] Device reinitialized successfully"); + return 0; // 本次读取失败,但设备已恢复 + } + return 0; + } + } + + // 成功读取 + if (frames_read != (snd_pcm_sframes_t)frames) { + LOG_DEBUG("[AudioCapture] Short read: expected %lu, got %ld frames", + frames, frames_read); + } + + return frames_read; +} diff --git a/avaota_app_demo/src/audio/audio_capture.h b/avaota_app_demo/src/audio/audio_capture.h new file mode 100644 index 0000000..e297289 --- /dev/null +++ b/avaota_app_demo/src/audio/audio_capture.h @@ -0,0 +1,49 @@ +/** + * @file audio_capture.h + * @brief 音频采集封装 - 基于 ALSA + */ + +#ifndef AUDIO_CAPTURE_H +#define AUDIO_CAPTURE_H + +#include +#include +#include + +class AudioCapture { +public: + /** + * @brief 构造函数 + * @param device ALSA 设备名,如 "hw:0,0" 或 "default" + * @param sample_rate 采样率 (Hz) + * @param channels 声道数 (1=单声道, 2=立体声) + */ + AudioCapture(const std::string& device, int sample_rate, int channels); + ~AudioCapture(); + + /** + * @brief 初始化 ALSA 采集设备 + * @return true 成功, false 失败 + */ + bool init(); + + /** + * @brief 读取 PCM 数据 + * @param buffer 输出缓冲区 (int16_t 数组) + * @param frames 帧数 (1帧 = channels * 2字节) + * @return 实际读取的帧数,<0 表示错误 + */ + snd_pcm_sframes_t read(int16_t* buffer, snd_pcm_uframes_t frames); + +private: + std::string m_device; + int m_sample_rate; + int m_channels; + + snd_pcm_t* m_pcm_handle; + + // 配置混音器以启用麦克风输入 + bool setup_mixer(const char* card_name); +}; + +#endif // AUDIO_CAPTURE_H diff --git a/avaota_app_demo/src/audio/audio_player.cpp b/avaota_app_demo/src/audio/audio_player.cpp new file mode 100644 index 0000000..6b4959d --- /dev/null +++ b/avaota_app_demo/src/audio/audio_player.cpp @@ -0,0 +1,327 @@ +/** + * @file audio_player.cpp + * @brief 音频播放实现 - 基于 ALSA + * @date 2024-11-24 + * @platform Avaota F1 (V821 / RISC-V) + */ + +#include "audio_player.h" +#include "../utils/logger.h" +#include +#include + +/** + * @brief 构造函数 + */ +AudioPlayer::AudioPlayer(const std::string& device, int sample_rate, int channels) + : m_device(device) + , m_sample_rate(sample_rate) + , m_channels(channels) + , m_pcm_handle(nullptr) +{ +} + +/** + * @brief 配置混音器以启用扬声器输出 + */ +bool AudioPlayer::setup_mixer(const char* card_name) { + snd_mixer_t *mixer = nullptr; + snd_mixer_selem_id_t *sid = nullptr; + int err; + + // 打开混音器 + err = snd_mixer_open(&mixer, 0); + if (err < 0) { + LOG_WARN("[AudioPlayer] Cannot open mixer: %s", snd_strerror(err)); + return false; + } + + // 附加到声卡 + err = snd_mixer_attach(mixer, card_name); + if (err < 0) { + LOG_WARN("[AudioPlayer] Cannot attach mixer to %s: %s", card_name, snd_strerror(err)); + snd_mixer_close(mixer); + return false; + } + + // 注册混音器 + err = snd_mixer_selem_register(mixer, NULL, NULL); + if (err < 0) { + LOG_WARN("[AudioPlayer] Cannot register mixer: %s", snd_strerror(err)); + snd_mixer_close(mixer); + return false; + } + + // 加载混音器元素 + err = snd_mixer_load(mixer); + if (err < 0) { + LOG_WARN("[AudioPlayer] Cannot load mixer: %s", snd_strerror(err)); + snd_mixer_close(mixer); + return false; + } + + LOG_INFO("[AudioPlayer] Mixer opened, scanning controls for playback..."); + + snd_mixer_elem_t *elem; + for (elem = snd_mixer_first_elem(mixer); elem; elem = snd_mixer_elem_next(elem)) { + if (!snd_mixer_selem_is_active(elem)) continue; + + snd_mixer_selem_id_alloca(&sid); + snd_mixer_selem_get_id(elem, sid); + const char *name = snd_mixer_selem_id_get_name(sid); + + if (snd_mixer_selem_has_playback_volume(elem)) { + long min, max; + snd_mixer_selem_get_playback_volume_range(elem, &min, &max); + // Day 22: 跳过 ADC (麦克风) 的 playback volume 设置 + // 避免覆盖 AudioCapture 中设置的静音逻辑,防止严重的回环噪声 + if (strstr(name, "ADC") || strstr(name, "Input") || strstr(name, "Capture")) { + LOG_INFO("[AudioPlayer] Skipping playback volume for '%s' (handled by AudioCapture)", name); + } else { + snd_mixer_selem_set_playback_volume_all(elem, max); + LOG_INFO("[AudioPlayer] Unmuted playback volume for '%s'", name); + } + } + + if (snd_mixer_selem_has_playback_switch(elem)) { + // Day 22 修复: 只禁用 loopback debug 开关 + // 注意:禁用 MIC playback switch 会导致麦克风无数据 (Day 12 发现) + std::string switch_name(name); + + // 检查是否是 loopback 开关 + bool is_loopback = (switch_name.find("loopback") != std::string::npos) || + (switch_name.find("Loopback") != std::string::npos) || + (switch_name.find("LOOPBACK") != std::string::npos); + + // Day 23 fix: User confirmed disabling "MIC Playback Switch" kills the microphone capture. + // We MUST enable it. Loopback/echo will be handled by other means or accepted for now. + if (is_loopback) { + snd_mixer_selem_set_playback_switch_all(elem, 0); // 禁用 + LOG_INFO("[AudioPlayer] DISABLED playback switch for '%s' (noise reduction)", name); + } else { + snd_mixer_selem_set_playback_switch_all(elem, 1); // 启用 + LOG_INFO("[AudioPlayer] Enabled playback switch for '%s'", name); + } + } + } + + snd_mixer_close(mixer); + return true; +} + +/** + * @brief 析构函数 + */ +AudioPlayer::~AudioPlayer() { + if (m_pcm_handle) { + snd_pcm_drain(m_pcm_handle); + snd_pcm_close(m_pcm_handle); + m_pcm_handle = nullptr; + LOG_INFO("[AudioPlayer] Device closed"); + } +} + +/** + * @brief 初始化 ALSA 播放设备 + */ +bool AudioPlayer::init() { + int err; + + // 0. 配置混音器 + // 尝试配置 hw:1 (可能是 I2S 接口) 和 hw:0 (可能是 Codec) + setup_mixer("hw:1"); + // 很多板子的扬声器音量其实还是得在 Codec (hw:0) 上调 + if (m_device.find("hw:1") != std::string::npos) { + setup_mixer("hw:0"); + } + + // 1. 打开 PCM 设备 (PLAYBACK 模式) + err = snd_pcm_open(&m_pcm_handle, m_device.c_str(), + SND_PCM_STREAM_PLAYBACK, 0); + if (err < 0) { + LOG_ERROR("[AudioPlayer] Cannot open device '%s': %s", + m_device.c_str(), snd_strerror(err)); + return false; + } + + LOG_INFO("[AudioPlayer] Opened device: %s", m_device.c_str()); + + // 2. 分配硬件参数对象 + snd_pcm_hw_params_t* hw_params; + snd_pcm_hw_params_alloca(&hw_params); + + // 3. 初始化硬件参数 + err = snd_pcm_hw_params_any(m_pcm_handle, hw_params); + if (err < 0) { + LOG_ERROR("[AudioPlayer] Cannot initialize hw params: %s", snd_strerror(err)); + snd_pcm_close(m_pcm_handle); + m_pcm_handle = nullptr; + return false; + } + + // 4. 设置访问模式 (交织模式) + err = snd_pcm_hw_params_set_access(m_pcm_handle, hw_params, + SND_PCM_ACCESS_RW_INTERLEAVED); + if (err < 0) { + LOG_ERROR("[AudioPlayer] Cannot set access type: %s", snd_strerror(err)); + snd_pcm_close(m_pcm_handle); + m_pcm_handle = nullptr; + return false; + } + + // 5. 设置采样格式 (16-bit signed little-endian) + err = snd_pcm_hw_params_set_format(m_pcm_handle, hw_params, + SND_PCM_FORMAT_S16_LE); + if (err < 0) { + LOG_ERROR("[AudioPlayer] Cannot set sample format: %s", snd_strerror(err)); + snd_pcm_close(m_pcm_handle); + m_pcm_handle = nullptr; + return false; + } + + // 6. 设置采样率 + unsigned int actual_rate = m_sample_rate; + err = snd_pcm_hw_params_set_rate_near(m_pcm_handle, hw_params, + &actual_rate, 0); + if (err < 0) { + LOG_ERROR("[AudioPlayer] Cannot set sample rate: %s", snd_strerror(err)); + snd_pcm_close(m_pcm_handle); + m_pcm_handle = nullptr; + return false; + } + + if (actual_rate != (unsigned int)m_sample_rate) { + LOG_WARN("[AudioPlayer] Sample rate %d Hz not supported, using %d Hz", + m_sample_rate, actual_rate); + } + + // 7. 设置声道数 + err = snd_pcm_hw_params_set_channels(m_pcm_handle, hw_params, m_channels); + if (err < 0) { + LOG_ERROR("[AudioPlayer] Cannot set channel count: %s", snd_strerror(err)); + snd_pcm_close(m_pcm_handle); + m_pcm_handle = nullptr; + return false; + } + + // 8. 设置缓冲区大小 (可选,优化延迟) + // Period: 160 frames (10ms @ 16kHz) + // Buffer: 1600 frames (100ms @ 16kHz) + snd_pcm_uframes_t period_size = 160; + snd_pcm_uframes_t buffer_size = 1600; + + err = snd_pcm_hw_params_set_period_size_near(m_pcm_handle, hw_params, + &period_size, 0); + if (err < 0) { + LOG_WARN("[AudioPlayer] Cannot set period size: %s", snd_strerror(err)); + } + + err = snd_pcm_hw_params_set_buffer_size_near(m_pcm_handle, hw_params, + &buffer_size); + if (err < 0) { + LOG_WARN("[AudioPlayer] Cannot set buffer size: %s", snd_strerror(err)); + } + + // 9. 应用硬件参数 + err = snd_pcm_hw_params(m_pcm_handle, hw_params); + if (err < 0) { + LOG_ERROR("[AudioPlayer] Cannot apply hw params: %s", snd_strerror(err)); + snd_pcm_close(m_pcm_handle); + m_pcm_handle = nullptr; + return false; + } + + // 10. 准备设备 + err = snd_pcm_prepare(m_pcm_handle); + if (err < 0) { + LOG_ERROR("[AudioPlayer] Cannot prepare device: %s", snd_strerror(err)); + snd_pcm_close(m_pcm_handle); + m_pcm_handle = nullptr; + return false; + } + + LOG_INFO("[AudioPlayer] Initialized: %d Hz, %d channels, S16_LE", + actual_rate, m_channels); + LOG_INFO("[AudioPlayer] Period: %lu frames, Buffer: %lu frames", + period_size, buffer_size); + + return true; +} + +/** + * @brief 写入 PCM 数据到扬声器 + * @param buffer 输入缓冲区 (int16_t 数组) + * @param frames 需要写入的帧数 + * @return 实际写入的帧数,<0 表示错误 + */ +snd_pcm_sframes_t AudioPlayer::write(const int16_t* buffer, snd_pcm_uframes_t frames) { + if (!m_pcm_handle) { + LOG_ERROR("[AudioPlayer] Device not initialized"); + return -1; + } + + snd_pcm_sframes_t frames_written = snd_pcm_writei(m_pcm_handle, buffer, frames); + + if (frames_written < 0) { + // 错误处理 + if (frames_written == -EPIPE) { + // Underrun (缓冲区欠载) + LOG_WARN("[AudioPlayer] Underrun occurred, recovering..."); + snd_pcm_prepare(m_pcm_handle); + + // 重试写入 + frames_written = snd_pcm_writei(m_pcm_handle, buffer, frames); + if (frames_written < 0) { + LOG_ERROR("[AudioPlayer] Write failed after underrun recovery"); + return frames_written; + } + } else if (frames_written == -ESTRPIPE) { + // Suspend (设备挂起) + LOG_WARN("[AudioPlayer] Device suspended, resuming..."); + while ((frames_written = snd_pcm_resume(m_pcm_handle)) == -EAGAIN) { + usleep(100000); // 等待 100ms + } + if (frames_written < 0) { + // 恢复失败,重新准备 + frames_written = snd_pcm_prepare(m_pcm_handle); + if (frames_written < 0) { + LOG_ERROR("[AudioPlayer] Cannot recover from suspend: %s", + snd_strerror(frames_written)); + return frames_written; + } + } + + // 重试写入 + frames_written = snd_pcm_writei(m_pcm_handle, buffer, frames); + if (frames_written < 0) { + LOG_ERROR("[AudioPlayer] Write failed after suspend recovery"); + return frames_written; + } + } else { + // 其他错误 + LOG_ERROR("[AudioPlayer] Write error: %s", snd_strerror(frames_written)); + + // 尝试自动恢复 + int err = snd_pcm_recover(m_pcm_handle, frames_written, 0); + if (err < 0) { + LOG_ERROR("[AudioPlayer] Cannot recover: %s", snd_strerror(err)); + return frames_written; + } + + // 重试写入 + frames_written = snd_pcm_writei(m_pcm_handle, buffer, frames); + if (frames_written < 0) { + LOG_ERROR("[AudioPlayer] Write failed after generic recovery"); + return frames_written; + } + } + } + + // 成功写入 + if (frames_written != (snd_pcm_sframes_t)frames) { + LOG_DEBUG("[AudioPlayer] Short write: expected %lu, wrote %ld frames", + frames, frames_written); + } + + return frames_written; +} diff --git a/avaota_app_demo/src/audio/audio_player.h b/avaota_app_demo/src/audio/audio_player.h new file mode 100644 index 0000000..a8bf390 --- /dev/null +++ b/avaota_app_demo/src/audio/audio_player.h @@ -0,0 +1,49 @@ +/** + * @file audio_player.h + * @brief 音频播放封装 - 基于 ALSA + */ + +#ifndef AUDIO_PLAYER_H +#define AUDIO_PLAYER_H + +#include +#include +#include + +class AudioPlayer { +public: + /** + * @brief 构造函数 + * @param device ALSA 设备名,如 "hw:0,0" 或 "default" + * @param sample_rate 采样率 (Hz) + * @param channels 声道数 (1=单声道, 2=立体声) + */ + AudioPlayer(const std::string& device, int sample_rate, int channels); + ~AudioPlayer(); + + /** + * @brief 初始化 ALSA 播放设备 + * @return true 成功, false 失败 + */ + bool init(); + + /** + * @brief 写入 PCM 数据到扬声器 + * @param buffer 输入缓冲区 (int16_t 数组) + * @param frames 帧数 (1帧 = channels * 2字节) + * @return 实际写入的帧数,<0 表示错误 + */ + snd_pcm_sframes_t write(const int16_t* buffer, snd_pcm_uframes_t frames); + +private: + std::string m_device; + int m_sample_rate; + int m_channels; + + snd_pcm_t* m_pcm_handle; + + // 私有方法: 配置混音器 + bool setup_mixer(const char* card_name); +}; + +#endif // AUDIO_PLAYER_H diff --git a/avaota_app_demo/src/camera/camera.cpp b/avaota_app_demo/src/camera/camera.cpp new file mode 100644 index 0000000..e15bc0b --- /dev/null +++ b/avaota_app_demo/src/camera/camera.cpp @@ -0,0 +1,425 @@ +/** + * @file camera.cpp + * @brief GC2083 摄像头驱动实现 - 基于全志 MPP 框架 + * + * 架构: VI (Video Input) → ISP → VENC (JPEG Encoder) + * 模式: 绑定模式 (自动流转,高性能) + */ + +#include "camera.h" +#include +#include +#include +#include +#include + +extern "C" { +#include +#include +#include +} + +// 日志宏 +#define LOG_TAG "Camera" +#define LOGD(fmt, ...) printf("[%s][D] " fmt "\n", LOG_TAG, ##__VA_ARGS__) +#define LOGI(fmt, ...) printf("[%s][I] " fmt "\n", LOG_TAG, ##__VA_ARGS__) +#define LOGW(fmt, ...) printf("[%s][W] " fmt "\n", LOG_TAG, ##__VA_ARGS__) +#define LOGE(fmt, ...) printf("[%s][E] " fmt "\n", LOG_TAG, ##__VA_ARGS__) + +// 默认配置 (Day 13: 降低负载减少网络拥堵) +#define DEFAULT_WIDTH 640 // Day 13: 从1280降低到640 +#define DEFAULT_HEIGHT 480 // Day 13: 从720降低到480 +// Day 22 优化: 户外稳定模式,适应4G手机热点网络波动 +#define DEFAULT_FPS 8 // 8fps 平衡流畅与带宽 +#define DEFAULT_QUALITY 45 // Qfactor=45,适度压缩节省带宽 +#define VI_BUFFER_NUM 5 // 增加缓冲区数量避免溢出 (Day 11) +#define VBV_BUFFER_SIZE 2048 // Day 13: 降低到2MB,640x480不需要4MB + +// GC2083 配置 +#define VIPP_DEV_ID 0 // sensor0 (GC2083) +#define ISP_DEV_ID 0 +#define VI_CHN_ID 0 +#define VENC_CHN_START 0 + +Camera::Camera() + : m_vi_dev(VIPP_DEV_ID) + , m_vi_chn(VI_CHN_ID) + , m_isp_dev(ISP_DEV_ID) + , m_venc_chn(MM_INVALID_CHN) + , m_width(DEFAULT_WIDTH) + , m_height(DEFAULT_HEIGHT) + , m_quality(DEFAULT_QUALITY) + , m_fps(0.0f) + , m_frame_count(0) + , m_last_time(0) +{ + LOGD("Camera constructor"); +} + +Camera::~Camera() +{ + LOGD("Camera destructor"); + + // 停止编码器 + if (m_venc_chn != MM_INVALID_CHN) { + AW_MPI_VENC_StopRecvPic(m_venc_chn); + AW_MPI_VENC_DestroyChn(m_venc_chn); + } + + // 停止 VI + AW_MPI_VI_DisableVirChn(m_vi_dev, m_vi_chn); + AW_MPI_VI_DestroyVirChn(m_vi_dev, m_vi_chn); + AW_MPI_VI_DisableVipp(m_vi_dev); + + // 停止 ISP + AW_MPI_ISP_Stop(m_isp_dev); + AW_MPI_VI_DestroyVipp(m_vi_dev); + + // 退出系统 + AW_MPI_SYS_Exit(); +} + +void Camera::deinit() +{ + LOGI("[Camera] Deinitializing for recovery..."); + + // 停止编码器 + if (m_venc_chn != MM_INVALID_CHN) { + AW_MPI_VENC_StopRecvPic(m_venc_chn); + AW_MPI_VENC_DestroyChn(m_venc_chn); + m_venc_chn = MM_INVALID_CHN; + } + + // 停止 VI + AW_MPI_VI_DisableVirChn(m_vi_dev, m_vi_chn); + AW_MPI_VI_DestroyVirChn(m_vi_dev, m_vi_chn); + AW_MPI_VI_DisableVipp(m_vi_dev); + + // 停止 ISP + AW_MPI_ISP_Stop(m_isp_dev); + AW_MPI_VI_DestroyVipp(m_vi_dev); + + // 退出系统 + AW_MPI_SYS_Exit(); + + // 重置统计 + m_fps = 0.0f; + m_frame_count = 0; + m_last_time = 0; + + LOGI("[Camera] Deinitialized, ready for reinit"); +} + +bool Camera::init() +{ + LOGI("Initializing camera: %dx%d @%dfps", m_width, m_height, DEFAULT_FPS); + + // 1. 初始化 MPP 系统 + MPP_SYS_CONF_S sys_conf; + memset(&sys_conf, 0, sizeof(MPP_SYS_CONF_S)); + sys_conf.nAlignWidth = 32; + AW_MPI_SYS_SetConf(&sys_conf); + + if (AW_MPI_SYS_Init() != SUCCESS) { + LOGE("AW_MPI_SYS_Init failed"); + return false; + } + LOGD("MPP system initialized"); + + // 2. 创建 VI 设备 (初始化 sensor subdev) + LOGD("Creating VI device %d...", m_vi_dev); + ERRORTYPE ret = AW_MPI_VI_CreateVipp(m_vi_dev); + if (ret != SUCCESS) { + LOGE("AW_MPI_VI_CreateVipp failed: 0x%x", ret); + AW_MPI_SYS_Exit(); + return false; + } + LOGD("VI device %d created successfully", m_vi_dev); + + // 配置 VIPP 属性 (使用 LBC 2.5x 压缩) + LOGD("Configuring VI attributes: %dx%d @%dfps", m_width, m_height, DEFAULT_FPS); + VI_ATTR_S vi_attr; + memset(&vi_attr, 0, sizeof(VI_ATTR_S)); + vi_attr.type = V4L2_BUF_TYPE_VIDEO_CAPTURE_MPLANE; + vi_attr.memtype = V4L2_MEMORY_MMAP; + vi_attr.format.pixelformat = map_PIXEL_FORMAT_E_to_V4L2_PIX_FMT(MM_PIXEL_FORMAT_YUV_AW_LBC_2_5X); + vi_attr.format.field = V4L2_FIELD_NONE; + vi_attr.format.colorspace = V4L2_COLORSPACE_REC709; + vi_attr.format.width = m_width; + vi_attr.format.height = m_height; + vi_attr.nbufs = VI_BUFFER_NUM; + vi_attr.nplanes = 2; + vi_attr.fps = DEFAULT_FPS; + vi_attr.use_current_win = 0; + vi_attr.wdr_mode = 0; + vi_attr.capturemode = V4L2_MODE_VIDEO; + vi_attr.drop_frame_num = 0; + + if (AW_MPI_VI_SetVippAttr(m_vi_dev, &vi_attr) != SUCCESS) { + LOGE("AW_MPI_VI_SetVippAttr failed"); + return false; + } + LOGD("VI device created and configured"); + + // 3. 启动 ISP (连接到 sensor) + if (!init_isp()) { + LOGE("init_isp failed"); + return false; + } + + // 4. 创建 VI 通道并启用 + if (AW_MPI_VI_CreateVirChn(m_vi_dev, m_vi_chn, NULL) != SUCCESS) { + LOGE("AW_MPI_VI_CreateVirChn failed"); + return false; + } + + if (AW_MPI_VI_EnableVipp(m_vi_dev) != SUCCESS) { + LOGE("AW_MPI_VI_EnableVipp failed"); + return false; + } + LOGD("VI channel created and enabled"); + + // 5. 初始化 VENC (Video Encoder) + if (!init_venc()) { + LOGE("init_venc failed"); + return false; + } + + // 6. 绑定 VI → VENC + MPP_CHN_S vi_chn = {MOD_ID_VIU, m_vi_dev, m_vi_chn}; + MPP_CHN_S venc_chn = {MOD_ID_VENC, 0, m_venc_chn}; + if (AW_MPI_SYS_Bind(&vi_chn, &venc_chn) != SUCCESS) { + LOGE("AW_MPI_SYS_Bind failed"); + return false; + } + LOGD("VI-VENC bind successful"); + + // 7. 启动采集和编码 + if (AW_MPI_VI_EnableVirChn(m_vi_dev, m_vi_chn) != SUCCESS) { + LOGE("AW_MPI_VI_EnableVirChn failed"); + return false; + } + + if (AW_MPI_VENC_StartRecvPic(m_venc_chn) != SUCCESS) { + LOGE("AW_MPI_VENC_StartRecvPic failed"); + return false; + } + + LOGI("Camera initialized successfully"); + return true; +} + +bool Camera::init_vi() +{ + // VI 初始化已在 init() 中完成 + return true; +} + +bool Camera::init_isp() +{ + LOGD("Initializing ISP..."); + + // 启动 ISP + if (AW_MPI_ISP_Run(m_isp_dev) != SUCCESS) { + LOGE("AW_MPI_ISP_Run failed"); + return false; + } + + LOGD("ISP running"); + return true; +} + +bool Camera::init_venc() +{ + LOGD("Initializing VENC (JPEG)..."); + + // 使用固定的大VBV缓冲区 (4MB) 避免 VBV FULL 错误 + unsigned int vbv_buf_size = VBV_BUFFER_SIZE * 1024; // 4MB + unsigned int vbv_thresh_size = m_width * m_height; + + LOGD("VBV buffer size: %u KB (%u bytes)", VBV_BUFFER_SIZE, vbv_buf_size); + + // 配置 VENC 通道属性 + VENC_CHN_ATTR_S venc_attr; + memset(&venc_attr, 0, sizeof(VENC_CHN_ATTR_S)); + + venc_attr.VeAttr.Type = PT_JPEG; + venc_attr.VeAttr.mVippID = m_vi_dev; + venc_attr.VeAttr.MaxKeyInterval = 1; + venc_attr.VeAttr.SrcPicWidth = m_width; + venc_attr.VeAttr.SrcPicHeight = m_height; + venc_attr.VeAttr.Field = VIDEO_FIELD_FRAME; + venc_attr.VeAttr.PixelFormat = MM_PIXEL_FORMAT_YUV_AW_LBC_2_5X; + venc_attr.VeAttr.mColorSpace = V4L2_COLORSPACE_REC709; + venc_attr.VeAttr.Rotate = ROTATE_NONE; + + // JPEG 特定配置 + venc_attr.VeAttr.AttrJpeg.MaxPicWidth = 0; + venc_attr.VeAttr.AttrJpeg.MaxPicHeight = 0; + venc_attr.VeAttr.AttrJpeg.BufSize = vbv_buf_size; + venc_attr.VeAttr.AttrJpeg.mThreshSize = vbv_thresh_size; + venc_attr.VeAttr.AttrJpeg.bByFrame = TRUE; + venc_attr.VeAttr.AttrJpeg.PicWidth = m_width; + venc_attr.VeAttr.AttrJpeg.PicHeight = m_height; + venc_attr.VeAttr.AttrJpeg.bSupportDCF = FALSE; + + // 创建编码通道 + m_venc_chn = VENC_CHN_START; + bool success = false; + while (m_venc_chn < VENC_MAX_CHN_NUM) { + ERRORTYPE ret = AW_MPI_VENC_CreateChn(m_venc_chn, &venc_attr); + if (ret == SUCCESS) { + success = true; + break; + } else if (ret == ERR_VENC_EXIST) { + m_venc_chn++; + } else { + LOGE("AW_MPI_VENC_CreateChn failed: 0x%x", ret); + m_venc_chn++; + } + } + + if (!success) { + LOGE("Failed to create VENC channel"); + m_venc_chn = MM_INVALID_CHN; + return false; + } + + // 设置 JPEG 质量 + VENC_PARAM_JPEG_S jpeg_param; + memset(&jpeg_param, 0, sizeof(VENC_PARAM_JPEG_S)); + jpeg_param.Qfactor = m_quality; + AW_MPI_VENC_SetJpegParam(m_venc_chn, &jpeg_param); + + // 允许丢帧以防止VBV满时完全阻塞 (Day 11: 改为允许丢帧) + AW_MPI_VENC_ForbidDiscardingFrame(m_venc_chn, FALSE); + + LOGD("VENC initialized: channel=%d, VBV=%uKB, quality=%d", + m_venc_chn, vbv_buf_size/1024, m_quality); + return true; +} + +bool Camera::capture_frame(uint8_t** jpeg_data, size_t* jpeg_size) +{ + if (!jpeg_data || !jpeg_size) { + LOGE("Invalid parameters"); + return false; + } + + // 获取编码流 + VENC_STREAM_S stream; + VENC_PACK_S pack; + memset(&stream, 0, sizeof(VENC_STREAM_S)); + memset(&pack, 0, sizeof(VENC_PACK_S)); + stream.mpPack = &pack; + stream.mPackCount = 1; + + // 增加超时时间到10秒,并添加重试机制 + const int max_retries = 3; + const int timeout_ms = 10000; // 10秒超时 + ERRORTYPE ret = ERR_VENC_BUF_EMPTY; + + for (int retry = 0; retry < max_retries && ret != SUCCESS; retry++) { + if (retry > 0) { + LOGW("Retry %d/%d getting stream...", retry, max_retries); + usleep(100000); // 100ms延迟再重试 + } + ret = AW_MPI_VENC_GetStream(m_venc_chn, &stream, timeout_ms); + } + + if (ret != SUCCESS) { + LOGE("AW_MPI_VENC_GetStream failed after %d retries: 0x%x", max_retries, ret); + return false; + } + + // 计算总大小 + size_t total_size = stream.mpPack[0].mLen0 + stream.mpPack[0].mLen1 + stream.mpPack[0].mLen2; + if (total_size == 0) { + LOGE("Empty JPEG frame"); + AW_MPI_VENC_ReleaseStream(m_venc_chn, &stream); + return false; + } + + // 分配内存并拷贝数据 + uint8_t* buffer = new uint8_t[total_size]; + size_t offset = 0; + + if (stream.mpPack[0].mLen0 > 0 && stream.mpPack[0].mpAddr0) { + memcpy(buffer + offset, stream.mpPack[0].mpAddr0, stream.mpPack[0].mLen0); + offset += stream.mpPack[0].mLen0; + } + if (stream.mpPack[0].mLen1 > 0 && stream.mpPack[0].mpAddr1) { + memcpy(buffer + offset, stream.mpPack[0].mpAddr1, stream.mpPack[0].mLen1); + offset += stream.mpPack[0].mLen1; + } + if (stream.mpPack[0].mLen2 > 0 && stream.mpPack[0].mpAddr2) { + memcpy(buffer + offset, stream.mpPack[0].mpAddr2, stream.mpPack[0].mLen2); + offset += stream.mpPack[0].mLen2; + } + + // 释放流 + AW_MPI_VENC_ReleaseStream(m_venc_chn, &stream); + + // 更新 FPS 统计 + update_fps_stats(); + + // 返回结果 + *jpeg_data = buffer; + *jpeg_size = total_size; + + LOGD("Captured JPEG: %zu bytes, FPS: %.1f", total_size, m_fps); + return true; +} + +void Camera::release_frame(uint8_t* jpeg_data) +{ + if (jpeg_data) { + delete[] jpeg_data; + } +} + +bool Camera::set_framesize(const std::string& size) +{ + LOGW("set_framesize not implemented yet: %s", size.c_str()); + // TODO: 动态调整分辨率需要重新配置 VI 和 VENC + return false; +} + +void Camera::set_quality(int quality) +{ + if (quality < 1 || quality > 99) { + LOGW("Invalid quality %d, using default %d", quality, DEFAULT_QUALITY); + quality = DEFAULT_QUALITY; + } + + m_quality = quality; + + if (m_venc_chn != MM_INVALID_CHN) { + VENC_PARAM_JPEG_S jpeg_param; + memset(&jpeg_param, 0, sizeof(VENC_PARAM_JPEG_S)); + jpeg_param.Qfactor = m_quality; + AW_MPI_VENC_SetJpegParam(m_venc_chn, &jpeg_param); + LOGD("JPEG quality updated: %d", m_quality); + } +} + +void Camera::update_fps_stats() +{ + m_frame_count++; + + struct timeval tv; + gettimeofday(&tv, NULL); + uint64_t current_time = tv.tv_sec * 1000000ULL + tv.tv_usec; + + if (m_last_time == 0) { + m_last_time = current_time; + return; + } + + uint64_t elapsed = current_time - m_last_time; + if (elapsed >= 1000000) { // 1秒 + m_fps = (float)m_frame_count * 1000000.0f / elapsed; + m_frame_count = 0; + m_last_time = current_time; + } +} diff --git a/avaota_app_demo/src/camera/camera.h b/avaota_app_demo/src/camera/camera.h new file mode 100644 index 0000000..57dbe40 --- /dev/null +++ b/avaota_app_demo/src/camera/camera.h @@ -0,0 +1,100 @@ +/** + * @file camera.h + * @brief 摄像头封装 - 基于全志 MPP 库 + * + * 功能: + * - 初始化 GC2083 MIPI CSI 摄像头 + * - 配置 ISP (Image Signal Processor) + * - JPEG 硬件编码 + * - 动态调整分辨率和画质 + */ + +#ifndef CAMERA_H +#define CAMERA_H + +#include +#include + +// MPP 库头文件 (根据 SDK 实际路径调整) +extern "C" { +#include +#include +#include +} + +class Camera { +public: + Camera(); + ~Camera(); + + /** + * @brief 初始化摄像头 + * @return true 成功, false 失败 + */ + bool init(); + + /** + * @brief 采集一帧 JPEG 图像 + * @param jpeg_data 输出参数,指向 JPEG 数据的指针 + * @param jpeg_size 输出参数,JPEG 数据大小(字节) + * @return true 成功, false 失败 + * @note 调用后必须使用 release_frame() 释放 + */ + bool capture_frame(uint8_t** jpeg_data, size_t* jpeg_size); + + /** + * @brief 释放帧缓冲 + * @param jpeg_data capture_frame() 返回的指针 + */ + void release_frame(uint8_t* jpeg_data); + + /** + * @brief 设置分辨率 + * @param size "VGA" / "SVGA" / "XGA" / "SXGA" + * @return true 成功, false 失败 + */ + bool set_framesize(const std::string& size); + + /** + * @brief 设置 JPEG 压缩质量 + * @param quality 5-40 (数值越小越清晰) + */ + void set_quality(int quality); + + /** + * @brief 获取当前 FPS 统计 + */ + float get_fps() const { return m_fps; } + + /** + * @brief 关闭摄像头(支持错误恢复后重新 init) + * @note Day 11 新增:用于错误恢复 + */ + void deinit(); + +private: + // MPP 句柄 + VI_DEV m_vi_dev; + VI_CHN m_vi_chn; + ISP_DEV m_isp_dev; + VENC_CHN m_venc_chn; + + // 配置参数 + int m_width; + int m_height; + int m_quality; + + // 性能统计 + float m_fps; + uint64_t m_frame_count; + uint64_t m_last_time; + + // 内部方法 + bool init_vi(); // Video Input + bool init_isp(); // Image Signal Processor + bool init_venc(); // Video Encoder + + void update_fps_stats(); +}; + +#endif // CAMERA_H diff --git a/avaota_app_demo/src/imu/icm42688.cpp b/avaota_app_demo/src/imu/icm42688.cpp new file mode 100644 index 0000000..4d5a1f5 --- /dev/null +++ b/avaota_app_demo/src/imu/icm42688.cpp @@ -0,0 +1,349 @@ +/** + * @file icm42688_spi.cpp + * @brief ICM-42688/ICM-42670 IMU 驱动 - GPIO 模拟 SPI 实现 + * @date 2025-11-27 + * @platform Avaota F1 (V821 / RISC-V) + * + * 硬件连接: + * - VCC → 3.3V + * - GND → GND + * - SCL/SCLK → PD3 (GPIO 99) + * - SDA/MOSI → PD2 (GPIO 98) + * - AD0/MISO → PD4 (GPIO 100) + * - CS → PD5 (GPIO 101) + * + * 使用 GPIO 模拟 SPI,速度约 1MHz + */ + +#include "icm42688.h" +#include "../utils/logger.h" + +#include +#include +#include +#include +#include + +// GPIO 引脚定义 +#define GPIO_SCLK 99 // PD3 - SPI 时钟 +#define GPIO_MOSI 98 // PD2 - 主→从数据 +#define GPIO_MISO 100 // PD4 - 从→主数据 +#define GPIO_CS 101 // PD5 - 片选 +#define GPIO_CHIP "/dev/gpiochip0" +#define SPI_DELAY_US 1 // 1us 延迟,约 500kHz + +// GPIO 句柄 +static int gpio_chip_fd = -1; +static int sclk_fd = -1; +static int mosi_fd = -1; +static int miso_fd = -1; +static int cs_fd = -1; + +// GPIO 控制函数 +static bool gpio_init() { + gpio_chip_fd = open(GPIO_CHIP, O_RDWR); + if (gpio_chip_fd < 0) { + LOG_ERROR("[IMU] Failed to open GPIO chip %s", GPIO_CHIP); + return false; + } + + // 请求 SCLK (输出) + struct gpiohandle_request req_sclk; + memset(&req_sclk, 0, sizeof(req_sclk)); + req_sclk.lineoffsets[0] = GPIO_SCLK; + req_sclk.flags = GPIOHANDLE_REQUEST_OUTPUT; + req_sclk.default_values[0] = 0; // 默认低电平 + req_sclk.lines = 1; + strcpy(req_sclk.consumer_label, "icm_sclk"); + + if (ioctl(gpio_chip_fd, GPIO_GET_LINEHANDLE_IOCTL, &req_sclk) < 0) { + LOG_ERROR("[IMU] Failed to request SCLK GPIO %d", GPIO_SCLK); + close(gpio_chip_fd); + return false; + } + sclk_fd = req_sclk.fd; + + // 请求 MOSI (输出) + struct gpiohandle_request req_mosi; + memset(&req_mosi, 0, sizeof(req_mosi)); + req_mosi.lineoffsets[0] = GPIO_MOSI; + req_mosi.flags = GPIOHANDLE_REQUEST_OUTPUT; + req_mosi.default_values[0] = 0; + req_mosi.lines = 1; + strcpy(req_mosi.consumer_label, "icm_mosi"); + + if (ioctl(gpio_chip_fd, GPIO_GET_LINEHANDLE_IOCTL, &req_mosi) < 0) { + LOG_ERROR("[IMU] Failed to request MOSI GPIO %d", GPIO_MOSI); + close(sclk_fd); + close(gpio_chip_fd); + return false; + } + mosi_fd = req_mosi.fd; + + // 请求 MISO (输入) + struct gpiohandle_request req_miso; + memset(&req_miso, 0, sizeof(req_miso)); + req_miso.lineoffsets[0] = GPIO_MISO; + req_miso.flags = GPIOHANDLE_REQUEST_INPUT; + req_miso.lines = 1; + strcpy(req_miso.consumer_label, "icm_miso"); + + if (ioctl(gpio_chip_fd, GPIO_GET_LINEHANDLE_IOCTL, &req_miso) < 0) { + LOG_ERROR("[IMU] Failed to request MISO GPIO %d", GPIO_MISO); + close(mosi_fd); + close(sclk_fd); + close(gpio_chip_fd); + return false; + } + miso_fd = req_miso.fd; + + // 请求 CS (输出,默认高电平 = 未选中) + struct gpiohandle_request req_cs; + memset(&req_cs, 0, sizeof(req_cs)); + req_cs.lineoffsets[0] = GPIO_CS; + req_cs.flags = GPIOHANDLE_REQUEST_OUTPUT; + req_cs.default_values[0] = 1; // 默认高电平(未选中) + req_cs.lines = 1; + strcpy(req_cs.consumer_label, "icm_cs"); + + if (ioctl(gpio_chip_fd, GPIO_GET_LINEHANDLE_IOCTL, &req_cs) < 0) { + LOG_ERROR("[IMU] Failed to request CS GPIO %d", GPIO_CS); + close(miso_fd); + close(mosi_fd); + close(sclk_fd); + close(gpio_chip_fd); + return false; + } + cs_fd = req_cs.fd; + + LOG_INFO("[IMU] GPIO SPI initialized: SCLK=PD3(GPIO%d), MOSI=PD2(GPIO%d), MISO=PD4(GPIO%d), CS=PD5(GPIO%d)", + GPIO_SCLK, GPIO_MOSI, GPIO_MISO, GPIO_CS); + return true; +} + +static void sclk_high() { + struct gpiohandle_data data; + data.values[0] = 1; + ioctl(sclk_fd, GPIOHANDLE_SET_LINE_VALUES_IOCTL, &data); + usleep(SPI_DELAY_US); +} + +static void sclk_low() { + struct gpiohandle_data data; + data.values[0] = 0; + ioctl(sclk_fd, GPIOHANDLE_SET_LINE_VALUES_IOCTL, &data); + usleep(SPI_DELAY_US); +} + +static void mosi_high() { + struct gpiohandle_data data; + data.values[0] = 1; + ioctl(mosi_fd, GPIOHANDLE_SET_LINE_VALUES_IOCTL, &data); +} + +static void mosi_low() { + struct gpiohandle_data data; + data.values[0] = 0; + ioctl(mosi_fd, GPIOHANDLE_SET_LINE_VALUES_IOCTL, &data); +} + +static bool miso_read() { + struct gpiohandle_data data; + ioctl(miso_fd, GPIOHANDLE_GET_LINE_VALUES_IOCTL, &data); + return data.values[0]; +} + +static void cs_select() { + struct gpiohandle_data data; + data.values[0] = 0; // 低电平 = 选中 + ioctl(cs_fd, GPIOHANDLE_SET_LINE_VALUES_IOCTL, &data); + usleep(SPI_DELAY_US); +} + +static void cs_deselect() { + struct gpiohandle_data data; + data.values[0] = 1; // 高电平 = 未选中 + ioctl(cs_fd, GPIOHANDLE_SET_LINE_VALUES_IOCTL, &data); + usleep(SPI_DELAY_US); +} + +// SPI 传输一个字节(Mode 0: CPOL=0, CPHA=0) +static uint8_t spi_transfer_byte(uint8_t tx_byte) { + uint8_t rx_byte = 0; + + for (int i = 7; i >= 0; i--) { + // 设置 MOSI(时钟下降沿前设置数据) + if (tx_byte & (1 << i)) { + mosi_high(); + } else { + mosi_low(); + } + + // 上升沿:从设备采样 MOSI + sclk_high(); + + // 读取 MISO(时钟上升沿后读取数据) + if (miso_read()) { + rx_byte |= (1 << i); + } + + // 下降沿:从设备改变 MISO + sclk_low(); + } + + return rx_byte; +} + +// 构造函数 +ICM42688::ICM42688(const std::string& i2c_device, uint8_t address) + : m_i2c_device(i2c_device), m_address(address), m_fd(-1), + m_ax(0), m_ay(0), m_az(0), + m_gx(0), m_gy(0), m_gz(0), + m_temp(0), + m_accel_scale(0.0f), m_gyro_scale(0.0f) { +} + +// 析构函数 +ICM42688::~ICM42688() { + if (cs_fd >= 0) close(cs_fd); + if (miso_fd >= 0) close(miso_fd); + if (mosi_fd >= 0) close(mosi_fd); + if (sclk_fd >= 0) close(sclk_fd); + if (gpio_chip_fd >= 0) close(gpio_chip_fd); +} + +// 初始化 IMU +bool ICM42688::init() { + // 1. 初始化 GPIO + if (!gpio_init()) { + LOG_ERROR("[IMU] GPIO initialization failed"); + return false; + } + + m_fd = 1; // 标记已初始化 + + // 等待芯片上电稳定 + LOG_INFO("[IMU] Waiting for chip power-up (100ms)..."); + usleep(100000); + + // 2. 读取 WHO_AM_I 验证设备 + LOG_INFO("[IMU] Reading WHO_AM_I register..."); + uint8_t who_am_i = read_register(ICM42688_WHO_AM_I); + if (who_am_i != ICM42688_DEVICE_ID && who_am_i != ICM42670_DEVICE_ID) { + LOG_ERROR("[IMU] ICM42688 not found, WHO_AM_I = 0x%02X (expected 0x47 or 0x67)", who_am_i); + return false; + } + LOG_INFO("[IMU] ICM42688 detected, WHO_AM_I = 0x%02X", who_am_i); + + // 3. 软复位 + write_register(ICM42688_PWR_MGMT0, 0x01); // SOFT_RESET + usleep(100000); // 等待 100ms + + // 4. 设置加速度计和陀螺仪为待机 + write_register(ICM42688_PWR_MGMT0, 0x1F); + usleep(1000); + + // 5. 配置加速度计(±16g, 1kHz ODR) + write_register(ICM42688_ACCEL_CONFIG0, + (uint8_t)AccelScale::AFS_16G << 5 | (uint8_t)ODR::ODR_1KHZ); + m_accel_scale = 16.0f / 32768.0f; // g + + // 6. 配置陀螺仪(±2000°/s, 1kHz ODR) + write_register(ICM42688_GYRO_CONFIG0, + (uint8_t)GyroScale::GFS_2000DPS << 5 | (uint8_t)ODR::ODR_1KHZ); + m_gyro_scale = 2000.0f / 32768.0f; // °/s + + // 7. 启动加速度计和陀螺仪 + write_register(ICM42688_PWR_MGMT0, 0x0F); // ACCEL + GYRO ON + usleep(100000); // 等待 100ms + + LOG_INFO("[IMU] ICM42688 initialized successfully"); + return true; +} + +// 读取传感器数据 +bool ICM42688::read_sensor() { + uint8_t data[14]; + + if (!read_registers(ICM42688_TEMP_DATA1, 14, data)) { + LOG_ERROR("[IMU] Failed to read sensor data"); + return false; + } + + // 解析数据(大端序) + m_temp = (int16_t)(data[0] << 8 | data[1]); + m_ax = (int16_t)(data[2] << 8 | data[3]); + m_ay = (int16_t)(data[4] << 8 | data[5]); + m_az = (int16_t)(data[6] << 8 | data[7]); + m_gx = (int16_t)(data[8] << 8 | data[9]); + m_gy = (int16_t)(data[10] << 8 | data[11]); + m_gz = (int16_t)(data[12] << 8 | data[13]); + + return true; +} + +// 获取数据 +float ICM42688::get_accel_x() { return (float)m_ax * m_accel_scale * G; } +float ICM42688::get_accel_y() { return (float)m_ay * m_accel_scale * G; } +float ICM42688::get_accel_z() { return (float)m_az * m_accel_scale * G; } +float ICM42688::get_gyro_x() { return (float)m_gx * m_gyro_scale; } +float ICM42688::get_gyro_y() { return (float)m_gy * m_gyro_scale; } +float ICM42688::get_gyro_z() { return (float)m_gz * m_gyro_scale; } +float ICM42688::get_temperature() { return ((float)m_temp / TEMP_SCALE) + TEMP_OFFSET; } + +// 写入寄存器(SPI) +bool ICM42688::write_register(uint8_t reg, uint8_t value) { + cs_select(); + + // 写操作:寄存器地址最高位为 0 + spi_transfer_byte(reg & 0x7F); + spi_transfer_byte(value); + + cs_deselect(); + return true; +} + +// 读取单个寄存器(SPI) +uint8_t ICM42688::read_register(uint8_t reg) { + cs_select(); + + // 读操作:寄存器地址最高位为 1 + spi_transfer_byte(reg | 0x80); + uint8_t value = spi_transfer_byte(0x00); // 发送 dummy 字节读取数据 + + cs_deselect(); + return value; +} + +// 读取多个寄存器(SPI) +bool ICM42688::read_registers(uint8_t reg, uint8_t count, uint8_t* data) { + cs_select(); + + // 读操作:寄存器地址最高位为 1 + spi_transfer_byte(reg | 0x80); + + for (uint8_t i = 0; i < count; i++) { + data[i] = spi_transfer_byte(0x00); // 发送 dummy 字节读取数据 + } + + cs_deselect(); + return true; +} + +// 读取所有传感器数据(便捷方法) +bool ICM42688::read_sensors(float& temp_c, float& ax, float& ay, float& az, + float& gx, float& gy, float& gz) { + if (!read_sensor()) { + return false; + } + + temp_c = get_temperature(); + ax = get_accel_x(); + ay = get_accel_y(); + az = get_accel_z(); + gx = get_gyro_x(); + gy = get_gyro_y(); + gz = get_gyro_z(); + + return true; +} diff --git a/avaota_app_demo/src/imu/icm42688.h b/avaota_app_demo/src/imu/icm42688.h new file mode 100644 index 0000000..5ca874d --- /dev/null +++ b/avaota_app_demo/src/imu/icm42688.h @@ -0,0 +1,202 @@ +/** + * @file icm42688.h + * @brief ICM-42688/ICM-42670 IMU 驱动 - Linux I2C 用户空间实现 + * @date 2025-11-26 + * @platform Avaota F1 (V821 / RISC-V) + * + * ICM-42688 是一款高性能 6 轴 IMU,支持 I2C 接口 + * - 3 轴加速度计:±2g, ±4g, ±8g, ±16g + * - 3 轴陀螺仪:±15.625°/s ~ ±2000°/s + * - 温度传感器 + */ + +#ifndef ICM42688_H +#define ICM42688_H + +#include +#include + +// ICM-42688 寄存器定义 +#define ICM42688_WHO_AM_I 0x75 +#define ICM42688_DEVICE_ID 0x47 // ICM-42688 +#define ICM42670_DEVICE_ID 0x67 // ICM-42670 + +#define ICM42688_PWR_MGMT0 0x4E // 电源管理 +#define ICM42688_GYRO_CONFIG0 0x4F // 陀螺仪配置 +#define ICM42688_ACCEL_CONFIG0 0x50 // 加速度计配置 +#define ICM42688_TEMP_DATA1 0x1D // 温度数据寄存器起始地址 + +/** + * @brief ICM-42688 IMU 类 + * + * 使用 Linux I2C 用户空间 API 与 ICM-42688 通信 + */ +class ICM42688 { +public: + /** + * @brief 加速度计量程 + */ + enum class AccelScale { + AFS_16G = 0, // ±16g + AFS_8G = 1, // ±8g + AFS_4G = 2, // ±4g + AFS_2G = 3 // ±2g + }; + + /** + * @brief 陀螺仪量程 + */ + enum class GyroScale { + GFS_2000DPS = 0, // ±2000°/s + GFS_1000DPS = 1, // ±1000°/s + GFS_500DPS = 2, // ±500°/s + GFS_250DPS = 3, // ±250°/s + GFS_125DPS = 4, // ±125°/s + GFS_62_5DPS = 5, // ±62.5°/s + GFS_31_25DPS = 6, // ±31.25°/s + GFS_15_625DPS = 7 // ±15.625°/s + }; + + /** + * @brief 输出数据率 (ODR) + */ + enum class ODR { + ODR_32KHZ = 0x01, + ODR_16KHZ = 0x02, + ODR_8KHZ = 0x03, + ODR_4KHZ = 0x04, + ODR_2KHZ = 0x05, + ODR_1KHZ = 0x06, // 推荐使用 + ODR_200HZ = 0x07, + ODR_100HZ = 0x08, + ODR_50HZ = 0x09, + ODR_25HZ = 0x0A, + ODR_12_5HZ = 0x0B + }; + + /** + * @brief 构造函数 + * @param i2c_device I2C 设备路径,如 "/dev/i2c-0" + * @param address I2C 地址,0x68 (AD0=GND) 或 0x69 (AD0=VCC) + */ + ICM42688(const std::string& i2c_device, uint8_t address = 0x68); + + /** + * @brief 析构函数 + */ + ~ICM42688(); + + /** + * @brief 初始化 IMU + * @return true 成功,false 失败 + */ + bool init(); + + /** + * @brief 读取传感器数据 + * @return true 成功,false 失败 + */ + bool read_sensor(); + + /** + * @brief 获取加速度计 X 轴数据 + * @return 加速度 (m/s²) + */ + float get_accel_x(); + + /** + * @brief 获取加速度计 Y 轴数据 + * @return 加速度 (m/s²) + */ + float get_accel_y(); + + /** + * @brief 获取加速度计 Z 轴数据 + * @return 加速度 (m/s²) + */ + float get_accel_z(); + + /** + * @brief 获取陀螺仪 X 轴数据 + * @return 角速度 (°/s) + */ + float get_gyro_x(); + + /** + * @brief 获取陀螺仪 Y 轴数据 + * @return 角速度 (°/s) + */ + float get_gyro_y(); + + /** + * @brief 获取陀螺仪 Z 轴数据 + * @return 角速度 (°/s) + */ + float get_gyro_z(); + + /** + * @brief 获取温度 + * @return 温度 (°C) + */ + float get_temperature(); + + /** + * @brief 读取所有传感器数据(便捷方法) + * @param temp_c 温度 (°C) + * @param ax 加速度 X (m/s²) + * @param ay 加速度 Y (m/s²) + * @param az 加速度 Z (m/s²) + * @param gx 陀螺仪 X (°/s) + * @param gy 陀螺仪 Y (°/s) + * @param gz 陀螺仪 Z (°/s) + * @return true 成功,false 失败 + */ + bool read_sensors(float& temp_c, float& ax, float& ay, float& az, + float& gx, float& gy, float& gz); + +private: + // I2C 设备信息 + std::string m_i2c_device; // I2C 设备路径 + uint8_t m_address; // I2C 地址 + int m_fd; // I2C 文件描述符 + + // 传感器原始数据 + int16_t m_ax, m_ay, m_az; // 加速度计原始值 + int16_t m_gx, m_gy, m_gz; // 陀螺仪原始值 + int16_t m_temp; // 温度原始值 + + // 缩放因子 + float m_accel_scale; // 加速度计缩放因子 (g) + float m_gyro_scale; // 陀螺仪缩放因子 (°/s) + + // 常量 + static constexpr float G = 9.80665f; // 重力加速度 (m/s²) + static constexpr float TEMP_SCALE = 333.87f; // 温度缩放因子 + static constexpr float TEMP_OFFSET = 21.0f; // 温度偏移 + + /** + * @brief 写入寄存器 + * @param reg 寄存器地址 + * @param value 写入的值 + * @return true 成功,false 失败 + */ + bool write_register(uint8_t reg, uint8_t value); + + /** + * @brief 读取单个寄存器 + * @param reg 寄存器地址 + * @return 读取的值(失败返回 0) + */ + uint8_t read_register(uint8_t reg); + + /** + * @brief 读取多个寄存器 + * @param reg 起始寄存器地址 + * @param count 读取字节数 + * @param data 数据缓冲区 + * @return true 成功,false 失败 + */ + bool read_registers(uint8_t reg, uint8_t count, uint8_t* data); +}; + +#endif // ICM42688_H diff --git a/avaota_app_demo/src/main.cpp b/avaota_app_demo/src/main.cpp new file mode 100644 index 0000000..06aaaa7 --- /dev/null +++ b/avaota_app_demo/src/main.cpp @@ -0,0 +1,377 @@ +/** + * @file main.cpp + * @brief AvaotaF1 智能眼镜客户端 - 主程序 + * @date 2025-11-21 + * @platform Avaota F1 (Allwinner V821 / RISC-V) + * + * 功能模块: + * - 摄像头视频流 (WebSocket /ws/camera) + * - 音频采集上传 (WebSocket /ws_audio) + * - TTS 音频播放 (WebSocket /ws_audio - 双向) + * - IMU 数据上报 (UDP :12345) + */ + +#include +#include +#include +#include +#include +#include + +#include "camera/camera.h" +#include "audio/audio_capture.h" +#include "audio/audio_player.h" +// Day 21: VAD 已移到服务器端 (Silero VAD),不再需要客户端 VAD +#include "imu/icm42688.h" +#include "network/ws_client.h" +#include "network/udp_sender.h" +#include "utils/logger.h" + +// ===== 配置参数 ===== +const char* SERVER_HOST = "8.148.25.142"; +const int SERVER_PORT = 8081; +const char* CAM_WS_PATH = "/ws/camera"; +const char* AUD_WS_PATH = "/ws_audio"; +const int UDP_PORT = 12345; + +// ===== 全局控制标志 ===== +std::atomic g_running{true}; + +// ===== 信号处理 ===== +void signal_handler(int sig) { + LOG_INFO("Received signal %d, shutting down...", sig); + g_running = false; +} + +// ===== 摄像头线程 ===== +void camera_thread() { + LOG_INFO("[CAM] Thread started"); + + Camera camera; + if (!camera.init()) { + LOG_ERROR("[CAM] Init failed"); + return; + } + + WSClient ws_cam(SERVER_HOST, SERVER_PORT, CAM_WS_PATH); + + // Day 11: 添加连续失败计数和恢复机制 + int consecutive_failures = 0; + const int MAX_FAILURES = 5; + + while (g_running) { + // 连接 WebSocket + bool connected = ws_cam.is_connected(); + if (!connected) { + if (ws_cam.connect()) { + LOG_INFO("[CAM] WebSocket connected"); + connected = true; + } else { + LOG_WARN("[CAM] WebSocket connect failed, will retry after frame consume"); + // Day 11: 不再 continue,而是继续采集帧来清空 VBV + } + } + + // 采集一帧 + uint8_t* jpeg_data = nullptr; + size_t jpeg_size = 0; + + if (camera.capture_frame(&jpeg_data, &jpeg_size)) { + consecutive_failures = 0; // 成功时重置计数 + + // Day 11: 只在连接时发送,否则丢弃帧以保持 VBV 流畅 + if (connected) { + if (!ws_cam.send_binary(jpeg_data, jpeg_size)) { + LOG_ERROR("[CAM] Send failed"); + ws_cam.disconnect(); + } + } else { + // 未连接时消费帧但不发送,间隔 1 秒重试连接 + usleep(1000000); + } + camera.release_frame(jpeg_data); + } else { + consecutive_failures++; + LOG_WARN("[CAM] Capture failed (%d/%d)", consecutive_failures, MAX_FAILURES); + + // Day 11: 连续失败超过阈值,尝试重新初始化 + if (consecutive_failures >= MAX_FAILURES) { + LOG_WARN("[CAM] Too many failures, reinitializing camera..."); + camera.deinit(); + usleep(1000000); // 等待 1 秒 + + if (!camera.init()) { + LOG_ERROR("[CAM] Reinit failed, fatal error!"); + break; // 无法恢复,退出线程 + } + + LOG_INFO("[CAM] Camera reinitialized successfully"); + consecutive_failures = 0; + } + + usleep(100000); // 100ms 等待 + } + + // 处理服务器消息 (SET:FRAMESIZE=VGA 等) + ws_cam.poll_messages([&camera](const std::string& msg) { + if (msg.find("SET:FRAMESIZE=") == 0) { + std::string size = msg.substr(14); + camera.set_framesize(size); + } else if (msg.find("SET:QUALITY=") == 0) { + int quality = std::stoi(msg.substr(12)); + camera.set_quality(quality); + } + }); + } + + LOG_INFO("[CAM] Thread stopped"); +} + +// ===== 音频采集线程 ===== +void audio_capture_thread() { + LOG_INFO("[AUD-CAP] Thread started"); + + AudioCapture mic("hw:0,0", 16000, 1); // 16kHz, mono - 麦克风 + if (!mic.init()) { + LOG_ERROR("[AUD-CAP] Init failed"); + return; + } + + // Day 21 改进: 移除客户端 VAD,改为服务器端 Silero VAD + // 客户端持续发送所有音频,服务器负责语音检测 + LOG_INFO("[AUD-CAP] Server-side VAD mode (continuous audio streaming)"); + + + // Day 14 修正: 恢复 WebSocket TTS 播放(经验证有效) + // 初始化扬声器 (hw:1,0 - I2S 接口连接 MAX98357A) + AudioPlayer speaker("hw:1,0", 16000, 1); // 16kHz, mono + bool speaker_enabled = false; + + if (speaker.init()) { + LOG_INFO("[AUD-PLAY] Speaker initialized on hw:1,0"); + speaker_enabled = true; + } else { + LOG_WARN("[AUD-PLAY] Speaker init failed, audio playback disabled"); + } + + WSClient ws_aud(SERVER_HOST, SERVER_PORT, AUD_WS_PATH); + + // Day 11: 添加诊断计数器 + int audio_send_count = 0; + int audio_bytes_total = 0; + int audio_read_attempts = 0; + int audio_zero_reads = 0; + + // TTS 预缓冲区 - Day 22 优化: 降低延迟 + // 原来2秒预缓冲导致外出时语音延迟太大,改为0.5秒 + std::vector tts_buffer; + const size_t PRE_BUFFER_FRAMES = 8000; // 0.5 秒的帧数 (16kHz) - 从32000降低 + const size_t MIN_PLAY_FRAMES = 1600; // 最小播放帧数 (0.1s) - 从4800降低 + bool is_buffering = true; + int tts_recv_count = 0; + + // Day 21 优化:指数退避重连策略 + int reconnect_delay = 1; // 初始 1 秒 + const int MAX_RECONNECT_DELAY = 16; // 最大 16 秒 + + while (g_running) { + if (!ws_aud.is_connected()) { + if (ws_aud.connect()) { + LOG_INFO("[AUD-CAP] WebSocket connected"); + ws_aud.send_text("START"); + // 重置 TTS 缓冲状态 + tts_buffer.clear(); + is_buffering = true; + // 连接成功,重置退避时间 + reconnect_delay = 1; + } else { + LOG_WARN("[AUD-CAP] Connect failed, retry in %ds", reconnect_delay); + sleep(reconnect_delay); + // 指数退避:每次失败后延迟翻倍,最大 16 秒 + reconnect_delay = std::min(reconnect_delay * 2, MAX_RECONNECT_DELAY); + continue; + } + } + + + // Day 22 优化: 使用20ms音频包(320 samples),与服务器ASR期望一致 + // 20ms @ 16kHz = 320 samples = 640 bytes + int16_t buffer[320]; + snd_pcm_sframes_t frames_read = mic.read(buffer, 320); + audio_read_attempts++; + + // 每 100 次读取输出诊断 + if (audio_read_attempts % 100 == 0) { + LOG_INFO("[AUD-CAP] Stats: attempts=%d, sent=%d, zero_reads=%d", + audio_read_attempts, audio_send_count, audio_zero_reads); + } + + // 检查致命错误(设备重新初始化失败) + if (frames_read < 0) { + LOG_ERROR("[AUD-CAP] Fatal error, exiting thread"); + break; + } + + if (frames_read > 0) { + // Day 21 改进: 移除客户端 VAD,改为持续发送所有音频 + // 服务器端使用 Silero VAD 进行语音检测(更准确) + int bytes_to_send = frames_read * 2; + if (ws_aud.send_binary((uint8_t*)buffer, bytes_to_send)) { + audio_send_count++; + audio_bytes_total += bytes_to_send; + + // 第一次发送时打印日志 + if (audio_send_count == 1) { + LOG_INFO("[AUD-CAP] First audio packet sent! (%d bytes)", bytes_to_send); + } + + // 每 100 次发送输出一次诊断日志 + if (audio_send_count % 100 == 0) { + LOG_INFO("[AUD-CAP] Sent %d packets, %d bytes total", + audio_send_count, audio_bytes_total); + } + } else { + LOG_WARN("[AUD-CAP] Send failed"); + } + } else { + audio_zero_reads++; + // 非阻塞模式:等待 20ms + usleep(20000); // 20ms + } + + // 处理服务器消息 (文本命令和二进制音频数据) + ws_aud.poll_messages([&](const std::string& msg) { + // Day 21: 正确处理 RESET/RESTART 命令,重新启动 ASR 会话 + if (msg == "RESTART" || msg == "RESET") { + LOG_INFO("[AUD-CAP] Received %s command, restarting ASR...", msg.c_str()); + ws_aud.send_text("START"); + // 重置 TTS 缓冲状态 + tts_buffer.clear(); + is_buffering = true; + tts_recv_count = 0; + } + }); + + // Day 14 修正: 恢复 WebSocket TTS 播放(服务器返回 16kHz PCM) + if (speaker_enabled) { + ws_aud.poll_binary_messages([&](const uint8_t* data, size_t size) { + // 服务器返回的是 16kHz, mono, S16_LE PCM 数据 + if (size % 2 == 0) { + size_t frames = size / 2; + tts_recv_count++; + + // 将新数据追加到缓冲区 + const int16_t* samples = (const int16_t*)data; + tts_buffer.insert(tts_buffer.end(), samples, samples + frames); + + // 第一次收到时输出日志 + if (tts_recv_count == 1) { + LOG_INFO("[AUD-PLAY] 🔊 First TTS chunk: %zu bytes", size); + } + + // 检查是否应该开始播放 + if (is_buffering && tts_buffer.size() >= PRE_BUFFER_FRAMES) { + LOG_INFO("[AUD-PLAY] Pre-buffer full (%zu frames), starting playback", + tts_buffer.size()); + is_buffering = false; + } + } + }); + + // 播放缓冲区中的数据 + if (!is_buffering && tts_buffer.size() >= MIN_PLAY_FRAMES) { + // 每次播放 1600 帧 (100ms) + size_t play_frames = std::min(tts_buffer.size(), (size_t)1600); + snd_pcm_sframes_t written = speaker.write(tts_buffer.data(), play_frames); + + if (written > 0) { + tts_buffer.erase(tts_buffer.begin(), tts_buffer.begin() + written); + } else if (written == -EAGAIN) { + usleep(5000); // 5ms + } + } else if (!is_buffering && tts_buffer.empty()) { + // 缓冲区空了,重新进入缓冲状态 + is_buffering = true; + tts_recv_count = 0; + } + } + } + + LOG_INFO("[AUD-CAP] Thread stopped"); +} + + + +// ===== IMU 线程 ===== +void imu_thread() { + LOG_INFO("[IMU] Thread started"); + + ICM42688 imu("/dev/spidev0.0"); + if (!imu.init()) { + LOG_ERROR("[IMU] Init failed (check Device Tree SPI config)"); + return; + } + + UDPSender udp(SERVER_HOST, UDP_PORT); + + while (g_running) { + float temp_c, ax, ay, az, gx, gy, gz; + + if (imu.read_sensors(temp_c, ax, ay, az, gx, gy, gz)) { + // 构造 JSON + char json[256]; + snprintf(json, sizeof(json), + "{\"ts\":%lu,\"temp_c\":%.2f," + "\"accel\":{\"x\":%.3f,\"y\":%.3f,\"z\":%.3f}," + "\"gyro\":{\"x\":%.3f,\"y\":%.3f,\"z\":%.3f}}", + (unsigned long)(time(nullptr) * 1000), temp_c, + ax, ay, az, gx, gy, gz); + + udp.send(json, strlen(json)); + } + + usleep(100000); // 10 Hz (100ms) - 降低采样率减少对音频的干扰 + } + + LOG_INFO("[IMU] Thread stopped"); +} + +// ===== 主函数 ===== +int main(int argc, char** argv) { + (void)argc; // 未使用 + (void)argv; + // 初始化日志系统 + Logger::init(LOG_LEVEL_INFO); + LOG_INFO("========================================"); + LOG_INFO("AvaotaF1 Client Starting..."); + LOG_INFO("Server: %s:%d", SERVER_HOST, SERVER_PORT); + LOG_INFO("========================================"); + + // 注册信号处理 + signal(SIGINT, signal_handler); + signal(SIGTERM, signal_handler); + + // 创建线程 + std::thread t_camera(camera_thread); + std::thread t_mic(audio_capture_thread); + // Day 14 修正: 移除 HTTP TTS 线程,改回 WebSocket TTS 播放(在 audio_capture_thread 中处理) + std::thread t_imu(imu_thread); + + // 主线程监控 + while (g_running) { + sleep(5); + LOG_INFO("[MAIN] Heartbeat - all threads running"); + } + + // 等待线程退出 + LOG_INFO("Waiting for threads to exit..."); + t_camera.join(); + t_mic.join(); + t_imu.join(); + + LOG_INFO("========================================"); + LOG_INFO("AvaotaF1 Client Stopped"); + LOG_INFO("========================================"); + + return 0; +} diff --git a/avaota_app_demo/src/network/udp_sender.cpp b/avaota_app_demo/src/network/udp_sender.cpp new file mode 100644 index 0000000..247b3d3 --- /dev/null +++ b/avaota_app_demo/src/network/udp_sender.cpp @@ -0,0 +1,70 @@ +/** + * @file udp_sender.cpp + * @brief UDP 发送器实现 + */ + +#include "udp_sender.h" +#include "../utils/logger.h" + +#include +#include +#include +#include +#include + +UDPSender::UDPSender(const std::string& host, int port) + : m_host(host), m_port(port), m_socket_fd(-1), m_sockaddr(nullptr) { + + // 创建 UDP socket + m_socket_fd = socket(AF_INET, SOCK_DGRAM, 0); + if (m_socket_fd < 0) { + LOG_ERROR("[UDP] Failed to create socket"); + return; + } + + // 配置目标地址 + struct sockaddr_in* addr = new struct sockaddr_in; + memset(addr, 0, sizeof(*addr)); + addr->sin_family = AF_INET; + addr->sin_port = htons(m_port); + + if (inet_pton(AF_INET, m_host.c_str(), &addr->sin_addr) <= 0) { + LOG_ERROR("[UDP] Invalid address: %s", m_host.c_str()); + close(m_socket_fd); + m_socket_fd = -1; + delete addr; + return; + } + + m_sockaddr = addr; + + LOG_INFO("[UDP] Initialized to %s:%d", m_host.c_str(), m_port); +} + +UDPSender::~UDPSender() { + if (m_socket_fd >= 0) { + close(m_socket_fd); + } + + if (m_sockaddr) { + delete (struct sockaddr_in*)m_sockaddr; + } +} + +int UDPSender::send(const void* data, size_t size) { + if (m_socket_fd < 0 || !m_sockaddr) { + return -1; + } + + struct sockaddr_in* addr = (struct sockaddr_in*)m_sockaddr; + + ssize_t sent = sendto(m_socket_fd, data, size, 0, + (struct sockaddr*)addr, sizeof(*addr)); + + if (sent < 0) { + LOG_ERROR("[UDP] Send failed"); + return -1; + } + + return (int)sent; +} diff --git a/avaota_app_demo/src/network/udp_sender.h b/avaota_app_demo/src/network/udp_sender.h new file mode 100644 index 0000000..ffaeba1 --- /dev/null +++ b/avaota_app_demo/src/network/udp_sender.h @@ -0,0 +1,37 @@ +/** + * @file udp_sender.h + * @brief UDP 发送器 - 用于 IMU 数据上报 + */ + +#ifndef UDP_SENDER_H +#define UDP_SENDER_H + +#include +#include + +class UDPSender { +public: + /** + * @brief 构造函数 + * @param host 目标主机地址 + * @param port 目标端口 + */ + UDPSender(const std::string& host, int port); + ~UDPSender(); + + /** + * @brief 发送数据 + * @param data 数据指针 + * @param size 数据大小 + * @return 发送的字节数,-1 表示失败 + */ + int send(const void* data, size_t size); + +private: + std::string m_host; + int m_port; + int m_socket_fd; + void* m_sockaddr; // struct sockaddr_in* (避免头文件依赖) +}; + +#endif // UDP_SENDER_H diff --git a/avaota_app_demo/src/network/ws_client.cpp b/avaota_app_demo/src/network/ws_client.cpp new file mode 100644 index 0000000..6dd8dc6 --- /dev/null +++ b/avaota_app_demo/src/network/ws_client.cpp @@ -0,0 +1,392 @@ +/** + * @file ws_client.cpp + * @brief WebSocket 客户端实现 - 轻量级版本 + */ + +#include "ws_client.h" +#include "../utils/logger.h" +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +// WebSocket 魔术字符串(用于握手验证,当前未使用) +// static const char* WS_MAGIC_STRING = "258EAFAA-5914-47DA-95CA-C5AB0DC85B11"; + +WSClient::WSClient(const std::string& host, int port, const std::string& path) + : m_host(host), m_port(port), m_path(path), + m_sockfd(-1), m_connected(false), m_running(false) { +} + +WSClient::~WSClient() { + disconnect(); +} + +bool WSClient::connect() { + if (m_connected) return true; + + // 创建 socket + m_sockfd = socket(AF_INET, SOCK_STREAM, 0); + if (m_sockfd < 0) { + LOG_ERROR("[WS] Failed to create socket: %s", strerror(errno)); + return false; + } + + // 解析主机地址 + struct sockaddr_in server_addr; + memset(&server_addr, 0, sizeof(server_addr)); + server_addr.sin_family = AF_INET; + server_addr.sin_port = htons(m_port); + + // 尝试直接解析 IP + if (inet_pton(AF_INET, m_host.c_str(), &server_addr.sin_addr) <= 0) { + // 不是IP地址,尝试 DNS 解析 + struct hostent* he = gethostbyname(m_host.c_str()); + if (!he) { + LOG_ERROR("[WS] Failed to resolve host: %s", m_host.c_str()); + close(m_sockfd); + m_sockfd = -1; + return false; + } + memcpy(&server_addr.sin_addr, he->h_addr_list[0], he->h_length); + } + + // 连接到服务器 + if (::connect(m_sockfd, (struct sockaddr*)&server_addr, sizeof(server_addr)) < 0) { + LOG_ERROR("[WS] Failed to connect to %s:%d: %s", + m_host.c_str(), m_port, strerror(errno)); + close(m_sockfd); + m_sockfd = -1; + return false; + } + + // 增大发送缓冲区到 256KB(默认通常只有 16KB) + int sndbuf = 256 * 1024; + if (setsockopt(m_sockfd, SOL_SOCKET, SO_SNDBUF, &sndbuf, sizeof(sndbuf)) < 0) { + LOG_WARN("[WS] Failed to set send buffer size: %s", strerror(errno)); + } + + // 增大接收缓冲区到 256KB + int rcvbuf = 256 * 1024; + if (setsockopt(m_sockfd, SOL_SOCKET, SO_RCVBUF, &rcvbuf, sizeof(rcvbuf)) < 0) { + LOG_WARN("[WS] Failed to set recv buffer size: %s", strerror(errno)); + } + + LOG_INFO("[WS] TCP connected to %s:%d (buffers: 256KB)", m_host.c_str(), m_port); + + // 执行 WebSocket 握手 + if (!perform_handshake()) { + close(m_sockfd); + m_sockfd = -1; + return false; + } + + m_connected = true; + m_running = true; + + // 修复: 在创建新线程前,必须确保旧线程已被 join,否则会触发 std::terminate + if (m_recv_thread.joinable()) { + m_recv_thread.join(); + } + + // 启动接收线程 + m_recv_thread = std::thread(&WSClient::recv_loop, this); + + LOG_INFO("[WS] WebSocket connected to ws://%s:%d%s", + m_host.c_str(), m_port, m_path.c_str()); + + return true; +} + +void WSClient::disconnect() { + if (!m_connected && m_sockfd < 0) return; + + m_running = false; + m_connected = false; + + // 发送关闭帧 + if (m_sockfd >= 0) { + uint8_t close_frame[] = {0x88, 0x00}; // FIN + CLOSE, 无payload + send(m_sockfd, close_frame, sizeof(close_frame), 0); + + // 关闭 socket 读写以中断任何阻塞的 recv()/send() + shutdown(m_sockfd, SHUT_RDWR); + } + + // 等待接收线程退出 + if (m_recv_thread.joinable()) { + m_recv_thread.join(); + } + + if (m_sockfd >= 0) { + close(m_sockfd); + m_sockfd = -1; + } + + LOG_INFO("[WS] Disconnected"); +} + +bool WSClient::send_text(const std::string& text) { + if (!m_connected) return false; + return send_frame((const uint8_t*)text.c_str(), text.length(), OP_TEXT); +} + +bool WSClient::send_binary(const uint8_t* data, size_t size) { + if (!m_connected) return false; + + // Day 12: 检查是否需要发送心跳 + time_t now = time(nullptr); + if (m_last_send_time > 0 && (now - m_last_send_time) > HEARTBEAT_INTERVAL) { + send_ping(); + } + + return send_frame(data, size, OP_BINARY); +} + +void WSClient::poll_messages(MessageCallback callback) { + std::lock_guard lock(m_recv_mutex); + + while (!m_recv_queue.empty()) { + callback(m_recv_queue.front()); + m_recv_queue.pop(); + } +} + +void WSClient::poll_binary_messages(std::function callback) { + std::lock_guard lock(m_binary_mutex); + + while (!m_binary_queue.empty()) { + const std::vector& data = m_binary_queue.front(); + callback(data.data(), data.size()); + m_binary_queue.pop(); + } +} + +// ===== 内部实现 ===== + +bool WSClient::perform_handshake() { + // 生成随机 Sec-WebSocket-Key (base64编码的16字节随机数) + uint8_t random_bytes[16]; + for (int i = 0; i < 16; ++i) { + random_bytes[i] = rand() % 256; + } + + // Base64 编码 + BIO *bio, *b64; + BUF_MEM *bufferPtr; + + b64 = BIO_new(BIO_f_base64()); + bio = BIO_new(BIO_s_mem()); + bio = BIO_push(b64, bio); + + BIO_set_flags(bio, BIO_FLAGS_BASE64_NO_NL); + BIO_write(bio, random_bytes, 16); + BIO_flush(bio); + BIO_get_mem_ptr(bio, &bufferPtr); + + std::string ws_key(bufferPtr->data, bufferPtr->length); + BIO_free_all(bio); + + // 构造 HTTP 升级请求 + char request[1024]; + snprintf(request, sizeof(request), + "GET %s HTTP/1.1\r\n" + "Host: %s:%d\r\n" + "Upgrade: websocket\r\n" + "Connection: Upgrade\r\n" + "Sec-WebSocket-Key: %s\r\n" + "Sec-WebSocket-Version: 13\r\n" + "\r\n", + m_path.c_str(), m_host.c_str(), m_port, ws_key.c_str()); + + // 发送请求 + if (send(m_sockfd, request, strlen(request), 0) < 0) { + LOG_ERROR("[WS] Failed to send handshake request"); + return false; + } + + // 接收响应 + char response[2048]; + int n = recv(m_sockfd, response, sizeof(response) - 1, 0); + if (n <= 0) { + LOG_ERROR("[WS] Failed to receive handshake response"); + return false; + } + response[n] = '\0'; + + // 简单验证响应(检查 "101 Switching Protocols") + if (strstr(response, "101") == NULL || + strstr(response, "Switching Protocols") == NULL) { + LOG_ERROR("[WS] Handshake failed: %s", response); + return false; + } + + LOG_DEBUG("[WS] Handshake successful"); + return true; +} + +void WSClient::recv_loop() { + LOG_INFO("[WS] Receive loop started"); + + while (m_running && m_connected) { + std::vector payload; + uint8_t opcode; + + if (recv_frame(payload, opcode)) { + if (opcode == OP_TEXT) { + // 文本消息 + std::string msg((char*)payload.data(), payload.size()); + std::lock_guard lock(m_recv_mutex); + m_recv_queue.push(msg); + LOG_INFO("[WS] 📩 Received text: %s", msg.c_str()); + } else if (opcode == OP_BINARY) { + // 二进制消息 - 保存到队列 + std::lock_guard lock(m_binary_mutex); + m_binary_queue.push(payload); + // Day 12: 提升日志级别,确认服务器是否发送 TTS 音频 + LOG_INFO("[WS] 🔔 Received binary: %zu bytes (queue: %zu)", payload.size(), m_binary_queue.size()); + } else if (opcode == OP_PING) { + // 回复 PONG + send_frame(payload.data(), payload.size(), OP_PONG); + } else if (opcode == OP_CLOSE) { + LOG_WARN("[WS] Server closed connection"); + m_connected = false; + break; + } + } else { + if (m_connected) { + LOG_ERROR("[WS] Failed to receive frame, disconnecting"); + m_connected = false; + } + break; + } + } + + LOG_INFO("[WS] Receive loop stopped"); +} + +bool WSClient::send_frame(const uint8_t* data, size_t len, uint8_t opcode) { + if (m_sockfd < 0 || !m_connected) return false; + + std::vector frame; + + // 第1字节: FIN=1, opcode + frame.push_back(0x80 | opcode); + + // 第2字节及后续: MASK=1, payload长度 + uint8_t mask_key[4]; + generate_mask_key(mask_key); + + if (len < 126) { + frame.push_back(0x80 | (uint8_t)len); + } else if (len < 65536) { + frame.push_back(0x80 | 126); + frame.push_back((len >> 8) & 0xFF); + frame.push_back(len & 0xFF); + } else { + frame.push_back(0x80 | 127); + for (int i = 7; i >= 0; --i) { + frame.push_back((len >> (i * 8)) & 0xFF); + } + } + + // Mask key + for (int i = 0; i < 4; ++i) { + frame.push_back(mask_key[i]); + } + + // Masked payload + for (size_t i = 0; i < len; ++i) { + frame.push_back(data[i] ^ mask_key[i % 4]); + } + + // 发送帧 + ssize_t sent = send(m_sockfd, frame.data(), frame.size(), 0); + if (sent < 0 || (size_t)sent != frame.size()) { + LOG_ERROR("[WS] Failed to send frame"); + return false; + } + + // Day 12: 更新最后发送时间 + m_last_send_time = time(nullptr); + + return true; +} + +bool WSClient::recv_frame(std::vector& payload, uint8_t& opcode) { + // 读取前2字节 + uint8_t header[2]; + if (recv(m_sockfd, header, 2, MSG_WAITALL) != 2) { + return false; + } + + // bool fin = (header[0] & 0x80) != 0; // 当前未使用 + opcode = header[0] & 0x0F; + bool masked = (header[1] & 0x80) != 0; + uint64_t payload_len = header[1] & 0x7F; + + // 读取扩展长度 + if (payload_len == 126) { + uint8_t len_bytes[2]; + if (recv(m_sockfd, len_bytes, 2, MSG_WAITALL) != 2) { + return false; + } + payload_len = ((uint64_t)len_bytes[0] << 8) | len_bytes[1]; + } else if (payload_len == 127) { + uint8_t len_bytes[8]; + if (recv(m_sockfd, len_bytes, 8, MSG_WAITALL) != 8) { + return false; + } + payload_len = 0; + for (int i = 0; i < 8; ++i) { + payload_len = (payload_len << 8) | len_bytes[i]; + } + } + + // 读取 mask key(服务器不应该发送masked数据) + uint8_t mask_key[4] = {0}; + if (masked) { + if (recv(m_sockfd, mask_key, 4, MSG_WAITALL) != 4) { + return false; + } + } + + // 读取 payload + payload.resize(payload_len); + if (payload_len > 0) { + ssize_t received = recv(m_sockfd, payload.data(), payload_len, MSG_WAITALL); + if (received != (ssize_t)payload_len) { + return false; + } + + // 解码(如果有mask) + if (masked) { + for (size_t i = 0; i < payload_len; ++i) { + payload[i] ^= mask_key[i % 4]; + } + } + } + + return true; +} + +void WSClient::generate_mask_key(uint8_t* mask) { + for (int i = 0; i < 4; ++i) { + mask[i] = rand() % 256; + } +} + +// Day 12: 心跳 PING 帧发送 +void WSClient::send_ping() { + if (m_sockfd >= 0 && m_connected) { + send_frame(nullptr, 0, OP_PING); + LOG_INFO("[WS] 💓 Sent PING heartbeat"); + } +} diff --git a/avaota_app_demo/src/network/ws_client.h b/avaota_app_demo/src/network/ws_client.h new file mode 100644 index 0000000..597575d --- /dev/null +++ b/avaota_app_demo/src/network/ws_client.h @@ -0,0 +1,130 @@ +/** + * @file ws_client.h + * @brief WebSocket 客户端封装 - 轻量级实现(无 libuwsc 依赖) + * + * 功能: + * - 连接到 WebSocket 服务器 + * - 发送文本/二进制消息 + * - 接收消息回调 + * - 线程安全的消息队列 + */ + +#ifndef WS_CLIENT_H +#define WS_CLIENT_H + +#include +#include +#include +#include +#include +#include +#include +#include + +class WSClient { +public: + using MessageCallback = std::function; + + /** + * @brief 构造函数 + * @param host 服务器地址 + * @param port 服务器端口 + * @param path WebSocket 路径 (如 "/ws/camera") + */ + WSClient(const std::string& host, int port, const std::string& path); + ~WSClient(); + + /** + * @brief 连接到服务器 + * @return true 成功, false 失败 + */ + bool connect(); + + /** + * @brief 断开连接 + */ + void disconnect(); + + /** + * @brief 检查是否已连接 + */ + bool is_connected() const { return m_connected; } + + /** + * @brief 发送文本消息 + * @param text 文本内容 + * @return true 成功, false 失败 + */ + bool send_text(const std::string& text); + + /** + * @brief 发送二进制消息 + * @param data 二进制数据 + * @param size 数据大小 + * @return true 成功, false 失败 + */ + bool send_binary(const uint8_t* data, size_t size); + + /** + * @brief 轮询消息 (处理接收到的消息) + * @param callback 消息处理回调函数 + */ + void poll_messages(MessageCallback callback); + + /** + * @brief 轮询二进制数据 (处理接收到的二进制帧) + * @param callback 二进制数据处理回调函数 (data, size) + */ + void poll_binary_messages(std::function callback); + +private: + std::string m_host; + int m_port; + std::string m_path; + + int m_sockfd; + std::atomic m_connected; + std::atomic m_running; + + std::thread m_recv_thread; + + // 发送队列 + struct Message { + std::vector data; + bool is_binary; + }; + std::queue m_send_queue; + std::mutex m_send_mutex; + + // 接收队列 (文本消息) + std::queue m_recv_queue; + std::mutex m_recv_mutex; + + // 接收队列 (二进制数据) + std::queue> m_binary_queue; + std::mutex m_binary_mutex; + + // 内部实现 + bool perform_handshake(); + void recv_loop(); + bool send_frame(const uint8_t* data, size_t len, uint8_t opcode); + bool recv_frame(std::vector& payload, uint8_t& opcode); + void generate_mask_key(uint8_t* mask); + + // Day 12: 心跳机制 (使用普通 time_t 避免 32 位平台原子操作问题) + time_t m_last_send_time = 0; // 上次发送时间 + static const int HEARTBEAT_INTERVAL = 25; // 心跳间隔(秒) + void send_ping(); // 发送 PING 帧 + + // WebSocket 操作码 + enum Opcode { + OP_CONTINUATION = 0x0, + OP_TEXT = 0x1, + OP_BINARY = 0x2, + OP_CLOSE = 0x8, + OP_PING = 0x9, + OP_PONG = 0xA + }; +}; + +#endif // WS_CLIENT_H diff --git a/avaota_app_demo/src/utils/logger.cpp b/avaota_app_demo/src/utils/logger.cpp new file mode 100644 index 0000000..32b834f --- /dev/null +++ b/avaota_app_demo/src/utils/logger.cpp @@ -0,0 +1,45 @@ +/** + * @file logger.cpp + * @brief 日志系统实现 + */ + +#include "logger.h" + +// 静态成员初始化 +LogLevel Logger::s_log_level = LOG_LEVEL_INFO; + +// ========================================== +// 用于解决 eyesee-mpp 库的链接依赖 (stub) +// 替代 liblog/libglog,避免动态链接错误 +// ========================================== + +#include +#include + +extern "C" { + +// 模拟 log_printf +void log_printf(int level, const char* fmt, ...) { + // 简单映射一下级别 (eyesee-mpp 定义可能不同,这不重要) + if (level < 2) return; // 忽略低级别日志 + + va_list args; + va_start(args, fmt); + vfprintf(stderr, fmt, args); + va_end(args); + // fprintf(stderr, "\n"); +} + +// 某些库可能还需要这些符号 +// void log_set_level(int level) { (void)level; } // libcdx_base 已定义 +// int log_get_level() { return 1; } // libcdx_base 已定义 +void alog(int level, const char* tag, const char* fmt, ...) { + (void)level; (void)tag; (void)fmt; +} +void SLOGD(const char* fmt, ...) { (void)fmt; } +void SLOGE(const char* fmt, ...) { (void)fmt; } +void SLOGW(const char* fmt, ...) { (void)fmt; } +void SLOGI(const char* fmt, ...) { (void)fmt; } +void SLOGV(const char* fmt, ...) { (void)fmt; } + +} // extern "C" diff --git a/avaota_app_demo/src/utils/logger.h b/avaota_app_demo/src/utils/logger.h new file mode 100644 index 0000000..181b0d1 --- /dev/null +++ b/avaota_app_demo/src/utils/logger.h @@ -0,0 +1,61 @@ +/** + * @file logger.h + * @brief 简易日志系统 + */ + +#ifndef LOGGER_H +#define LOGGER_H + +#include +#include +#include + +enum LogLevel { + LOG_LEVEL_DEBUG = 0, + LOG_LEVEL_INFO = 1, + LOG_LEVEL_WARN = 2, + LOG_LEVEL_ERROR = 3 +}; + +class Logger { +public: + static void init(LogLevel level) { + s_log_level = level; + } + + static void log(LogLevel level, const char* file, int line, const char* fmt, ...) { + if (level < s_log_level) return; + + // 时间戳 + time_t now = time(nullptr); + struct tm* t = localtime(&now); + char timestamp[32]; + strftime(timestamp, sizeof(timestamp), "%Y-%m-%d %H:%M:%S", t); + + // 日志级别 + const char* level_str[] = {"DEBUG", "INFO", "WARN", "ERROR"}; + + // 输出前缀 + fprintf(stderr, "[%s] [%s] ", timestamp, level_str[level]); + + // 输出消息 + va_list args; + va_start(args, fmt); + vfprintf(stderr, fmt, args); + va_end(args); + + fprintf(stderr, " (%s:%d)\n", file, line); + fflush(stderr); + } + +private: + static LogLevel s_log_level; +}; + +// 宏定义 +#define LOG_DEBUG(fmt, ...) Logger::log(LOG_LEVEL_DEBUG, __FILE__, __LINE__, fmt, ##__VA_ARGS__) +#define LOG_INFO(fmt, ...) Logger::log(LOG_LEVEL_INFO, __FILE__, __LINE__, fmt, ##__VA_ARGS__) +#define LOG_WARN(fmt, ...) Logger::log(LOG_LEVEL_WARN, __FILE__, __LINE__, fmt, ##__VA_ARGS__) +#define LOG_ERROR(fmt, ...) Logger::log(LOG_LEVEL_ERROR, __FILE__, __LINE__, fmt, ##__VA_ARGS__) + +#endif // LOGGER_H diff --git a/docs/1.png b/docs/1.png new file mode 100644 index 0000000..b1632f4 Binary files /dev/null and b/docs/1.png differ diff --git a/docs/2.png b/docs/2.png new file mode 100644 index 0000000..dac91a6 Binary files /dev/null and b/docs/2.png differ diff --git a/docs/AvaotaF1.md b/docs/AvaotaF1.md new file mode 100644 index 0000000..4577b32 --- /dev/null +++ b/docs/AvaotaF1.md @@ -0,0 +1,1366 @@ +# 百问网 AvaotaF1 核心板 + +百问网的 **AvaotaF1 V821 开发套件** 采用 Pico 尺寸设计,紧凑且功能强大,支持标准 2.54 排针接口,方便与面包板连接,进行 DIY 实验。其超薄双面设计令其尺寸仅与 1 元硬币相当,集成了 V821 所有核心功能,极大地提升了开发灵活性与可扩展性。 + +这款开发套件具备多种强大特性: + +- **板载 MIPI CSI 摄像头接口**,支持高清图像采集。 +- **MIC 拾音功能**,便于音频采集。 +- **SPI NOR FLASH(32MB)**,提供充足的存储空间。 +- **WiFi 陶瓷天线**,支持无线连接,拓展网络功能。 +- **TF 卡卡座**,方便数据存储和扩展。 +- **烧录按键**,简化固件烧录操作。 +- 丰富的 **GPIO 资源**,可灵活配置和控制外部硬件设备。 +- 硬件**没有使用PMC**功能 + +该开发套件支持最新的 **Tina Linux 5.0 系统**,可直接在 V821 AvaotaF1 上进行开发。除此之外,还支持多种配件: + +- **MIPI 摄像头 GC2083**,提供高质量图像采集。 +- **SPI 屏幕**:包括 3.5 寸 320x480 分辨率显示屏和 1.54 寸 240x240 分辨率显示屏,适应多样的显示需求。 + +AvaotaF1 V821 开发套件集成了丰富的功能,操作简便且便于拓展,是进行嵌入式开发与实验的理想选择。 + +![image-20250424093755858](https://docs.aw-ol.com/assets/images/image-20250424093755858-281a5b7a60fac210009c0a40e352776e.png) + +## 核心板参数 + +| 项目 | 参数 | +| -------- | -------------------------------------------------- | +| 主控 | 全志V821L2-WXX | +| PMU | 集成电源芯片EA3036 | +| DDR | Internal 64MB DDR2 | +| Memory | Nor Flash 32MB(PY25Q256) | +| 无线网络 | SIP 2.4GHz WIFI | +| 摄像头 | 单目 1920x1080@30fps | +| 屏幕 | 3.5寸(320*480)SPI 屏 | +| 麦克风 | 模拟麦克风*1 | +| 按键 | FEL烧录 | +| 灯 | LED * 1 | +| Debug | 支持uart串口调试,支持ADB USB调试 | +| USB | Type-C USB * 1, 同时支持供电和数据传输以及串口输出 | +| GPIO | 引出双盘排针30Pin 支持多达28个GPIO信号 | +| 板身尺寸 | 长35mm*宽22mm | +| 板层 | 6层板 | + +## 核心板接口功能示意 + +![image-20250424100013313](https://docs.aw-ol.com/assets/images/image-20250424100013313-f549f27f1da1cf80ca34db274b4e9760.png) + +## 核心板接口功能 + +![image-20250421132702741](https://docs.aw-ol.com/assets/images/image-20250421132702741-db92937e87cebb5f50a48b8aa4934d1b.png) + +![image-20250421132722612](https://docs.aw-ol.com/assets/images/image-20250421132722612-06a5b19112b0ac7b7c7eecfeb0e9fefd.png) + +| Signal Name | Description | Type | +| --------------------- | ------------------------------------------------------------ | ------- | +| FEL | Boot Process Select Jump to the Try Media Boot process when FEL is high level, or else enter into the mandatory upgrade process. | I | +| **Clock Fanout** | | | +| CLK-FANOUT0 | Internal Clock Fanout Optional Frequency: 32 kHz, 12 MHz, 16 MHz, 24 MHz, 25 MHz, 27 MHz | O | +| **RF** | | | +| FEM-CTRL0 | Front End Module Control, TX-EN | I/O | +| FEM-CTRL1 | Front End Module Control, RX-EN | I/O | +| **SD Card/SDIO/eMMC** | | | +| SDC1-CMD | SDIO Command Output/Response Input | I/O, OD | +| SDC1-CLK | SDIO Clock Output | O | +| SDC1-D0 | SDIO Data Input/ Output 0 | I/O | +| SDC1-D1 | SDIO Data Input/ Output 1 | I/O | +| SDC1-D2 | SDIO Data Input/ Output 2 | I/O | +| SDC1-D3 | SDIO Data Input/ Output 3 | I/O | +| **I2S/PCM** | | | +| I2S0-MCLK | I2S0 Master Clock | O | +| I2S0-LRCK | I2S0/PCM0 Sample Rate Clock/Sync | I/O | +| I2S0-BCLK | I2S0/PCM0 Bit Rate Clock | I/O | +| I2S0-DIN0 | I2S0/PCM0 Serial Data Input 0 | I | +| I2S0-DIN1 | I2S0/PCM0 Serial Data Input 1 | I | +| I2S0-DIN2 | I2S0/PCM0 Serial Data Input 2 | I | +| I2S0-DIN3 | I2S0/PCM0 Serial Data Input 3 | I | +| I2S0-DOUT0 | I2S0/PCM0 Serial Data Output 0 | O | +| I2S0-DOUT1 | I2S0/PCM0 Serial Data Output 1 | O | +| I2S0-DOUT2 | I2S0/PCM0 Serial Data Output 2 | O | +| I2S0-DOUT3 | I2S0/PCM0 Serial Data Output 3 | O | +| GPADC | | | +| GPADC0-0 | General Purpose ADC0 Input 0 | AI | +| GPADC0-2 | General Purpose ADC0 Input 2 | AI | +| GPADC0-3 | General Purpose ADC0 Input 3 | AI | +| **MIPI CSI** | | | +| CSI-SM-HS | CSI Horizontal SYNC | O | +| CSI-SM-VS | CSI Vertical SYNC/Frame SYNC | O | +| **Parallel CSI** | | | +| NCSI-PCLK | Parallel CSI Pixel Clock Input | I | +| NCSI-MCLK | Parallel CSI Master Clock Output | O | +| NCSI-HSYNC | Parallel CSI Horizontal Synchronous Input | I | +| NCSI-VSYNC | Parallel CSI Vertical Synchronous Input | I | +| NCSI-D0 | Parallel CSI Pixel Data 0 | I | +| NCSI-D1 | Parallel CSI Pixel Data 1 | I | +| NCSI-D2 | Parallel CSI Pixel Data 2 | I | +| NCSI-D3 | Parallel CSI Pixel Data 3 | I | +| NCSI-D4 | Parallel CSI Pixel Data 4 | I | +| NCSI-D5 | Parallel CSI Pixel Data 5 | I | +| NCSI-D6 | Parallel CSI Pixel Data 6 | I | +| NCSI-D7 | Parallel CSI Pixel Data 7 | I | +| NCSI-D8 | Parallel CSI Pixel Data 8 | I | +| NCSI-D9 | Parallel CSI Pixel Data 9 | I | +| NCSI-D10 | Parallel CSI Pixel Data 10 | I | +| NCSI-D11 | Parallel CSI Pixel Data 11 | I | +| **LCD** | | | +| LCD-CLK | LCD Clock | O | +| LCD-VSYNC | LCD Vertical Synchronization | O | +| LCD-HSYNC | LCD Horizontal Synchronization | O | +| LCD-DE | LCD Data Enable | O | +| TCON-FSYNC | Frame Synchronization Signal for TCON and Sensor | O | +| TCON-TRIG | Screen Trigger Signal | I | +| LCD-D3 | LCD Data Input/Output 3 | I/O | +| LCD-D4 | LCD Data Input/Output 4 | I/O | +| LCD-D5 | LCD Data Input/Output 5 | I/O | +| LCD-D6 | LCD Data Input/Output 6 | I/O | +| LCD-D7 | LCD Data Input/Output 7 | I/O | +| LCD-D10 | LCD Data Input/Output 10 | I/O | +| LCD-D11 | LCD Data Input/Output 11 | I/O | +| LCD-D12 | LCD Data Input/Output 12 | I/O | +| **Ethernet MAC** | | | +| RMII-TXCK | RMII Transmit Clock | I | +| RMII-RXER | RMII Receive Error | I | +| RMII-CRS-DV | RMII Carrier Sense Receive Data Valid | I | +| RMII-TXEN | RMII Transmit Enable | O | +| RMII-EPHY-25M | EMAC PHY 25 MHz Clock Output | O | +| RMII-MDC | RMII Management Data Clock | O | +| RMII-MDIO | RMII Management Data Input/ Output | I/O | +| RMII-RXD0 | RMII Receive Data 0 | I | +| RMII-RXD1 | RMII Receive Data 1 | I | +| RMII-TXD0 | RMII Transmit Data 0 | O | +| RMII-TXD1 | RMII Transmit Data 1 | O | +| **SPI&SPI DBI** | | | +| SPI1-CS0 | SPI1 Chip Select 0 (Active Low) | I/O | +| SPI1-CS1 | SPI1 Chip Select 1 (Active Low) | I/O | +| SPI1-CLK | SPI1 Clock | I/O | +| SPI1-MOSI | SPI1 Master Data Out, Slave Data In | I/O | +| SPI1-MISO | SPI1 Master Data In, Slave Data Out | I/O | +| SPI1-WP | SPI1 Write Protection (Active Low)/ Serial Data Input and Output for Quad Input or Quad Output | I/O | +| SPI1-HOLD | SPI1 Hold Signal/ Serial Data Input and Output for Quad Input or Quad Output | I/O | +| SPI2-CS0 | SPI2 Chip Select 0 (Active Low) | I/O | +| SPI2-CLK | SPI2 Clock | I/O | +| SPI2-MOSI | SPI2 Master Data Out, Slave Data In | I/O | +| SPI2-MISO | SPI2 Master Data In, Slave Data Out | I/O | +| SPI2-WP | SPI2 Write Protection (Active Low)/ Serial Data Input and Output for Quad Input or Quad Output | I/O | +| SPI2-HOLD | SPI2 Hold Signal/ Serial Data Input and Output for Quad Input or Quad Output | I/O | +| DBI-CSX | Chip Select Signal (Active Low) | I/O | +| DBI-SCLK | Serial Clock Signal | I/O | +| DBI-SDO | Data Output Signal | I/O | +| DBI-SDI | Data Input Signal The data is sampled on the rising edge and the falling edge. | I/O | +| DBI-TE | Tearing Effect Input It is used to capture the external TE signal edge. The rising and falling edge is configurable. | I/O | +| DBI-DCX | DCX pin is the select output signal of data and command. DCX = 0: register command; DCX = 1: data or parameter. | I/O | +| DBI-WRX | When DBI operates in dual data lane format, the RGB666 format 2 can use WRX to transfer data | I/O | +| **UART** | | | +| UART0-RX | UART0 Data Receiver | I | +| UART0-TX | UART0 Data Transmitter | O | +| UART1-CTS | UART1 Clear to Send | I | +| UART1-RTS | UART1 Request to Send | O | +| UART1-RX | UART1 Data Receiver | I | +| UART1-TX | UART1 Data Transmitter | O | +| UART2-CTS | UART2 Clear to Send | I | +| UART2-RTS | UART2 Request to Send | O | +| UART2-RX | UART2 Data Receiver | I | +| UART2-TX | UART2 Data Transmitter | O | +| UART3-RX | UART3 Data Receiver | I | +| UART3-TX | UART3 Data Transmitter | O | +| **PWM** | | | +| PWM0-0 | PWM0 Wave Output /Capture Wave Input 0 | I/O | +| PWM0-1 | PWM0 Wave Output /Capture Wave Input 1 | I/O | +| PWM0-2 | PWM0 Wave Output /Capture Wave Input 2 | I/O | +| PWM0-3 | PWM0 Wave Output /Capture Wave Input 3 | I/O | +| PWM0-4 | PWM0 Wave Output /Capture Wave Input 4 | I/O | +| PWM0-5 | PWM0 Wave Output /Capture Wave Input 5 | I/O | +| PWM0-6 | PWM0 Wave Output /Capture Wave Input 6 | I/O | +| PWM0-7 | PWM0 Wave Output /Capture Wave Input 7 | I/O | +| PWM0-8 | PWM0 Wave Output /Capture Wave Input 8 | I/O | +| PWM0-9 | PWM0 Wave Output /Capture Wave Input 9 | I/O | +| PWM0-10 | PWM0 Wave Output /Capture Wave Input 10 | I/O | +| PWM0-11 | PWM0 Wave Output /Capture Wave Input 11 | I/O | +| **TWI** | | | +| TWI0-SCK | TWI0 Serial Clock Signal | I/O | +| TWI0-SDA | TWI0 Serial Data Signal | I/O | +| TWI1-SCK | TWI1 Serial Clock Signal | I/O | +| TWI1-SDA | TWI1 Serial Data Signal | I/O | +| TWI2-SCK | TWI2 Serial Clock Signal | I/O | +| TWI2-SDA | TWI2 Serial Data Signal | I/O | +| **JTAG** | | | +| R-JTAG0-TMS | CPU0 JTAG Mode Select | I/O | +| R-JTAG0-TCK | CPU0 JTAG Clock Signal | I | +| R-JTAG1-TMS | CPU1 JTAG Mode Select | I/O | +| R-JTAG1-TCK | CPU1 JTAG Clock Signal | I | +| **Interrupt** | | | +| PD-EINT1 | Port D Interrupt | I | +| PD-EINT2 | Port D Interrupt | I | +| PD-EINT3 | Port D Interrupt | I | +| PD-EINT4 | Port D Interrupt | I | +| PD-EINT5 | Port D Interrupt | I | +| PD-EINT6 | Port D Interrupt | I | +| PD-EINT7 | Port D Interrupt | I | +| PD-EINT8 | Port D Interrupt | I | +| PD-EINT9 | Port D Interrupt | I | +| PD-EINT10 | Port D Interrupt | I | +| PD-EINT11 | Port D Interrupt | I | +| PD-EINT12 | Port D Interrupt | I | +| PD-EINT13 | Port D Interrupt | I | +| PD-EINT14 | Port D Interrupt | I | +| PD-EINT15 | Port D Interrupt | I | +| PD-EINT16 | Port D Interrupt | I | +| PD-EINT17 | Port D Interrupt | I | +| PD-EINT18 | Port D Interrupt | I | +| PD-EINT19 | Port D Interrupt | I | +| PD-EINT22 | Port D Interrupt | I | +| PD-EINT23 | Port D Interrupt | I | +| PL-EINT2 | Port L Interrupt | I | +| PL-EINT3 | Port L Interrupt | I | +| PL-EINT4 | Port L Interrupt | I | +| PL-EINT5 | Port L Interrupt | I | +| PL-EINT6 | Port L Interrupt | I | +| PL-EINT7 | Port L Interrupt | I | + +## 核心板使用入门 + +### 串口调试 + +核心板支持接出两路调试串口,分别为 RISC-V CPU Linux 核心串口 UART0,RISC-V MCU RTOS 核心串口 UART3,波特率均为 115200 + +危险 + +SDK 1.2 默认波特率修改为 `1500000`,请使用波特率 `1500000` + +提示 + +SDK 1.3 支持切换波特率,在 `lunch` 的时候可以选择 `115200` 或者 `1500000` + +核心板调试串口有两种接入方式: + +- 使用 USB 拆分器接入串口:仅接出常用的 CPU 核心串口 UART0 +- 使用 GPIO 接入串口:支持接出 CPU 核心串口 UART0 和 MCU 核心串口 UART3 + +**使用 USB 拆分器接入串口** + +核心板设计之时复用了 TypeC 中的 SBU 信号线用于传输串口信号,这个串口是 UART0,与 PL4,PL5 并联。接入方法如下: + +![image-20250424091735539](https://docs.aw-ol.com/assets/images/image-20250424091735539-5205349f7060993af0ea44c34fb32b56.png) + +**使用 GPIO 接入串口** + +核心板串口位于 PL 口,如下图所示,需要焊接或者排针接出。其中绿色的是 RISC-V MCU 核心串口,蓝色的是 RISC-V CPU 串口。 + +![image-20250423232024357](https://docs.aw-ol.com/assets/images/image-20250423232024357-061a79019f59a1052d9ebcf13db225d0.png) + +串口线打开电脑的设备管理器,确认串口号,例如这里是 COM5 + +![下载](data:image/png;base64,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) + +硬件连接完成后,使用串口终端访问,波特率 `115200` 。例如这里使用的 `PuTTY` + +危险 + +SDK 1.2 默认波特率修改为 `1500000`,请使用波特率 `1500000` + +提示 + +SDK 1.3 支持切换波特率,在 `lunch` 的时候可以选择 `115200` 或者 `1500000` + +![image-20241119154137938](https://docs.aw-ol.com/assets/images/image-20241119154137938-17415738627349-7f2d2a9d50c474e8872d77f0d9d4f7e2-7f2d2a9d50c474e8872d77f0d9d4f7e2.png) + +如果是刷入固件的核心板,上电后即可看到启动日志与控制台 + +![image-20241119154325232](https://docs.aw-ol.com/assets/images/image-20241119154325232-17415738627348-321630832a633e86294eab953bb542a6-321630832a633e86294eab953bb542a6.png) + +### ADB 调试 + +备注 + +如果烧录的是 UVC 固件,UVC 会自动切换 USB 枚举为 UVC 设备,此时无法使用 ADB 调试。 + +在电脑上安装 ADB,打开 CMD 使用 `adb shell` 进入终端。 + +(1) 在 [全志开发者社区-资料下载 专区 ](https://www.aw-ol.com/downloads?cat=5)下载 ADB 工具 `ADB(tab自动补全版)` (2)下载后解压放到本地磁盘下(例如D盘的adb文件夹里) + +![adb_ins_1](https://docs.aw-ol.com/assets/images/adb_ins_1-17415738627347-57ada7e769a9aaade7376a09459bb9cf-57ada7e769a9aaade7376a09459bb9cf.png) + +(3) 右键 ”此电脑“,属性,找到高级系统设置,点击环境变量,xxx用户的环境变量,Path,新增一个环境变量。 + +![adb_ins_2](https://docs.aw-ol.com/assets/images/adb_ins_2-174157386273410-df9204a20d62347f8950c36e964fcbc1-df9204a20d62347f8950c36e964fcbc1.png) + +(4) 打开命令提示符,输入 `adb shell` + +![image-20241119154459505](https://docs.aw-ol.com/assets/images/image-20241119154459505-174157386273411-de1e746e8096e7634408c01423f9df38-de1e746e8096e7634408c01423f9df38.png) + +ADB 也可以作为文件传输使用,例如: + +- 将 sample.mp4 上传到核心板 /mnt/UDISK 目录内 + +```text +C:\System> adb push sample.mp4 /mnt/UDISK +``` + + + +- 将 /mnt/UDISK/sample.mp4 下拉到当前目录内 + +```text +C:\System> adb pull /mnt/UDISK/sample.mp4 +``` + + + +### 重启 + +在核心板终端 Linux 命令行中输入 `reboot` 即可重启 + +![image-20241119154725553](https://docs.aw-ol.com/assets/images/image-20241119154725553-174157386273413-ef4977152178b27e2713e46ceeac2e5f-ef4977152178b27e2713e46ceeac2e5f.png) + +在核心板终端 U-Boot 命令行中输入 `reset` 即可重启 + +![image-20241119154815320](https://docs.aw-ol.com/assets/images/image-20241119154815320-174157386273412-871cb7353e5f9bde2d4fbabce67aa86d-871cb7353e5f9bde2d4fbabce67aa86d.png) + +### 进入烧录模式 + +有多种方式可以让核心板进入烧录模式。 + +**按键进入烧录模式** + +在核心板找到按键 `FEL`,断开USB,电源, + +(1)按住 `FEL` 按键 + +(2)插入 USB 线 + +(3)等待电脑连接成功,松开 `FEL` 按键即可进入烧录模式 + +![image-20250423232255073](https://docs.aw-ol.com/assets/images/image-20250423232255073-8681aaab953c4865dc250624e4bd77e9.png) + +**命令行进入烧录模式** + +在 Linux 命令行中输入 `reboot efex` 即可重启进入烧录模式 + +```text +reboot efex +``` + + + +在 U-Boot 命令行中输入 `efex` 即可重启进入烧录模式 + +```text +=> efex +``` + + + +**破坏启动介质进入烧录模式(SPI NOR)** + +在 Linux 命令行中输入 `echo 000000 > /dev/mtd0`,破坏启动引导介质,重启后即可进入烧录模式 + +### WI-FI + +**Wi-Fi 连接网络** + +这里首先介绍如何使用 `wifi` 扫描网络: + +(1)设置 `Wi-Fi` 为 `STATION` 模式 + +```text +wifi -o sta +``` + + + +(2)扫描当前网络环境的 Wi-Fi 站点 + +```text +wifi -s +``` + + + +(3)连接Wi-Fi(SSID:awol,密码 1234567890) + +```text +wifi -c awol 1234567890 +``` + + + +(4)连接网络后输入 `ifconfig` 即可查看当前 ip 地址 + +![image-20241119161156996](https://docs.aw-ol.com/assets/images/image-20241119161156996-174157386273518-33b4484eedea2862098d9faf9e4b6699-33b4484eedea2862098d9faf9e4b6699.png) + +可以使用 `ping` 命令测试 网络连接 + +```text +ping www.baidu.com +``` + + + +它会输出以下内容 + +```text +PING 202.108.22.5 (202.108.22.5): 56 data bytes +64 bytes from 202.108.22.5: seq=0 ttl=49 time=48.734 ms +64 bytes from 202.108.22.5: seq=1 ttl=49 time=48.624 ms +64 bytes from 202.108.22.5: seq=2 ttl=49 time=58.370 ms +64 bytes from 202.108.22.5: seq=3 ttl=49 time=69.119 ms +64 bytes from 202.108.22.5: seq=4 ttl=49 time=49.635 ms +``` + + + +(5)断开Wi-Fi + +```text +wifi -d +``` + + + +**Wi-Fi 建立 AP** + +(1)创建热点 (SSID:v821,密码 12345678) + +```text +wifi -o ap v821 12345678 +``` + + + +![image-20241119161500112](https://docs.aw-ol.com/assets/images/image-20241119161500112-174157386273519-aa6535be950b73342a394f15c349ea77-aa6535be950b73342a394f15c349ea77.png) + +(2)然后就可以扫描到 Wi-Fi 了,输入密码 12345678 进行连接 + +![image-20241119161644816](https://docs.aw-ol.com/assets/images/image-20241119161644816-174157386273520-cf83500b0ddb243e22941c1f2e28f28c-cf83500b0ddb243e22941c1f2e28f28c.png) + +### 音频 MIC + +**查看音频设备** + +使用命令 `amixer` 可以列出全部音频设备 + +```text +amixer +Simple mixer control 'ADC',0 + Capabilities: volume volume-joined + Playback channels: Mono + Capture channels: Mono + Limits: 0 - 255 + Mono: 160 [63%] [0.75dB] +Simple mixer control 'ADC DRC0 Mode',0 + Capabilities: enum + Items: 'Off' 'On' + Item0: 'Off' +Simple mixer control 'ADC DRC1 Mode',0 + Capabilities: enum + Items: 'Off' 'On' + Item0: 'Off' +Simple mixer control 'ADC HPF0 Mode',0 + Capabilities: enum + Items: 'Off' 'On' + Item0: 'Off' +Simple mixer control 'ADC HPF1 Mode',0 + Capabilities: enum + Items: 'Off' 'On' + Item0: 'Off' +Simple mixer control 'ADDA Loop Mode',0 + Capabilities: enum + Items: 'Off' 'DAC-to-ADC' + Item0: 'Off' +Simple mixer control 'DAC',0 + Capabilities: volume volume-joined + Playback channels: Mono + Capture channels: Mono + Limits: 0 - 63 + Mono: 63 [100%] [-1.16dB] +Simple mixer control 'DAC DRC Mode',0 + Capabilities: enum + Items: 'Off' 'On' + Item0: 'Off' +Simple mixer control 'DAC HPF Mode',0 + Capabilities: enum + Items: 'Off' 'On' + Item0: 'Off' +Simple mixer control 'DACL',0 + Capabilities: volume volume-joined + Playback channels: Mono + Capture channels: Mono + Limits: 0 - 255 + Mono: 160 [63%] [0.75dB] +Simple mixer control 'LINEOUT',0 + Capabilities: pswitch pswitch-joined + Playback channels: Mono + Mono: Playback [off] +Simple mixer control 'LINEOUT Gain',0 + Capabilities: volume volume-joined + Playback channels: Mono + Capture channels: Mono + Limits: 0 - 31 + Mono: 31 [100%] +Simple mixer control 'LINEOUT Output Select',0 + Capabilities: enum + Items: 'DIFFER' 'SINGLE' + Item0: 'SINGLE' +Simple mixer control 'MIC',0 + Capabilities: pswitch pswitch-joined + Playback channels: Mono + Mono: Playback [off] +Simple mixer control 'MIC Gain',0 + Capabilities: volume volume-joined + Playback channels: Mono + Capture channels: Mono + Limits: 0 - 31 + Mono: 31 [100%] +Simple mixer control 'SPK',0 + Capabilities: pswitch pswitch-joined + Playback channels: Mono + Mono: Playback [off] +Simple mixer control 'rx sync mode',0 + Capabilities: enum + Items: 'Off' 'On' + Item0: 'Off' +Simple mixer control 'tx hub mode',0 + Capabilities: enum + Items: 'Off' 'On' + Item0: 'Off' +``` + + + +**查看录音设备** + +可以使用 `arecord -l` 命令查看核心板提供的录音设备。 + +```text +arecord -l +``` + + + +![image-20241119162200635](https://docs.aw-ol.com/assets/images/image-20241119162200635-174157386274222-eaa478f0eaf5e1350fae8dc67c140a8c-eaa478f0eaf5e1350fae8dc67c140a8c.png) + +**麦克风录音** + +V821 核心板板载一个麦克风,在录音之前,首先需要打开音频通路,配置内部 MIC0录制音频(需要 SDK 配置 `alsa-utils` 软件包才能直线 `amixer` 等命令)。 + +提示 + +配置软件包方法:`make menuconfig`,勾选以下软件包 + +```text +Allwinner ---> + Audio ---> + <*> AudioSystem.......................................... AudioSystem library + <*> aactd............................ Allwinner Audio Calibration Tool Daemon + -*- aactd-lib....................... Allwinner Audio Calibration Tool Library + <*> alsa-plugins-aw.............................. ALSA plugins from Allwinner +Sound ---> + <*> alsa-utils............ ALSA (Advanced Linux Sound Architecture) utilities +``` + + + +(1)打开 MIC 通路 + +```text +amixer -Dhw:audiocodec cset name="MIC Switch" 1 +``` + + + +输出如下,表示音频通路已开启 + +```text +numid=16,iface=MIXER,name='MIC Switch' + ; type=BOOLEAN,access=rw------,values=1 + : values=on +``` + + + +(2)设置 MIC 音量 + +```text +amixer -Dhw:audiocodec cset name="MIC Gain" 10 +``` + + + +输出如下,表示设置成功 + +```text +numid=15,iface=MIXER,name='MIC Gain' + ; type=INTEGER,access=rw---R--,values=1,min=0,max=31,step=0 + : values=30 + | dBscale-min=0.00dB,step=1.00dB,mute=0 +``` + + + +使用 `arecord -D hw:audiocodec -f S16_LE -t wav -r 16000 -d 3 t.wav` 命令,使用板载的麦克风进行录音。 + +```text +arecord -D hw:audiocodec -f S16_LE -t wav -r 16000 -d 3 t.wav +``` + + + +可以看到输出的 `t.wav` 文件 + +## 配套模块 + +### 摄像头模块 + +核心板套件配备了摄像头模块与配套的排线,请注意排线需要同向排线。 + +![image-20250423232434784](https://docs.aw-ol.com/assets/images/image-20250423232434784-a70c7e13e60b1a580ac2d8ebf1748eef.png) + +摄像头模组排线的 1 脚如图所示,蓝色塑料面朝上插入排线 + +![image-20250423232520890](https://docs.aw-ol.com/assets/images/image-20250423232520890-5b18ab14574eeb2e9ca25692deecc130.png) + +核心板摄像头接口的 1 脚 + +![image-20250423232559172](https://docs.aw-ol.com/assets/images/image-20250423232559172-36eee0bb40375875ba7d0f84eb2aded7.png) + +在接入时请确保 1 脚与 1 脚对应,否则会出现摄像头烧毁的风险。 + +- 金属触点这一面面向 Avaota F1 文字 + +![image-20250423232634803](https://docs.aw-ol.com/assets/images/image-20250423232634803-91194f07a93fcf3be593b263cc92b8f6.png) + +- 蓝色塑料这一面面向核心板内部 + +![image-20250423232654361](https://docs.aw-ol.com/assets/images/image-20250423232654361-f33d6b3a299ccf43fde6338b50547e91.png) + +摄像头具体使用可以参考 【[SDK 功能演示体验](https://docs.aw-ol.com/docs/soc/v821/software/demo)】,具体演示如何编译运行一个 RTSP 测试 DEMO + +# SDK 功能演示体验 + +本文将以 V821 PERF2 板为示例,演示搭建 Smart IPC 场景功能,包括: + +- RTSP H264 1280*720@20fps 预览 +- 1280*720@20fps H264 编码视频分段滚动录像 +- 定时拍照 + +需要准备如下物品: + +- V821 PERF2 开发板 +- 单目GC1084模组 +- 串口线(用于调试) +- USB线(用于下载烧录,传输文件) +- SD 卡(用于保存码流) +- WIFI天线(用于无线传输) +- 路由器(用于数据交换) +- 手机或笔记本电脑(用于播放码流) + +## 硬件连接 + +准备好摄像头,排线,V821 PERF2 开发板,排线需要同向排线。 + +![image-20241118170410614](https://docs.aw-ol.com/assets/images/image-20241118170410614-a6165dd5603b19d8c8913b586e9886fe.png) + +将排线的蓝面朝上,接入摄像头模块 + +![image-20241118170507963](https://docs.aw-ol.com/assets/images/image-20241118170507963-e7588158be4bc72d795335e2d67dbc10.png) + +排线另外一边,触点面朝向芯片,接入 PERF2 开发板 + +![image-20241118170645214](https://docs.aw-ol.com/assets/images/image-20241118170645214-db6041f3a7ea7b1e462cb0cf00a4f612.png) + +摄像头安装完成 + +![image-20241118170706269](https://docs.aw-ol.com/assets/images/image-20241118170706269-e05bb44f37c0e2ca9f2c1cb220f71577.png) + +安装天线,将天线接入天线插口 + +![image-20241118170739004](https://docs.aw-ol.com/assets/images/image-20241118170739004-53a00c2aadba1e2711da78779c342361.png) + +插入调试串口 + +![image-20241118171820917](https://docs.aw-ol.com/assets/images/image-20241118171820917-21f5dab91dd2345d218ecfc086696193.png) + +## 准备固件 + +> 如果已有固件,可以跳过本章节,从烧录固件开始看 + +### 配置方案 + +首先输入以下命令,配置SDK开发环境 + +```text +source build/envsetup.sh +``` + + + +然后输入 `lunch` 命令加载方案 + +```text +lunch +``` + + + +这里选择 v821-perf2-tina 方案,输入 4,按回车 + +![image-20241118171552061](https://docs.aw-ol.com/assets/images/image-20241118171552061-ef0f66f13c01cb3cb0dc7712a0ed19f5.png) + +### 配置测试 Sample + +``` + +``` + + + +输入以下命令,进入配置界面 + +```text +make menuconfig +``` + + + +![image-20241118163536930](data:image/png;base64,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) + +配置页面如下 + +![image-20241118163553180](https://docs.aw-ol.com/assets/images/image-20241118163553180-9cadc1a9a50e50299556f7c271b6219a.png) + +下拉找到 Allwinner 按回车进入 + +![image-20241118163621775](https://docs.aw-ol.com/assets/images/image-20241118163621775-1a32eed4e8c7dfa7880e40fe40ef90c0.png) + +在最下面找到 eyesee-mpp,按回车进入 + +![image-20241118163640800](https://docs.aw-ol.com/assets/images/image-20241118163640800-77674f69b0cca4dff3260bf67feedb43.png) + +找到 `select mpp sample`,按空格选中(先选择`eyesee-mpp-middleware-demo config`就出来`select mpp sample`) + +![image-20241118164505217](https://docs.aw-ol.com/assets/images/image-20241118164505217-edaec93b9e9c1564f112df8b64f7d208.png) + +找到 `mpp sample smartIPC_demo`,按空格选中 + +![image-20241118164525565](https://docs.aw-ol.com/assets/images/image-20241118164525565-56ac759a6aba1be36cc4c539d434289a.png) + +提示 + +如果找不到 `mpp sample smartIPC_demo` 选项,先去检查一下依赖软件包 `rgb_ctrl` 有没有打开,如果没有打开需要开一下 + +![image-20250526103537915](https://docs.aw-ol.com/assets/images/image-20250526103537915-3adbff6c2fbf968fb4a6b55841b75762.png) + +使用方向键选择 `Save` + +![image-20241118164558256](https://docs.aw-ol.com/assets/images/image-20241118164558256-de39b191f0dfb30f7d7147d3cd5601f9.png) + +选择 `OK` + +![image-20241118164611317](https://docs.aw-ol.com/assets/images/image-20241118164611317-a49e248abc247925692ce07d20cad376.png) + +选择 EXIT + +![image-20241118164617725](data:image/png;base64,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) + +使用方向键选择 Exit + +![image-20241118164655148](https://docs.aw-ol.com/assets/images/image-20241118164655148-5801275126fa3ee1e7e0873dca1b651a.png) + +继续退出 + +![image-20241118164710249](https://docs.aw-ol.com/assets/images/image-20241118164710249-a9ae787b3a95358e1ff8ade6aa491ae0.png) + +继续退出 + +![image-20241118164732177](https://docs.aw-ol.com/assets/images/image-20241118164732177-e3fe518332cda6f1ea8a271330f06dcf.png) + +### 编译 SDK + +回到控制台,输入 `mp -j4` 以 4 线程并行方式编译 + +![image-20241118164823029](data:image/png;base64,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) + +等待 SDK 编译完成,会在 `out` 目录下生成固件 + +![image-20241118171426560](https://docs.aw-ol.com/assets/images/image-20241118171426560-bb7e3e7bd4a11d4e6a524e8d65be6fc3.png) + +将固件拷贝出来,准备烧录 + +![image-20241118171446163](https://docs.aw-ol.com/assets/images/image-20241118171446163-18105af7e30e1f3d9cb04fca6ce0b7e7.png) + +## 烧写固件 + +打开 PhoenixSuit,选择一键刷机,点击浏览,打开刚才生成的固件 + +![image-20241118165428364](https://docs.aw-ol.com/assets/images/image-20241118165428364-3f46c09c8606d70d0d720523814368b5.png) + +选择全盘擦除升级 + +![image-20241118171506827](https://docs.aw-ol.com/assets/images/image-20241118171506827-75671bafc478a80b4ccad241f044f9d8.png) + +按住 PERF2 开发板上的FEL按键,插入USB线 + +![image-20241118165707091](https://docs.aw-ol.com/assets/images/image-20241118165707091-889836e7f6770e610d534a5dce06b91d.png) + +烧录工具出现提示,选择是 + +![image-20241118171028491](https://docs.aw-ol.com/assets/images/image-20241118171028491-227ca42688fbfef63383bbf12d8ebca6.png) + +烧录中,请耐心等待 + +![image-20241118171611288](https://docs.aw-ol.com/assets/images/image-20241118171611288-e7aa37779a26f01641b95622b75e7604.png) + +烧写结束,系统自动启动 + +![image-20241118171845874](https://docs.aw-ol.com/assets/images/image-20241118171845874-cdde96393f93652b16d72ec3eae40ac4.png) + +## 配置 Sample + +前往 `platform/allwinner/eyesee-mpp/middleware/sun300iw1/sample/bin` 找到刚才编译出来的Sample + +![image-20241118172041858](https://docs.aw-ol.com/assets/images/image-20241118172041858-b857ea2878462d08686cb5f604b04818.png) + +编辑 `sample_smartIPC_demo.conf` 修改配置文件,需要修改的项目如下(可以在附录获取完整版配置文件): + +```text +stream_buf_size = -1 # 使用码流大小推流 +main_rtsp_id = 0 # 启用 RTSP +main_src_frame_rate = 20 # 帧率设置 20 帧 +main_encode_frame_rate = 20 # 配置编码器20帧 +main_2nd_enable = 1 # 开启子码流 +main_2nd_src_frame_rate = 20 # 子码流帧率20帧 +main_2nd_encode_frame_rate = 20 # 子码流编码帧率20帧 +main_2nd_take_picture = 1 # 子码流开启拍照功能 +``` + + + +将SD卡格式化为 FAT32 格式 + +![image-20241118172735225](https://docs.aw-ol.com/assets/images/image-20241118172735225-49d35a51ef50d078d4bf44a3ff7ee626.png) + +将上面编译出来的 sample 和 配置文件复制到 SD 卡里 + +![image-20241118172836521](https://docs.aw-ol.com/assets/images/image-20241118172836521-c9e95087bf001cf956c2cac829631225.png) + +## 测试运行 Sample + +### 配置无线网络 + +使用命令扫描无线网络 + +```text +wifi -s +``` + + + +![image-20241118173306056](https://docs.aw-ol.com/assets/images/image-20241118173306056-e1f42389a48e72eeabb0d6264d893f2c.png) + +使用命令连接无线网络,连接成功后使用 `ifconfig` 命令查看连接情况与 IP 地址 + +```text +wifi -c <密码> +ifconfig wlan0 +``` + + + +![image-20241118173535716](https://docs.aw-ol.com/assets/images/image-20241118173535716-6162c5421a20b4742ba9457c1acca69c.png) + +### 挂载 SD 卡 + +插入 SD 卡后,可以在日志里看到新生成的卡设备 + +![image-20241118173626105](https://docs.aw-ol.com/assets/images/image-20241118173626105-80ffc62bdbc50f6b002be8dac236c9ac.png) + +使用命令挂载 SD 卡 + +```text +mount /dev/mmcblk0p1 /mnt/extsd +``` + + + +![image-20241118174051714](data:image/png;base64,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) + +### 运行 Sample + +前往SD卡的挂载目录,查看文件是否存在 + +```text +cd /mnt/extsd +``` + + + +![image-20241118174134210](data:image/png;base64,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) + +使用命令,运行 sample + +```text +./sample_smartIPC_demo -path sample_smartIPC_demo.conf & +``` + + + +![image-20241118174552557](https://docs.aw-ol.com/assets/images/image-20241118174552557-fdb86700cff5b3b3e3486d5917a5b801.png) + +在平板上打开 VLC 播放器。配置日志显示的地址 + +```text +rtsp://192.168.51.101:8554/ch0 +``` + + + +![image-20241118175852117](https://docs.aw-ol.com/assets/images/image-20241118175852117-b66b359880fc1f9f4ce8ca383de062a0.png) + +即可打开串流视频 + +![image-20241118180020486](https://docs.aw-ol.com/assets/images/image-20241118180020486-2b290d118813144de4ad1f178e907aef.png) + +SD 卡插上电脑也可以看到拍到的图片和码流 + +![image-20241118180113645](https://docs.aw-ol.com/assets/images/image-20241118180113645-3c05a58ef43b1c91b42577e4360ef6ce.png) + +## 附录:Sample 配置 + +```conf +########### paramter (ref to tulip_cedarx.conf)############ +[parameter] + +rtsp_net_type = 3 #RTSP Network type, 0: "lo", 1: "eth0", 2: "br0", 3: "wlan0" +ve_rec_ref_buf_reduce_enable = 1 #0:disable buf reduce, 1:enable buf reduce +stream_buf_size = -1 +product_mode = 0 #0:static ipc, 1:moving ipc, 2: doorbell, 3:cdr, 4:sdv, 5:projection, 6:UAV(Unmanned Aerial Vehicle) +vbr_opt_en = 1 #0: old vbr bitrate control, 1:new vbr bitrate control +vbr_opt_rc_priority = 0 #only for vbr opt, balance bitrate and quality, 0:quality priority, 1:bitrate priority, 2:avg bitrate first, 3:instantaneous bitrate first +rc_mode = 1 #for H264, 0:CBR 1:VBR 2:FIXQP(only for debug) +init_qp = 37 +min_i_qp = 25 +max_i_qp = 45 +min_p_qp = 25 +max_p_qp = 45 +moving_th = 20 +mb_qp_limit_en = 1 +quality = 1 +p_bits_coef = 10 +i_bits_coef = 10 +isp_ve_linkage_enable = 1 +region_link_enable = 1 +region_link_tex_detect_enable = 1 +region_link_motion_detect_enable = 1 +camera_adaptive_moving_and_static_enable = 1 +ve_lens_moving_max_qp = 40 +wb_yuv_enable = 0 +wb_yuv_buf_num = 3 +wb_yuv_scaler_ratio = 0 #0:no scaler, 1: 1/8, 2: 1/2, 3: 1/4 +wb_yuv_start_index = 0 +wb_yuv_total_cnt = 100 +wb_yuv_stream_channel = 0 #venc channel id +wb_yuv_file_path = "/mnt/extsd/wb_yuv.yuv" +vi_timeout_reset_disable = 0 #0:enable(default), >0:disable vi timeout reset for debug. +test_trigger_vi_timeout = 0 #0:disable, >0:enable and means time interval, unit is ms. +encpp_sharp_debug_disable = 0 +tdm_speed_down_enable = 0 +ve_2dnr_disable = 0 +ve_3dnr_disable = 0 +test_duration = 0 #unit:s, 0:Infinite duration. + +ir_cut_switch_test_enable = 0 +ir_cut_switch_interval = 10 #unit:s +ir_cut_switch_isp = 0 +ir_cut_switch_ir_bin_path = "/mnt/extsd/ir" +ir_cut_switch_rbg_bin_path = "/mnt/extsd/rgb" + +audio_test_enable = 0 +capture_en = 1 +capture_sample_rate = 16000 +capture_bit_witdh = 16 +capture_channel_cnt = 1 +capture_ans_en = 1 +capture_agc_en = 1 +capture_aec_en = 1 +capture_save_file = "/mnt/extsd/capture_" +capture_save_file_max_cnt = 10 +capture_save_file_duration = 600 +playback_en = 1 +playback_volume = 80 +playback_file = "/mnt/extsd/test.wav" + +motionAlarm_on = 0 +motionAlarm_result_print_interval = 50 #fps +motionAlarm_sensitivity = 60 #[20,40,60,80,100] +motionAlarm_support_zone = 1 +motionAlarm_left_up_x = 0 +motionAlarm_left_up_y = 0 +motionAlarm_left_bottom_x = 0 +motionAlarm_left_bottom_y = 10000 +motionAlarm_right_bottom_x = 10000 +motionAlarm_right_bottom_y = 10000 +motionAlarm_right_up_x = 10000 +motionAlarm_right_up_y = 0 +motionAlarm_useDefaultCfgEnable = 1 +motionAlarm_HorizontalRegionNum = 15 +motionAlarm_VerticalRegionNum = 8 +motionAlarm_Threshold_High = 2 +motionAlarm_Threshold_MediumHigh = 3 +motionAlarm_Threshold_Default = 5 +motionAlarm_Threshold_MediumLow = 10 +motionAlarm_Threshold_Low = 36 + +main_enable = 1 #0:disable main stream, 1:enable main stream +main_rtsp_id = 0 +main_isp = 0 +main_isp_d3d_lbc_ratio = 0 #[100,400], 0:not set but use default, 100:lossless, 125:1.25x, 150:1.5x(default), 400:4x +main_vipp = 0 +main_src_width = 1280 +main_src_height = 720 +main_pixel_format = "aw_lbc_2_5x" #nv21,nv12,yu12,yv12;aw_lbc_2_5x,aw_lbc_2_0x,aw_lbc_1_5x,aw_lbc_1_0x +main_wdr_enable = 0 +main_vi_buf_num = 3 +main_src_frame_rate = 20 +main_vi_stitch_mode = 0 # 0: DMA_STITCH_NONE, 1: DMA_STITCH_2IN1_LINNER, 2: DMA_STITCH_HORIZONTAL, 3: DMA_STITCH_VERTICAL +main_viChn = 0 +main_venc_chn = 0 +main_encode_type = "H.264" +main_encode_width = 1280 +main_encode_height = 720 +main_encode_frame_rate = 20 +main_encode_bitrate = 1048576 #5M:5242880, 2.5M:2621440, 2M:2097152, 1.5M:1572864, 1M:1048576, 0.5M:524288, 0.25M:262144 +main_online_en = 0 +main_online_share_buf_num = 2 +main_encpp_enable = 1 +main_ve_ref_frame_lbc_mode = 0 #0:default(1.5x), 1:1.5x, 2:2.0x, 3:2.5x, 4:no lossy +main_key_frame_interval = 30 +main_file_path = "/mnt/extsd/mainStream" #if no path is specified, it will not be saved. +main_save_one_file_duration = 60 #unit:s, 0:Infinite duration. +main_save_max_file_cnt = 10 +main_draw_osd_text = "main stream" + +main_isp_test_enable = 0 +main_isp_test_interval_ms = 2000 +main_detect_mipi_desk_en = 0 +main_detect_mipi_interv_ms = 1000 +main_detect_mipi_channel = 0 # MIPI0/MIPIA: 0, MIPI1/MIPIB: 1 + +main_venc_recreate_enable = 0 +main_venc_recreate_loop_cnt = -1 # loop count, -1:infinite +main_venc_recreate_interval = 10 #unit:s +main_venc_recreate_encoder = "H.264" +main_venc_recreate_framerate = 15 +main_venc_recreate_bitrate = 1048576 +main_venc_recreate_dst_width = 1280 +main_venc_recreate_dst_height = 720 +main_venc_recreate_key_frame_interval = 30 + +main_isp_tdm_raw_process_type = -1 #-1:disable, 0:dump 8bit, 1:dump 10bit, 2:dump 8bit for tools, 3:dump 10bit for tools, 4:send 8bit, 5:send 10bit +main_isp_tdm_raw_width = 1280 +main_isp_tdm_raw_height = 720 +main_isp_tdm_raw_rxbuf_num = 5 +main_isp_tdm_raw_process_frame_cnt_min = 0 +main_isp_tdm_raw_process_frame_cnt_max = 5 +main_isp_tdm_raw_file_path = "/mnt/extsd/tdm_raw.bin" + +main_offline_raw_simulate_type = -1 #-1:disable, 0:after reaching the end, start over from the beginning, 1: after reaching the end, read backwards. +main_offline_raw_type = 43 #39:BGGR8, 40:GBRG8, 41:GRBG8, 42:RGGB8, 43:BGGR10, 44:GBRG10, 45:GRBG10, 46:RGGB10, 47:BGGR12, 48:GBRG12, 49:GRBG12, 50:RGGB12 +main_offline_raw_simulate_cnt_start = 0 +main_offline_raw_simulate_cnt_end = 19 +main_offline_raw_file_path = "/mnt/extsd/test.bin" + +main_2nd_enable = 1 +main_2nd_vipp = 4 +main_2nd_src_width = 640 +main_2nd_src_height = 480 +main_2nd_pixel_format = "nv21" +main_2nd_vi_buf_num = 3 +main_2nd_src_frame_rate = 20 +main_2nd_vi_stitch_mode = 0 # 0: DMA_STITCH_NONE, 1: DMA_STITCH_2IN1_LINNER, 2: DMA_STITCH_HORIZONTAL, 3: DMA_STITCH_VERTICAL +main_2nd_viChn = 0 +main_2nd_venc_chn = 2 +main_2nd_encode_type = "H.264" +main_2nd_encode_width = 640 +main_2nd_encode_height = 480 +main_2nd_encode_frame_rate = 20 +main_2nd_encode_bitrate = 262144 +main_2nd_online_en = 0 +main_2nd_online_share_buf_num = 2 +main_2nd_encpp_enable = 1 +main_2nd_ve_ref_frame_lbc_mode = 0 +main_2nd_key_frame_interval = 30 +main_2nd_file_path = #"/mnt/extsd/main2ndStream" +main_2nd_save_one_file_duration = 60 +main_2nd_save_max_file_cnt = 10 + +main_2nd_take_picture = 1 +main_2nd_take_picture_viChn = 1 +main_2nd_take_picture_venc_chn = 8 +main_2nd_take_picture_interval = 10 #unit:s +main_2nd_take_picture_file = "/mnt/extsd/main_2nd_pic" +main_2nd_take_picture_file_cnt = 10 +main_2nd_take_picture_only_capture_yuv = 0 + +main_2nd_pdet_enable = 0 +main_2nd_pdet_viChn = 2 +main_2nd_pdet_input_width = 320 +main_2nd_pdet_input_height = 192 +main_2nd_pdet_input_channel = 3 +main_2nd_pdet_conf_thres = 0.3 +main_2nd_pdet_run_interval = 30 #unit:fps, default: framerate*2 + +sub_enable = 0 #0:disable sub stream, 1:enable sub stream +sub_rtsp_id = -1 #-1:disable sub rtsp +sub_isp = 1 +sub_isp_d3d_lbc_ratio = 0 #[100,400], 0:not set but use default, 100:lossless, 125:1.25x, 150:1.5x(default), 400:4x +sub_vipp = 1 +sub_src_width = 1280 +sub_src_height = 720 +sub_pixel_format = "aw_lbc_2_5x" #nv21,nv12,yu12,yv12;aw_lbc_2_5x,aw_lbc_2_0x,aw_lbc_1_5x,aw_lbc_1_0x +sub_wdr_enable = 0 +sub_vi_buf_num = 3 +sub_src_frame_rate = 15 #fps +sub_viChn = 0 +sub_venc_chn = 1 +sub_encode_type = "H.264" +sub_encode_width = 1280 #1280x720->720p, 1920x1080->1080p, 2304x1296->3M, 2560×1440->2k, 3840x2160->4k, 7680x4320->8k +sub_encode_height = 720 +sub_encode_frame_rate = 15 #fps +sub_encode_bitrate = 1048576 #5M:5242880, 2.5M:2621440, 2M:2097152, 1.5M:1572864, 1M:1048576, 0.5M:524288, 0.25M:262144 +sub_online_en = 0 +sub_online_share_buf_num = 2 +sub_encpp_enable = 1 +sub_ve_ref_frame_lbc_mode = 0 #0:default(1.5x), 1:1.5x, 2:2.0x, 3:2.5x, 4:no lossy +sub_key_frame_interval = 30 +sub_file_path = "/mnt/extsd/subStream" #if no path is specified, it will not be saved. +sub_save_one_file_duration = 60 #unit:s, 0:Infinite duration. +sub_save_max_file_cnt = 10 +sub_draw_osd_text = "sub stream" + +sub_venc_recreate_enable = 0 +sub_venc_recreate_loop_cnt = -1 # loop count, -1:infinite +sub_venc_recreate_interval = 10 #unit:s +sub_venc_recreate_encoder = "H.264" +sub_venc_recreate_framerate = 15 +sub_venc_recreate_bitrate = 1048576 +sub_venc_recreate_dst_width = 1280 +sub_venc_recreate_dst_height = 720 +sub_venc_recreate_key_frame_interval = 30 + +sub_isp_tdm_raw_process_type = -1 #-1:disable, 0:dump 8bit, 1:dump 10bit, 2:dump 8bit for tools, 3:dump 10bit for tools, 4:send 8bit, 5:send 10bit +sub_isp_tdm_raw_width = 1280 +sub_isp_tdm_raw_height = 720 +sub_isp_tdm_raw_rxbuf_num = 5 +sub_isp_tdm_raw_process_frame_cnt_min = 0 +sub_isp_tdm_raw_process_frame_cnt_max = 5 +sub_isp_tdm_raw_file_path = "/mnt/extsd/tdm_raw.bin" + +sub_2nd_enable = 0 +sub_2nd_vipp = 5 +sub_2nd_src_width = 640 +sub_2nd_src_height = 480 +sub_2nd_pixel_format = "nv21" +sub_2nd_vi_buf_num = 3 +sub_2nd_src_frame_rate = 15 +sub_2nd_viChn = 0 +sub_2nd_venc_chn = 3 +sub_2nd_encode_type = "H.264" +sub_2nd_encode_width = 640 +sub_2nd_encode_height = 480 +sub_2nd_encode_frame_rate = 15 +sub_2nd_encode_bitrate = 262144 +sub_2nd_online_en = 0 +sub_2nd_online_share_buf_num = 2 +sub_2nd_encpp_enable = 1 +sub_2nd_ve_ref_frame_lbc_mode = 0 +sub_2nd_key_frame_interval = 30 +sub_2nd_file_path = #"/mnt/extsd/sub2ndStream" +sub_2nd_save_one_file_duration = 60 +sub_2nd_save_max_file_cnt = 10 + +sub_2nd_take_picture = 0 +sub_2nd_take_picture_viChn = 1 +sub_2nd_take_picture_venc_chn = 9 +sub_2nd_take_picture_interval = 10 #unit:s +sub_2nd_take_picture_file = "/mnt/extsd/sub_2nd_pic" +sub_2nd_take_picture_file_cnt = 10 +sub_2nd_take_picture_only_capture_yuv = 0 + +sub_2nd_pdet_enable = 0 +sub_2nd_pdet_viChn = 2 +sub_2nd_pdet_model_pathname = "/mnt/extsd/model/person_det_v4.0.0" +sub_2nd_pdet_input_width = 288 +sub_2nd_pdet_input_height = 160 +sub_2nd_pdet_input_channel = 3 +sub_2nd_pdet_conf_thres = 0.3 +sub_2nd_pdet_run_interval = 30 #unit:fps, default: framerate*2 + +three_enable = 0 #0:disable sub stream, 1:enable sub stream +three_rtsp_id = -1 #-1:disable sub rtsp +three_isp = 2 +three_isp_d3d_lbc_ratio = 0 #[100,400], 0:not set but use default, 100:lossless, 125:1.25x, 150:1.5x(default), 400:4x +three_vipp = 2 +three_src_width = 1280 +three_src_height = 720 +three_pixel_format = "aw_lbc_2_5x" #nv21,nv12,yu12,yv12;aw_lbc_2_5x,aw_lbc_2_0x,aw_lbc_1_5x,aw_lbc_1_0x +three_wdr_enable = 0 +three_vi_buf_num = 3 +three_src_frame_rate = 15 #fps +three_viChn = 0 +three_venc_chn = 4 +three_encode_type = "H.264" +three_encode_width = 1280 #1280x720->720p, 1920x1080->1080p, 2304x1296->3M, 2560×1440->2k, 3840x2160->4k, 7680x4320->8k +three_encode_height = 720 +three_encode_frame_rate = 15 #fps +three_encode_bitrate = 1048576 #5M:5242880, 2.5M:2621440, 2M:2097152, 1.5M:1572864, 1M:1048576, 0.5M:524288, 0.25M:262144 +three_encpp_enable = 1 +three_ve_ref_frame_lbc_mode = 0 #0:default(1.5x), 1:1.5x, 2:2.0x, 3:2.5x, 4:no lossy +three_key_frame_interval = 30 +three_file_path = "/mnt/extsd/threeStream" #if no path is specified, it will not be saved. +three_save_one_file_duration = 60 #unit:s, 0:Infinite duration. +three_save_max_file_cnt = 10 +three_draw_osd_text = "three stream" + +three_venc_recreate_enable = 0 +three_venc_recreate_loop_cnt = -1 # loop count, -1:infinite +three_venc_recreate_interval = 10 #unit:s +three_venc_recreate_encoder = "H.264" +three_venc_recreate_framerate = 15 +three_venc_recreate_bitrate = 1048576 +three_venc_recreate_dst_width = 1280 +three_venc_recreate_dst_height = 720 +three_venc_recreate_key_frame_interval = 30 + +three_isp_tdm_raw_process_type = -1 #-1:disable, 0:dump 8bit, 1:dump 10bit, 2:dump 8bit for tools, 3:dump 10bit for tools, 4:send 8bit, 5:send 10bit +three_isp_tdm_raw_width = 1280 +three_isp_tdm_raw_height = 720 +three_isp_tdm_raw_rxbuf_num = 5 +three_isp_tdm_raw_process_frame_cnt_min = 0 +three_isp_tdm_raw_process_frame_cnt_max = 5 +three_isp_tdm_raw_file_path = "/mnt/extsd/tdm_raw.bin" + +three_2nd_enable = 0 +three_2nd_vipp = 6 +three_2nd_src_width = 640 +three_2nd_src_height = 480 +three_2nd_pixel_format = "nv21" +three_2nd_vi_buf_num = 3 +three_2nd_src_frame_rate = 15 +three_2nd_viChn = 0 +three_2nd_venc_chn = 6 +three_2nd_encode_type = "H.264" +three_2nd_encode_width = 640 +three_2nd_encode_height = 480 +three_2nd_encode_frame_rate = 15 +three_2nd_encode_bitrate = 262144 +three_2nd_online_en = 0 +three_2nd_online_share_buf_num = 2 +three_2nd_encpp_enable = 1 +three_2nd_ve_ref_frame_lbc_mode = 0 +three_2nd_key_frame_interval = 30 +three_2nd_file_path = #"/mnt/extsd/three2ndStream" +three_2nd_save_one_file_duration = 60 +three_2nd_save_max_file_cnt = 10 + +three_2nd_take_picture = 0 +three_2nd_take_picture_viChn = 1 +three_2nd_take_picture_venc_chn = 10 +three_2nd_take_picture_interval = 10 #unit:s +three_2nd_take_picture_file = "/mnt/extsd/three_2nd_pic" +three_2nd_take_picture_file_cnt = 10 +three_2nd_take_picture_only_capture_yuv = 0 + +three_2nd_pdet_enable = 0 +three_2nd_pdet_viChn = 2 +three_2nd_pdet_model_pathname = "/mnt/extsd/model/person_det_v4.0.0" +three_2nd_pdet_input_width = 288 +three_2nd_pdet_input_height = 160 +three_2nd_pdet_input_channel = 3 +three_2nd_pdet_conf_thres = 0.3 +three_2nd_pdet_run_interval = 30 #unit:fps, default: framerate*2 + +four_enable = 0 #0:disable sub stream, 1:enable sub stream +four_rtsp_id = -1 #-1:disable sub rtsp +four_isp = 3 +four_isp_d3d_lbc_ratio = 0 #[100,400], 0:not set but use default, 100:lossless, 125:1.25x, 150:1.5x(default), 400:4x +four_vipp = 3 +four_src_width = 1280 +four_src_height = 720 +four_pixel_format = "aw_lbc_2_5x" #nv21,nv12,yu12,yv12;aw_lbc_2_5x,aw_lbc_2_0x,aw_lbc_1_5x,aw_lbc_1_0x +four_wdr_enable = 0 +four_vi_buf_num = 3 +four_src_frame_rate = 15 #fps +four_viChn = 0 +four_venc_chn = 5 +four_encode_type = "H.264" +four_encode_width = 1280 #1280x720->720p, 1920x1080->1080p, 2304x1296->3M, 2560×1440->2k, 3840x2160->4k, 7680x4320->8k +four_encode_height = 720 +four_encode_frame_rate = 15 #fps +four_encode_bitrate = 1048576 #5M:5242880, 2.5M:2621440, 2M:2097152, 1.5M:1572864, 1M:1048576, 0.5M:524288, 0.25M:262144 +four_encpp_enable = 1 +four_ve_ref_frame_lbc_mode = 0 #0:default(1.5x), 1:1.5x, 2:2.0x, 3:2.5x, 4:no lossy +four_key_frame_interval = 30 +four_file_path = "/mnt/extsd/fourStream" #if no path is specified, it will not be saved. +four_save_one_file_duration = 60 #unit:s, 0:Infinite duration. +four_save_max_file_cnt = 10 +four_draw_osd_text = "four stream" + +four_venc_recreate_enable = 0 +four_venc_recreate_loop_cnt = -1 # loop count, -1:infinite +four_venc_recreate_interval = 10 #unit:s +four_venc_recreate_encoder = "H.264" +four_venc_recreate_framerate = 15 +four_venc_recreate_bitrate = 1048576 +four_venc_recreate_dst_width = 1280 +four_venc_recreate_dst_height = 720 +four_venc_recreate_key_frame_interval = 30 + +four_isp_tdm_raw_process_type = -1 #-1:disable, 0:dump 8bit, 1:dump 10bit, 2:dump 8bit for tools, 3:dump 10bit for tools, 4:send 8bit, 5:send 10bit +four_isp_tdm_raw_width = 1280 +four_isp_tdm_raw_height = 720 +four_isp_tdm_raw_rxbuf_num = 5 +four_isp_tdm_raw_process_frame_cnt_min = 0 +four_isp_tdm_raw_process_frame_cnt_max = 5 +four_isp_tdm_raw_file_path = "/mnt/extsd/tdm_raw.bin" + +four_2nd_enable = 0 +four_2nd_vipp = 7 +four_2nd_src_width = 640 +four_2nd_src_height = 480 +four_2nd_pixel_format = "nv21" +four_2nd_vi_buf_num = 3 +four_2nd_src_frame_rate = 15 +four_2nd_viChn = 0 +four_2nd_venc_chn = 7 +four_2nd_encode_type = "H.264" +four_2nd_encode_width = 640 +four_2nd_encode_height = 480 +four_2nd_encode_frame_rate = 15 +four_2nd_encode_bitrate = 262144 +four_2nd_online_en = 0 +four_2nd_online_share_buf_num = 2 +four_2nd_encpp_enable = 1 +four_2nd_ve_ref_frame_lbc_mode = 0 +four_2nd_key_frame_interval = 30 +four_2nd_file_path = #"/mnt/extsd/four2ndStream" +four_2nd_save_one_file_duration = 60 +four_2nd_save_max_file_cnt = 10 + +four_2nd_take_picture = 0 +four_2nd_take_picture_viChn = 1 +four_2nd_take_picture_venc_chn = 11 +four_2nd_take_picture_interval = 10 #unit:s +four_2nd_take_picture_file = "/mnt/extsd/four_2nd_pic" +four_2nd_take_picture_file_cnt = 10 +four_2nd_take_picture_only_capture_yuv = 0 + +four_2nd_pdet_enable = 0 +four_2nd_pdet_viChn = 2 +four_2nd_pdet_model_pathname = "/mnt/extsd/model/person_det_v4.0.0" +four_2nd_pdet_input_width = 288 +four_2nd_pdet_input_height = 160 +four_2nd_pdet_input_channel = 3 +four_2nd_pdet_conf_thres = 0.3 +four_2nd_pdet_run_interval = 30 #unit:fps, default: framerate*2 +``` \ No newline at end of file diff --git a/docs/引脚.md b/docs/引脚.md new file mode 100644 index 0000000..3f52260 --- /dev/null +++ b/docs/引脚.md @@ -0,0 +1,21 @@ +### 扬声器MAX98357A + +VIN-3V3 +GND-GND +SD-3V3 +GAIN-GND +DIN-PD15 +BCLK-PD12 +LRC-PD13 + +### IMU + +VCC-3V3 +GND-GND +AD0-PD4 +SDA-PD2 +SCL-PD3 +CS-PD5 + + +