This commit is contained in:
2024-06-03 16:27:41 +08:00
commit b7ab42dd94
625 changed files with 214806 additions and 0 deletions

70
SOFTWARE/Source/DTH11.cpp Normal file
View File

@@ -0,0 +1,70 @@
#include "DTH11.hpp"
typedef struct {
float humidity;
float temp_celsius;
} dht_reading;
void read_from_dht(dht_reading * result, int DHT_PIN)
{
int data[5] = { 0, 0, 0, 0, 0 };
uint last = 1;
uint j = 0;
gpio_set_dir(DHT_PIN, GPIO_OUT);
gpio_put(DHT_PIN, 0);
sleep_ms(20);
gpio_set_dir(DHT_PIN, GPIO_IN);
for (uint i = 0; i < MAX_TIMINGS; i++) {
uint count = 0;
while (gpio_get(DHT_PIN) == last) {
count++;
sleep_us(1);
if (count == 255)
break;
}
last = gpio_get(DHT_PIN);
if (count == 255)
break;
if ((i >= 4) && (i % 2 == 0)) {
data[j / 8] <<= 1;
if (count > 16)
data[j / 8] |= 1;
j++;
}
}
if ((j >= 40) && (data[4] == ((data[0] + data[1] + data[2] + data[3]) & 0xFF))) {
result->humidity = (float)((data[0] << 8) + data[1]) / 10;
if (result->humidity > 100) {
result->humidity = data[0];
}
result->temp_celsius = (float)(((data[2] & 0x7F) << 8) + data[3]) / 10;
if (result->temp_celsius > 125) {
result->temp_celsius = data[2];
}
if (data[2] & 0x80) {
result->temp_celsius = -result->temp_celsius;
}
} else {
printf("Bad data\n");
}
}
int DTH11_(int DHT_PIN)
{
stdio_init_all();
gpio_init(DHT_PIN);
dht_reading reading;
read_from_dht(&reading, DHT_PIN);
float fahrenheit = (reading.temp_celsius * 9 / 5) + 32;
printf("Humidity = %.1f%%, Temperature = %.1fC (%.1fF)\n", reading.humidity, reading.temp_celsius, fahrenheit);
sleep_ms(2000);
return 0;
}

11
SOFTWARE/Source/DTH11.hpp Normal file
View File

@@ -0,0 +1,11 @@
#ifndef DTH11_H
#define DTH11_H
#include <stdio.h>
#include <math.h>
#include "pico/stdlib.h"
#include "hardware/gpio.h"
const uint MAX_TIMINGS = 85;
#endif

20
SOFTWARE/Source/HC-12.cpp Normal file
View File

@@ -0,0 +1,20 @@
#include "HC-12.hpp"
void _HC_12_INIT()
{
uint tx_offset = pio_add_program(pio1, &uart_tx_program);
uart_tx_program_init(HC_12_PIO, HC_12_PIO_SM_TX, tx_offset, HC_12_PIO_TX_PIN, HC_12_PIO_SERIAL_BAUD);
uint rx_offset = pio_add_program(pio1, &uart_rx_program);
uart_rx_program_init(HC_12_PIO, HC_12_PIO_SM_RX, rx_offset, HC_12_PIO_RX_PIN, HC_12_PIO_SERIAL_BAUD);
return;
}
void _HC_12(const char *string)
{
uart_tx_program_puts(HC_12_PIO, HC_12_PIO_SM_TX, string);
sleep_ms(100);
return;
}

19
SOFTWARE/Source/HC-12.hpp Normal file
View File

@@ -0,0 +1,19 @@
#ifndef HC_12_H
#define HC_12_H
#include "pico/stdlib.h"
#include "hardware/pio.h"
#include "uart_tx.pio.h"
#include "uart_rx.pio.h"
#define HC_12_PIO pio1
#define HC_12_PIO_TX_PIN 16 // 接 HC-12 RX
#define HC_12_PIO_RX_PIN 15 // 接 HC-12 TX
#define HC_12_PIO_SM_TX 0
#define HC_12_PIO_SM_RX 1
#define HC_12_PIO_SERIAL_BAUD 9600
extern void _HC_12_INIT();
extern void _HC_12(const char *string);
#endif

380
SOFTWARE/Source/MAIN.cpp Normal file
View File

@@ -0,0 +1,380 @@
/*
*
* 基于 Raspberry Pico 的厨房危险(火灾)报警
* 使用 DS18B20温度传感器
* 使用 CH4 N55A甲烷气体传感器(进口)
* 使用 PASCO2V01 CO2二氧化碳传感器模块(进口模块暂时买不到!)
* 使用 MH-Z14B CO2二氧化碳传感器模块(国产)(0 - 5000ppm)
* 使用 ME2_CO CO一氧化碳传感器模块(国产)
*
* Date: 20240103
*
*/
#include "MAIN.hpp"
#include "DTH11.hpp"
#include "HC-12.hpp"
#include "ZC13.hpp"
#ifndef PICO_DEFAULT_LED_PIN
#warning pio/hello_pio example requires a board with a regular LED
#define PICO_DEFAULT_LED_PIN 25
#endif
static inline bool uart_rx_program_available(PIO pio, uint sm)
{
return !pio_sm_is_rx_fifo_empty(pio, sm);
}
// 闪烁LED
static void light_flashing()
{
gpio_init(PICO_DEFAULT_LED_PIN);
gpio_set_dir(PICO_DEFAULT_LED_PIN, GPIO_OUT);
gpio_put(PICO_DEFAULT_LED_PIN, 1);
sleep_ms(100);
gpio_put(PICO_DEFAULT_LED_PIN, 0);
sleep_ms(100);
return;
}
int wifi()
{
if (cyw43_arch_init()) {
printf("failed to initialise\n");
return 1;
}
cyw43_arch_enable_sta_mode();
printf("Connecting to Wi-Fi...\n");
if (cyw43_arch_wifi_connect_timeout_ms(WIFI_SSID, WIFI_PASSWORD, CYW43_AUTH_WPA2_AES_PSK, 30000)) {
printf("failed to connect.\n");
return 1;
} else {
printf("Connected.\n");
}
cyw43_arch_deinit();
return 0;
}
// 获取主板温度
float read_onboard_temperature()
{
adc_init();
adc_set_temp_sensor_enabled(true);
adc_select_input(4); // Input 4 is the onboard temperature sensor.
/* 12-bit conversion, assume max value == ADC_VREF == 3.3 V */
const float conversionFactor = 3.3f / (1 << 12);
float adc = (float)adc_read() * conversionFactor;
float tempC = 27.0f - (adc - 0.706f) / 0.001721f;
//printf("Onboard temperature %.02f°C %.02f°F\n", tempC, (tempC * 9 / 5 + 32));
return tempC;
}
// 温度传感器
float DS18B20()
{
float TEMPERATURE = -1;
One_wire one_wire(DS18B20_PIN);
one_wire.init();
rom_address_t address {
};
one_wire.single_device_read_rom(address);
/*
printf("Device Address: %02x%02x%02x%02x%02x%02x%02x%02x\n",
address.rom[0], address.rom[1], address.rom[2], address.rom[3],
address.rom[4], address.rom[5], address.rom[6], address.rom[7]);
*/
one_wire.convert_temperature(address, true, false);
TEMPERATURE = one_wire.temperature(address);
//printf("Temperature: %3.1f°C\n", one_wire.temperature(address));
return TEMPERATURE;
}
// 甲烷气体传感器
int CH4()
{
int CH4_TRUE = 0;
gpio_init(PICO_DEFAULT_LED_PIN);
gpio_set_dir(PICO_DEFAULT_LED_PIN, GPIO_OUT);
gpio_init(CH4_PIN); // 设置 GP14 引脚作为输入引脚
gpio_set_dir(CH4_PIN, GPIO_IN);
if (gpio_get(CH4_PIN) == 1) {
CH4_TRUE = 1;
}
sleep_ms(100);
return CH4_TRUE;
}
// CO2
static uint16_t MH_Z14B(int *MH_Z14B_DATA_IS_OK)
{
// 初始化UART
uart_init(UART1, BAUD_RATE);
gpio_set_function(UART1_TX_PIN, GPIO_FUNC_UART);
gpio_set_function(UART1_RX_PIN, GPIO_FUNC_UART);
uart_set_hw_flow(UART1, false, false);
uart_set_format(UART1, DATA_BITS, STOP_BITS, PARITY);
// 0x86 读气体浓度值
uint8_t CMD[9] = { 0xFF, 0x01, 0x86, 0x00, 0x00, 0x00, 0x00, 0x00, 0x79 };
uart_write_blocking(UART1, CMD, 9);
sleep_ms(200);
// 读取
uint8_t CO2_DATA[9] = { 0 };
uart_read_blocking(UART1, CO2_DATA, 9);
// CO2 浓度
uint16_t CO2_CONC = (256 * CO2_DATA[2]) + CO2_DATA[3];
// 校验
uint8_t CHECKSUM = (0xFF - (CO2_DATA[1] + CO2_DATA[2] + CO2_DATA[3] + CO2_DATA[4] + CO2_DATA[5] + CO2_DATA[6] + CO2_DATA[7])) + 1;
if (CO2_DATA[8] == CHECKSUM && CO2_DATA[1] == 0x86) {
//printf("CHECKSUM: %X = %X\n", CO2_DATA[8], CHECKSUM);
//printf("CO2 Concentration: %d ppm\n", CO2_CONC);
*MH_Z14B_DATA_IS_OK = 1;
} else {
// 校准传感器 零点 ZERO
uint8_t ZERO[] = { 0XFF, 0X01, 0X87, 0X00, 0X00, 0X00, 0X00, 0X00, 0X78 };
uart_write_blocking(UART1, ZERO, 9);
sleep_ms(200);
// 校准传感器 跨度点 SPAN
uint8_t SPAN[] = { 0XFF, 0X01, 0X88, 0X07, 0XD0, 0X00, 0X00, 0X00, 0XA0 };
uart_write_blocking(UART1, SPAN, 9);
sleep_ms(200);
*MH_Z14B_DATA_IS_OK = 0;
printf("CO2 concentration reading failed!\n");
}
return CO2_CONC;
}
// CO
static uint16_t ME2_CO(int IS_ANSWER, int *ME2_CO_DATA_IS_OK)
{
// 初始化UART
uart_init(UART0, BAUD_RATE);
gpio_set_function(UART0_TX_PIN, GPIO_FUNC_UART);
gpio_set_function(UART0_RX_PIN, GPIO_FUNC_UART);
uart_set_hw_flow(UART0, false, false);
uart_set_format(UART0, DATA_BITS, STOP_BITS, PARITY);
if (IS_ANSWER == 1) {
// 应答模式
uint8_t _ANSWER[9] = { 0xFF, 0x01, 0x78, 0x41, 0x00, 0x00, 0x00, 0x00, 0x46 };
uart_write_blocking(UART0, _ANSWER, 9);
sleep_ms(100);
}
// 读取
uint8_t CO_DATA[9] = { 0 };
uart_read_blocking(UART0, CO_DATA, 9);
// CO 浓度
uint16_t CO_CONC = (256 * CO_DATA[4]) + CO_DATA[5];
// 校验
uint8_t CHECKSUM = (0xFF - (CO_DATA[1] + CO_DATA[2] + CO_DATA[3] + CO_DATA[4] + CO_DATA[5] + CO_DATA[6] + CO_DATA[7])) + 1;
if (CO_DATA[8] == CHECKSUM && CO_DATA[1] == 0x04) {
//printf("CHECKSUM: %X = %X\n", CO_DATA[8], CHECKSUM);
//printf("CO Concentration: %d ppm\n", CO_CONC);
*ME2_CO_DATA_IS_OK = 1;
} else {
*ME2_CO_DATA_IS_OK = 0;
}
return CO_CONC;
}
// 433MHZ 无线电发送数据到服务器端Raspberry pico W WiFi 暂时不实现)
int _433_MHZ(unsigned long val)
{
const uint RADIO_TRANSMIT_PIN = _433_MHZ_PIN; // 433发射模块引脚
const uint PULSE_LENGTH = 169; // set this to PULSELENGTH RECIEVED
const uint REPEAT_TRANSMIT = 4; // set this to whatever works best for you. // 重复发送
const uint PROTOCOL = 1; // set this to PROTOCOL RECIEVED
const uint BIT_LENGTH = 24; // set this to BIT LENGTH RECIEVED
gpio_init(RADIO_TRANSMIT_PIN);
RCSwitch mySwitch = RCSwitch();
mySwitch.enableTransmit(RADIO_TRANSMIT_PIN);
mySwitch.setProtocol(PROTOCOL);
mySwitch.setPulseLength(PULSE_LENGTH);
mySwitch.setRepeatTransmit(REPEAT_TRANSMIT);
mySwitch.send(val, BIT_LENGTH);
sleep_ms(10);
return 0;
}
// 简单编码通过433MHZ发送
int addDigit(int number, int digit)
{
char TEMP[BUFER] = { 0 };
snprintf(TEMP, sizeof(TEMP), "%d%d%d", digit, number, digit);
return atoi(TEMP);
}
// 核心0发送数据到核心1, 核心1判断是否有数据到来.
static void core1_main()
{
while (1) {
multicore_fifo_push_blocking(CH4());
watchdog_update();
sleep_ms(1000);
}
return;
}
int main()
{
stdio_init_all();
sleep_ms(1000);
set_sys_clock_khz(250000, true);
int FIFO_ = -1;
float TEMPERATURE = -1;
float ONBOARD_TEMPERATURE = -1;
uint16_t CO2_DATA = -1;
uint16_t CO_DATA = -1;
int MH_Z14B_DATA_IS_OK = 0;
int ME2_CO_DATA_IS_OK = 0;
// core1
multicore_reset_core1();
multicore_launch_core1(core1_main);
if (watchdog_caused_reboot()) { // 判断是否从看门狗启动或者正常启动
printf("Rebooted by Watchdog!\n");
} else {
printf("Clean boot\n");
}
watchdog_enable(8300, 1); // 8秒检测是否重新加载看门狗计数器. (不更新计数器则重启硬件, 最高8秒)
watchdog_start_tick(12);
_HC_12_INIT();
ZC13_INIT();
while (1) {
watchdog_update(); // 喂狗
// RP2040温度
ONBOARD_TEMPERATURE = read_onboard_temperature();
if (ONBOARD_TEMPERATURE != -1) {
printf("Onboard temperature %.02f°C %.02f°F\n", ONBOARD_TEMPERATURE, (ONBOARD_TEMPERATURE * 9 / 5 + 32));
//_433_MHZ(addDigit(ONBOARD_TEMPERATURE, SIGN_RP2040));
char ONBOARD_TEMPERATURE_TEMP[BUFER] = { 0 };
sprintf(ONBOARD_TEMPERATURE_TEMP, "Onboard temperature %.02f°C %.02f°F\n", ONBOARD_TEMPERATURE, (ONBOARD_TEMPERATURE * 9 / 5 + 32));
_HC_12(ONBOARD_TEMPERATURE_TEMP);
}
watchdog_update(); // 喂狗
// CH4
FIFO_ = multicore_fifo_pop_blocking();
if (FIFO_ == 1) {
printf("Kitchen danger (fire) alarm detects CH4!!!\n");
light_flashing();
FIFO_ = -1;
//_433_MHZ(addDigit(4, SIGN_CH4));
}
watchdog_update(); // 喂狗
/*
if (1 == CH4()) {
printf("Kitchen danger (fire) alarm detects CH4!!!\n");
light_flashing();
_HC_12("Kitchen danger (fire) alarm detects CH4!!!\n");
}
watchdog_update(); // 喂狗
*/
// DS18B20
TEMPERATURE = DS18B20();
if (TEMPERATURE != -1) {
if (TEMPERATURE >= 10) {
printf("Temperature: %.3f°C\n", TEMPERATURE);
}
//_433_MHZ(addDigit(TEMPERATURE, SIGN_DS18B20));
if (TEMPERATURE != 85) {
char TEMPERATURE_TEMP[BUFER] = { 0 };
sprintf(TEMPERATURE_TEMP, "Temperature: %.3f°C\n", TEMPERATURE);
_HC_12(TEMPERATURE_TEMP);
TEMPERATURE = -1;
}
}
watchdog_update(); // 喂狗
// ZC13 CH4 传感器
char CH4_DATA[BUFER] = { 0 };
sprintf(CH4_DATA, "CH4 Concentration: %d\n", ZC13("ZC05"));
_HC_12(CH4_DATA);
watchdog_update(); // 喂狗
// ME2_CO CO
// 50 ppm百万分之一长时间暴露可能会导致头痛、恶心、疲劳等不适症状。
// 200 ppm短时间暴露可能会导致轻微的头痛、疲劳和呼吸困难。
// 800 ppm短时间暴露可能会导致头晕、恶心和死亡。
// 1600 ppm短时间暴露可能会导致昏迷、危及生命。
CO_DATA = ME2_CO(0, &ME2_CO_DATA_IS_OK);
if (CO_DATA != -1 && ME2_CO_DATA_IS_OK == 1) {
printf("CO Concentration: %d ppm\n", CO_DATA);
//_433_MHZ(addDigit(CO_DATA, SIGN_CO));
char CO_DATA_TEMP[BUFER] = { 0 };
sprintf(CO_DATA_TEMP, "CO Concentration: %d ppm\n", CO_DATA);
_HC_12(CO_DATA_TEMP);
}
watchdog_update(); // 喂狗
// MH_Z14B CO2
CO2_DATA = MH_Z14B(&MH_Z14B_DATA_IS_OK);
if (CO2_DATA != -1 && MH_Z14B_DATA_IS_OK == 1) {
printf("CO2 Concentration: %d ppm\n", CO2_DATA);
//_433_MHZ(addDigit(CO2_DATA, SIGN_CO2));
char CO2_DATA_TEMP[BUFER] = { 0 };
sprintf(CO2_DATA_TEMP, "CO2 Concentration: %d ppm\n", CO2_DATA);
_HC_12(CO2_DATA_TEMP);
}
printf("\r\n");
watchdog_update(); // 喂狗
sleep_ms(3000);
watchdog_update(); // 喂狗
}
return 0;
}

49
SOFTWARE/Source/MAIN.hpp Normal file
View File

@@ -0,0 +1,49 @@
#ifndef MAIN_H
#define MAIN_H
#include <cstdio>
#include "pico/stdlib.h"
#include "hardware/gpio.h"
#include "lib/pico-onewire/api/one_wire.h"
#include "lib/radio-switch.h"
#include "hardware/clocks.h"
#include "hardware/watchdog.h"
#include "pico/multicore.h"
#include "hardware/i2c.h"
#include "pico/binary_info.h"
#include "hardware/uart.h"
#include "hardware/pwm.h"
#include "hardware/adc.h"
#include "pico/cyw43_arch.h"
#include "lwip/pbuf.h"
#include "lwip/tcp.h"
#define BUFER 1024
#define DS18B20_PIN 15 // DS18B20 引脚
#define CH4_PIN 14 // CH4 引脚
#define _433_MHZ_PIN 13
#define SIGN_CH4 1
#define SIGN_DS18B20 2
#define SIGN_CO 3
#define SIGN_CO2 4
#define SIGN_RP2040 5
#define WIFI_SSID "your_wifi_ssid"
#define WIFI_PASSWORD "your_wifi_password"
#define UART1 uart1
#define BAUD_RATE 9600
#define DATA_BITS 8
#define STOP_BITS 1
#define PARITY UART_PARITY_NONE
#define UART1_TX_PIN 5 // MH-Z14B T
#define UART1_RX_PIN 4 // MH-Z14B R
#define UART0 uart0
#define UART0_TX_PIN 1 //
#define UART0_RX_PIN 0 //
#endif

171
SOFTWARE/Source/ZC13.cpp Normal file
View File

@@ -0,0 +1,171 @@
#include "ZC13.hpp"
#include "common.h"
int ZC13_INIT()
{
uint tx_offset = pio_add_program(ZC13_PIO, &uart_tx_program);
uart_tx_program_init(ZC13_PIO, ZC13_PIO_SM_TX, tx_offset, ZC13_PIO_TX_PIN, ZC13_PIO_SERIAL_BAUD);
uint rx_offset = pio_add_program(ZC13_PIO, &uart_rx_program);
uart_rx_program_init(ZC13_PIO, ZC13_PIO_SM_RX, rx_offset, ZC13_PIO_RX_PIN, ZC13_PIO_SERIAL_BAUD);
return 0;
}
int ZC13_PIO_UART_TX_DATA(PIO pio, uint sm, uint8_t *DATA, int DATA_LEN) {
for (int i = 0; i < DATA_LEN; i++) {
uart_tx_program_putc(pio, sm, DATA[i]);
sleep_ms(3);
}
return 0;
}
int ZC13_PIO_UART_RX_DATA(PIO pio, uint sm, uint8_t *DATA, int DATA_LEN) {
char c = '\0';
int received_count = 0;
int timeout_ms = 100; // 设置较长的超时时间
while (received_count < DATA_LEN && timeout_ms > 0) {
if (uart_rx_program_available(pio, sm)) {
c = uart_rx_program_getc(pio, sm);
DATA[received_count++] = c;
printf("0x%X ", c);
if (c == '\n') {
// 接收到换行符,停止接收数据
break;
}
} else {
// 没有接收到数据,继续等待
sleep_ms(1);
timeout_ms--;
}
}
if (received_count == 0) {
// 没有接收到有效数据,可以进行相应的处理
return -1;
}
return received_count;
}
int ZC13(const char *model)
{
uint8_t CH4_DATA[270] = { 0 };
int CH4_DATA_LEN = 0;
// 发送指令
uint8_t CH4_CMD[9] = { 0xFF, 0x01, 0x86, 0x00, 0x00, 0x00, 0x00, 0x00, 0x79 };
ZC13_PIO_UART_TX_DATA(ZC13_PIO, ZC13_PIO_SM_TX, CH4_CMD, sizeof(CH4_CMD));
sleep_ms(200);
// 接收指令
CH4_DATA_LEN = ZC13_PIO_UART_RX_DATA(ZC13_PIO, ZC13_PIO_SM_RX, CH4_DATA, 9);
printf("\n");
printf("%d\n", CH4_DATA_LEN);
uint8_t highByte = CH4_DATA[2]; // 假设这是气体浓度高位字节
uint8_t lowByte = CH4_DATA[3]; // 假设这是气体浓度高位字节
// 判断最高位是否为 1
if (highByte & 0x80) {
// 最高位是 1表示传感器故障
printf("CH4 sensor malfunction!\n");
} else {
if (CH4_DATA[1] == 0X86) {
if ( 0 == strcasecmp(model, "ZC05")) {
// 计算气体浓度值
uint16_t gasConcentration = (highByte & 0x3F) * 256 + lowByte;
// 输出气体浓度值
printf("CH4 Concentration: %uppm\n", gasConcentration);
return gasConcentration;
}
if ( 0 == strcasecmp(model, "ZC13")) {
// 计算气体浓度值
uint16_t gasConcentration = (highByte & 0x1F) * 256 + lowByte;
// 输出气体浓度值
printf("CH4 Concentration: %uppm\n", gasConcentration);
return gasConcentration;
}
}
}
return -1;
}
/*
int ZC13(const char *model)
{
char CH4_DATA[9] = { 0 };
int CH4_DATA_index = 0;
// 发送指令
char CH4_CMD[9] = { 0xFF, 0x01, 0x86, 0x00, 0x00, 0x00, 0x00, 0x00, 0x79 };
for (int i = 0; i < 9; i++) {
uart_tx_program_putc(ZC13_PIO, ZC13_PIO_SM_TX, CH4_CMD[i]);
sleep_ms(1);
}
sleep_ms(200);
// 接收数据,直到收到换行符或达到缓冲区大小限制
char c = '\0';
int timeout_ms = 100; // 设置超时时间为100ms
int received_count = 0;
while (received_count < 9 && timeout_ms > 0) {
if (uart_rx_program_available(ZC13_PIO, ZC13_PIO_SM_RX)) {
c = uart_rx_program_getc(ZC13_PIO, ZC13_PIO_SM_RX);
CH4_DATA[CH4_DATA_index++] = c;
received_count++;
timeout_ms = 100; // 重置超时时间
} else {
sleep_ms(1);
timeout_ms--; // 减少超时时间
}
}
// 处理接收到的数据
for (int i = 0; i < 9; i++) {
printf("0x%X ", CH4_DATA[i]);
}
printf("\n");
uint8_t highByte = CH4_DATA[2]; // 假设这是气体浓度高位字节
uint8_t lowByte = CH4_DATA[3]; // 假设这是气体浓度高位字节
// 判断最高位是否为 1
if (highByte & 0x80) {
// 最高位是 1表示传感器故障
printf("CH4 sensor malfunction!\n");
} else {
if (CH4_DATA[1] == 0X86) {
if ( 0 == strcasecmp(model, "ZC05")) {
// 计算气体浓度值
uint16_t gasConcentration = (highByte & 0x3F) * 256 + lowByte;
// 输出气体浓度值
printf("CH4 Concentration: %uppm\n", gasConcentration);
return gasConcentration;
}
if ( 0 == strcasecmp(model, "ZC13")) {
// 计算气体浓度值
uint16_t gasConcentration = (highByte & 0x1F) * 256 + lowByte;
// 输出气体浓度值
printf("CH4 Concentration: %uppm\n", gasConcentration);
return gasConcentration;
}
}
}
return -1;
}
*/

21
SOFTWARE/Source/ZC13.hpp Normal file
View File

@@ -0,0 +1,21 @@
#ifndef ZC13_HPP
#define ZC13_HPP
#include <stdio.h>
#include <strings.h>
#include "pico/stdlib.h"
#include "hardware/pio.h"
#include "uart_tx.pio.h"
#include "uart_rx.pio.h"
#define ZC13_PIO pio0
#define ZC13_PIO_TX_PIN 19 // 接ZC13 4 TX PIN
#define ZC13_PIO_RX_PIN 20 // 接ZC13 5 RX PIN
#define ZC13_PIO_SM_TX 0
#define ZC13_PIO_SM_RX 1
#define ZC13_PIO_SERIAL_BAUD 9600
extern int ZC13_INIT();
extern int ZC13(const char *model);
#endif

4
SOFTWARE/Source/common.c Normal file
View File

@@ -0,0 +1,4 @@
#include "common.h"

12
SOFTWARE/Source/common.h Normal file
View File

@@ -0,0 +1,12 @@
#ifndef COMMOM_H
#define COMMOM_H
#include "hardware/pio.h"
static inline bool uart_rx_program_available(PIO pio, uint sm)
{
return !pio_sm_is_rx_fifo_empty(pio, sm);
}
#endif

View File

@@ -0,0 +1,10 @@
#ifndef _LWIPOPTS_H
#define _LWIPOPTS_H
// Generally you would define your own explicit list of lwIP options
// (see https://www.nongnu.org/lwip/2_1_x/group__lwip__opts.html)
//
// This example uses a common include to avoid repetition
#include "lwipopts_examples_common.h"
#endif

View File

@@ -0,0 +1,89 @@
#ifndef _LWIPOPTS_EXAMPLE_COMMONH_H
#define _LWIPOPTS_EXAMPLE_COMMONH_H
// Common settings used in most of the pico_w examples
// (see https://www.nongnu.org/lwip/2_1_x/group__lwip__opts.html for details)
// allow override in some examples
#ifndef NO_SYS
#define NO_SYS 1
#endif
// allow override in some examples
#ifndef LWIP_SOCKET
#define LWIP_SOCKET 0
#endif
#if PICO_CYW43_ARCH_POLL
#define MEM_LIBC_MALLOC 1
#else
// MEM_LIBC_MALLOC is incompatible with non polling versions
#define MEM_LIBC_MALLOC 0
#endif
#define MEM_ALIGNMENT 4
#define MEM_SIZE 4000
#define MEMP_NUM_TCP_SEG 32
#define MEMP_NUM_ARP_QUEUE 10
#define PBUF_POOL_SIZE 24
#define LWIP_ARP 1
#define LWIP_ETHERNET 1
#define LWIP_ICMP 1
#define LWIP_RAW 1
#define TCP_WND (8 * TCP_MSS)
#define TCP_MSS 1460
#define TCP_SND_BUF (8 * TCP_MSS)
#define TCP_SND_QUEUELEN ((4 * (TCP_SND_BUF) + (TCP_MSS - 1)) / (TCP_MSS))
#define LWIP_NETIF_STATUS_CALLBACK 1
#define LWIP_NETIF_LINK_CALLBACK 1
#define LWIP_NETIF_HOSTNAME 1
#define LWIP_NETCONN 0
#define MEM_STATS 0
#define SYS_STATS 0
#define MEMP_STATS 0
#define LINK_STATS 0
// #define ETH_PAD_SIZE 2
#define LWIP_CHKSUM_ALGORITHM 3
#define LWIP_DHCP 1
#define LWIP_IPV4 1
#define LWIP_TCP 1
#define LWIP_UDP 1
#define LWIP_DNS 1
#define LWIP_TCP_KEEPALIVE 1
#define LWIP_NETIF_TX_SINGLE_PBUF 1
#define DHCP_DOES_ARP_CHECK 0
#define LWIP_DHCP_DOES_ACD_CHECK 0
#ifndef NDEBUG
#define LWIP_DEBUG 1
#define LWIP_STATS 1
#define LWIP_STATS_DISPLAY 1
#endif
#define ETHARP_DEBUG LWIP_DBG_OFF
#define NETIF_DEBUG LWIP_DBG_OFF
#define PBUF_DEBUG LWIP_DBG_OFF
#define API_LIB_DEBUG LWIP_DBG_OFF
#define API_MSG_DEBUG LWIP_DBG_OFF
#define SOCKETS_DEBUG LWIP_DBG_OFF
#define ICMP_DEBUG LWIP_DBG_OFF
#define INET_DEBUG LWIP_DBG_OFF
#define IP_DEBUG LWIP_DBG_OFF
#define IP_REASS_DEBUG LWIP_DBG_OFF
#define RAW_DEBUG LWIP_DBG_OFF
#define MEM_DEBUG LWIP_DBG_OFF
#define MEMP_DEBUG LWIP_DBG_OFF
#define SYS_DEBUG LWIP_DBG_OFF
#define TCP_DEBUG LWIP_DBG_OFF
#define TCP_INPUT_DEBUG LWIP_DBG_OFF
#define TCP_OUTPUT_DEBUG LWIP_DBG_OFF
#define TCP_RTO_DEBUG LWIP_DBG_OFF
#define TCP_CWND_DEBUG LWIP_DBG_OFF
#define TCP_WND_DEBUG LWIP_DBG_OFF
#define TCP_FR_DEBUG LWIP_DBG_OFF
#define TCP_QLEN_DEBUG LWIP_DBG_OFF
#define TCP_RST_DEBUG LWIP_DBG_OFF
#define UDP_DEBUG LWIP_DBG_OFF
#define TCPIP_DEBUG LWIP_DBG_OFF
#define PPP_DEBUG LWIP_DBG_OFF
#define SLIP_DEBUG LWIP_DBG_OFF
#define DHCP_DEBUG LWIP_DBG_OFF
#endif /* __LWIPOPTS_H__ */

View File

@@ -0,0 +1,94 @@
;
; Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
;
; SPDX-License-Identifier: BSD-3-Clause
;
.program uart_rx_mini
; Minimum viable 8n1 UART receiver. Wait for the start bit, then sample 8 bits
; with the correct timing.
; IN pin 0 is mapped to the GPIO used as UART RX.
; Autopush must be enabled, with a threshold of 8.
wait 0 pin 0 ; Wait for start bit
set x, 7 [10] ; Preload bit counter, delay until eye of first data bit
bitloop: ; Loop 8 times
in pins, 1 ; Sample data
jmp x-- bitloop [6] ; Each iteration is 8 cycles
% c-sdk {
#include "hardware/clocks.h"
#include "hardware/gpio.h"
static inline void uart_rx_mini_program_init(PIO pio, uint sm, uint offset, uint pin, uint baud) {
pio_sm_set_consecutive_pindirs(pio, sm, pin, 1, false);
pio_gpio_init(pio, pin);
gpio_pull_up(pin);
pio_sm_config c = uart_rx_mini_program_get_default_config(offset);
sm_config_set_in_pins(&c, pin); // for WAIT, IN
// Shift to right, autopush enabled
sm_config_set_in_shift(&c, true, true, 8);
sm_config_set_fifo_join(&c, PIO_FIFO_JOIN_RX);
// SM transmits 1 bit per 8 execution cycles.
float div = (float)clock_get_hz(clk_sys) / (8 * baud);
sm_config_set_clkdiv(&c, div);
pio_sm_init(pio, sm, offset, &c);
pio_sm_set_enabled(pio, sm, true);
}
%}
.program uart_rx
; Slightly more fleshed-out 8n1 UART receiver which handles framing errors and
; break conditions more gracefully.
; IN pin 0 and JMP pin are both mapped to the GPIO used as UART RX.
start:
wait 0 pin 0 ; Stall until start bit is asserted
set x, 7 [10] ; Preload bit counter, then delay until halfway through
bitloop: ; the first data bit (12 cycles incl wait, set).
in pins, 1 ; Shift data bit into ISR
jmp x-- bitloop [6] ; Loop 8 times, each loop iteration is 8 cycles
jmp pin good_stop ; Check stop bit (should be high)
irq 4 rel ; Either a framing error or a break. Set a sticky flag,
wait 1 pin 0 ; and wait for line to return to idle state.
jmp start ; Don't push data if we didn't see good framing.
good_stop: ; No delay before returning to start; a little slack is
push ; important in case the TX clock is slightly too fast.
% c-sdk {
static inline void uart_rx_program_init(PIO pio, uint sm, uint offset, uint pin, uint baud) {
pio_sm_set_consecutive_pindirs(pio, sm, pin, 1, false);
pio_gpio_init(pio, pin);
gpio_pull_up(pin);
pio_sm_config c = uart_rx_program_get_default_config(offset);
sm_config_set_in_pins(&c, pin); // for WAIT, IN
sm_config_set_jmp_pin(&c, pin); // for JMP
// Shift to right, autopush disabled
sm_config_set_in_shift(&c, true, false, 32);
// Deeper FIFO as we're not doing any TX
sm_config_set_fifo_join(&c, PIO_FIFO_JOIN_RX);
// SM transmits 1 bit per 8 execution cycles.
float div = (float)clock_get_hz(clk_sys) / (8 * baud);
sm_config_set_clkdiv(&c, div);
pio_sm_init(pio, sm, offset, &c);
pio_sm_set_enabled(pio, sm, true);
}
static inline char uart_rx_program_getc(PIO pio, uint sm) {
// 8-bit read from the uppermost byte of the FIFO, as data is left-justified
io_rw_8 *rxfifo_shift = (io_rw_8*)&pio->rxf[sm] + 3;
while (pio_sm_is_rx_fifo_empty(pio, sm))
tight_loop_contents();
return (char)*rxfifo_shift;
}
%}

View File

@@ -0,0 +1,61 @@
;
; Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
;
; SPDX-License-Identifier: BSD-3-Clause
;
.program uart_tx
.side_set 1 opt
; An 8n1 UART transmit program.
; OUT pin 0 and side-set pin 0 are both mapped to UART TX pin.
pull side 1 [7] ; Assert stop bit, or stall with line in idle state
set x, 7 side 0 [7] ; Preload bit counter, assert start bit for 8 clocks
bitloop: ; This loop will run 8 times (8n1 UART)
out pins, 1 ; Shift 1 bit from OSR to the first OUT pin
jmp x-- bitloop [6] ; Each loop iteration is 8 cycles.
% c-sdk {
#include "hardware/clocks.h"
static inline void uart_tx_program_init(PIO pio, uint sm, uint offset, uint pin_tx, uint baud) {
// Tell PIO to initially drive output-high on the selected pin, then map PIO
// onto that pin with the IO muxes.
pio_sm_set_pins_with_mask(pio, sm, 1u << pin_tx, 1u << pin_tx);
pio_sm_set_pindirs_with_mask(pio, sm, 1u << pin_tx, 1u << pin_tx);
pio_gpio_init(pio, pin_tx);
pio_sm_config c = uart_tx_program_get_default_config(offset);
// OUT shifts to right, no autopull
sm_config_set_out_shift(&c, true, false, 32);
// We are mapping both OUT and side-set to the same pin, because sometimes
// we need to assert user data onto the pin (with OUT) and sometimes
// assert constant values (start/stop bit)
sm_config_set_out_pins(&c, pin_tx, 1);
sm_config_set_sideset_pins(&c, pin_tx);
// We only need TX, so get an 8-deep FIFO!
sm_config_set_fifo_join(&c, PIO_FIFO_JOIN_TX);
// SM transmits 1 bit per 8 execution cycles.
float div = (float)clock_get_hz(clk_sys) / (8 * baud);
sm_config_set_clkdiv(&c, div);
pio_sm_init(pio, sm, offset, &c);
pio_sm_set_enabled(pio, sm, true);
}
static inline void uart_tx_program_putc(PIO pio, uint sm, char c) {
pio_sm_put_blocking(pio, sm, (uint32_t)c);
}
static inline void uart_tx_program_puts(PIO pio, uint sm, const char *s) {
while (*s)
uart_tx_program_putc(pio, sm, *s++);
}
%}