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

54
SOFTWARE/CMakeLists.txt Normal file
View File

@@ -0,0 +1,54 @@
cmake_minimum_required(VERSION 3.25.1)
include(pico_sdk_import.cmake)
include(pico_extras_import.cmake)
project(Danger-alarm CXX C ASM)
set(CMAKE_C_STANDARD 11)
set(CMAKE_CXX_STANDARD 17)
pico_sdk_init()
add_subdirectory(Lib/pico-onewire)
add_executable(
Danger-alarm
)
pico_generate_pio_header(Danger-alarm ${CMAKE_CURRENT_LIST_DIR}/Source/uart_tx.pio)
pico_generate_pio_header(Danger-alarm ${CMAKE_CURRENT_LIST_DIR}/Source/uart_rx.pio)
target_sources(Danger-alarm PRIVATE
lib/radio-switch.cc
${CMAKE_CURRENT_LIST_DIR}/Source/common.c
${CMAKE_CURRENT_LIST_DIR}/Source/MAIN.cpp
${CMAKE_CURRENT_LIST_DIR}/Source/DTH11.cpp
${CMAKE_CURRENT_LIST_DIR}/Source/HC-12.cpp
${CMAKE_CURRENT_LIST_DIR}/Source/ZC13.cpp
)
pico_enable_stdio_uart(Danger-alarm 1)
pico_enable_stdio_usb(Danger-alarm 1)
pico_add_extra_outputs(Danger-alarm)
target_include_directories(Danger-alarm PRIVATE
${CMAKE_CURRENT_LIST_DIR}
${CMAKE_CURRENT_LIST_DIR}/Source
${CMAKE_CURRENT_LIST_DIR}/lib
)
target_link_libraries(
Danger-alarm
pico_stdlib
pico_runtime
pico_multicore
pico_one_wire
hardware_sleep
hardware_rtc
hardware_i2c
hardware_uart
hardware_pwm
hardware_adc
hardware_pio
pico_lwip
pico_cyw43_arch
pico_cyw43_arch_lwip_poll
)

View File

@@ -0,0 +1,728 @@
/*
RCSwitch - Arduino libary for remote control outlet switches
Copyright (c) 2011 Suat Özgür. All right reserved.
Contributors:
- Andre Koehler / info(at)tomate-online(dot)de
- Gordeev Andrey Vladimirovich / gordeev(at)openpyro(dot)com
- Skineffect / http://forum.ardumote.com/viewtopic.php?f=2&t=46
- Dominik Fischer / dom_fischer(at)web(dot)de
- Frank Oltmanns / <first name>.<last name>(at)gmail(dot)com
- Andreas Steinel / A.<lastname>(at)gmail(dot)com
- Max Horn / max(at)quendi(dot)de
- Robert ter Vehn / <first name>.<last name>(at)gmail(dot)com
- Johann Richard / <first name>.<last name>(at)gmail(dot)com
- Vlad Gheorghe / <first name>.<last name>(at)gmail(dot)com https://github.com/vgheo
- Matias Cuenca-Acuna
Project home: https://github.com/sui77/rc-switch/
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
#include "radio-switch.h"
#include "pico/stdlib.h"
#include "hardware/gpio.h"
#include "hardware/uart.h"
#ifdef _PICO_STDLIB_H
#define HIGH 1
#define LOW 0
#endif
#define PROGMEM
#define memcpy_P(dest, src, num) memcpy((dest), (src), (num))
#if defined(ESP8266)
// interrupt handler and related code must be in RAM on ESP8266,
// according to issue #46.
#define RECEIVE_ATTR ICACHE_RAM_ATTR
#define VAR_ISR_ATTR
#elif defined(ESP32)
#define RECEIVE_ATTR IRAM_ATTR
#define VAR_ISR_ATTR DRAM_ATTR
#else
#define RECEIVE_ATTR
#define VAR_ISR_ATTR
#endif
/* Format for protocol definitions:
* {pulselength, Sync bit, "0" bit, "1" bit, invertedSignal}
*
* pulselength: pulse length in microseconds, e.g. 350
* Sync bit: {1, 31} means 1 high pulse and 31 low pulses
* (perceived as a 31*pulselength long pulse, total length of sync bit is
* 32*pulselength microseconds), i.e:
* _
* | |_______________________________ (don't count the vertical bars)
* "0" bit: waveform for a data bit of value "0", {1, 3} means 1 high pulse
* and 3 low pulses, total length (1+3)*pulselength, i.e:
* _
* | |___
* "1" bit: waveform for a data bit of value "1", e.g. {3,1}:
* ___
* | |_
*
* These are combined to form Tri-State bits when sending or receiving codes.
*/
#if defined(ESP8266) || defined(ESP32)
static const VAR_ISR_ATTR RCSwitch::Protocol proto[] = {
#else
static const RCSwitch::Protocol PROGMEM proto[] = {
#endif
{ 350, { 1, 31 }, { 1, 3 }, { 3, 1 }, false }, // protocol 1
{ 650, { 1, 10 }, { 1, 2 }, { 2, 1 }, false }, // protocol 2
{ 100, { 30, 71 }, { 4, 11 }, { 9, 6 }, false }, // protocol 3
{ 380, { 1, 6 }, { 1, 3 }, { 3, 1 }, false }, // protocol 4
{ 500, { 6, 14 }, { 1, 2 }, { 2, 1 }, false }, // protocol 5
{ 450, { 23, 1 }, { 1, 2 }, { 2, 1 }, true }, // protocol 6 (HT6P20B)
{ 150, { 2, 62 }, { 1, 6 }, { 6, 1 }, false }, // protocol 7 (HS2303-PT, i. e. used in AUKEY Remote)
{ 200, { 3, 130}, { 7, 16 }, { 3, 16}, false}, // protocol 8 Conrad RS-200 RX
{ 200, { 130, 7 }, { 16, 7 }, { 16, 3 }, true}, // protocol 9 Conrad RS-200 TX
{ 365, { 18, 1 }, { 3, 1 }, { 1, 3 }, true }, // protocol 10 (1ByOne Doorbell)
{ 270, { 36, 1 }, { 1, 2 }, { 2, 1 }, true }, // protocol 11 (HT12E)
{ 320, { 36, 1 }, { 1, 2 }, { 2, 1 }, true } // protocol 12 (SM5212)
};
void RCSwitch::gpio_callback(unsigned int gpio, uint32_t events) {
RCSwitch::handleInterrupt();
}
enum {
numProto = sizeof(proto) / sizeof(proto[0])
};
#if not defined( RCSwitchDisableReceiving )
volatile unsigned long RCSwitch::nReceivedValue = 0;
volatile unsigned int RCSwitch::nReceivedBitlength = 0;
volatile unsigned int RCSwitch::nReceivedDelay = 0;
volatile unsigned int RCSwitch::nReceivedProtocol = 0;
int RCSwitch::nReceiveTolerance = 60;
const unsigned int VAR_ISR_ATTR RCSwitch::nSeparationLimit = 4300;
// separationLimit: minimum microseconds between received codes, closer codes are ignored.
// according to discussion on issue #14 it might be more suitable to set the separation
// limit to the same time as the 'low' part of the sync signal for the current protocol.
unsigned int RCSwitch::timings[RCSWITCH_MAX_CHANGES];
#endif
RCSwitch::RCSwitch() {
this->nTransmitterPin = -1;
this->setRepeatTransmit(10);
this->setProtocol(1);
#if not defined( RCSwitchDisableReceiving )
this->nReceiverInterrupt = -1;
this->setReceiveTolerance(60);
RCSwitch::nReceivedValue = 0;
#endif
}
/**
* Sets the protocol to send.
*/
void RCSwitch::setProtocol(Protocol protocol) {
this->protocol = protocol;
}
/**
* Sets the protocol to send, from a list of predefined protocols
*/
void RCSwitch::setProtocol(int nProtocol) {
if (nProtocol < 1 || nProtocol > numProto) {
nProtocol = 1; // TODO: trigger an error, e.g. "bad protocol" ???
}
#if defined(ESP8266) || defined(ESP32)
this->protocol = proto[nProtocol-1];
#else
memcpy_P(&this->protocol, &proto[nProtocol-1], sizeof(Protocol));
#endif
}
/**
* Sets the protocol to send with pulse length in microseconds.
*/
void RCSwitch::setProtocol(int nProtocol, int nPulseLength) {
setProtocol(nProtocol);
this->setPulseLength(nPulseLength);
}
/**
* Sets pulse length in microseconds
*/
void RCSwitch::setPulseLength(int nPulseLength) {
this->protocol.pulseLength = nPulseLength;
}
/**
* Sets Repeat Transmits
*/
void RCSwitch::setRepeatTransmit(int nRepeatTransmit) {
this->nRepeatTransmit = nRepeatTransmit;
}
/**
* Set Receiving Tolerance
*/
#if not defined( RCSwitchDisableReceiving )
void RCSwitch::setReceiveTolerance(int nPercent) {
RCSwitch::nReceiveTolerance = nPercent;
}
#endif
/**
* Enable transmissions
*
* @param nTransmitterPin Arduino Pin to which the sender is connected to
*/
void RCSwitch::enableTransmit(int nTransmitterPin) {
this->nTransmitterPin = nTransmitterPin;
// pinMode(this->nTransmitterPin, OUTPUT);
gpio_set_dir(this->nTransmitterPin,GPIO_OUT);
}
/**
* Disable transmissions
*/
void RCSwitch::disableTransmit() {
this->nTransmitterPin = -1;
}
/**
* Switch a remote switch on (Type D REV)
*
* @param sGroup Code of the switch group (A,B,C,D)
* @param nDevice Number of the switch itself (1..3)
*/
void RCSwitch::switchOn(char sGroup, int nDevice) {
this->sendTriState( this->getCodeWordD(sGroup, nDevice, true) );
}
/**
* Switch a remote switch off (Type D REV)
*
* @param sGroup Code of the switch group (A,B,C,D)
* @param nDevice Number of the switch itself (1..3)
*/
void RCSwitch::switchOff(char sGroup, int nDevice) {
this->sendTriState( this->getCodeWordD(sGroup, nDevice, false) );
}
/**
* Switch a remote switch on (Type C Intertechno)
*
* @param sFamily Familycode (a..f)
* @param nGroup Number of group (1..4)
* @param nDevice Number of device (1..4)
*/
void RCSwitch::switchOn(char sFamily, int nGroup, int nDevice) {
this->sendTriState( this->getCodeWordC(sFamily, nGroup, nDevice, true) );
}
/**
* Switch a remote switch off (Type C Intertechno)
*
* @param sFamily Familycode (a..f)
* @param nGroup Number of group (1..4)
* @param nDevice Number of device (1..4)
*/
void RCSwitch::switchOff(char sFamily, int nGroup, int nDevice) {
this->sendTriState( this->getCodeWordC(sFamily, nGroup, nDevice, false) );
}
/**
* Switch a remote switch on (Type B with two rotary/sliding switches)
*
* @param nAddressCode Number of the switch group (1..4)
* @param nChannelCode Number of the switch itself (1..4)
*/
void RCSwitch::switchOn(int nAddressCode, int nChannelCode) {
this->sendTriState( this->getCodeWordB(nAddressCode, nChannelCode, true) );
}
/**
* Switch a remote switch off (Type B with two rotary/sliding switches)
*
* @param nAddressCode Number of the switch group (1..4)
* @param nChannelCode Number of the switch itself (1..4)
*/
void RCSwitch::switchOff(int nAddressCode, int nChannelCode) {
this->sendTriState( this->getCodeWordB(nAddressCode, nChannelCode, false) );
}
/**
* Deprecated, use switchOn(const char* sGroup, const char* sDevice) instead!
* Switch a remote switch on (Type A with 10 pole DIP switches)
*
* @param sGroup Code of the switch group (refers to DIP switches 1..5 where "1" = on and "0" = off, if all DIP switches are on it's "11111")
* @param nChannelCode Number of the switch itself (1..5)
*/
void RCSwitch::switchOn(const char* sGroup, int nChannel) {
const char* code[6] = { "00000", "10000", "01000", "00100", "00010", "00001" };
this->switchOn(sGroup, code[nChannel]);
}
/**
* Deprecated, use switchOff(const char* sGroup, const char* sDevice) instead!
* Switch a remote switch off (Type A with 10 pole DIP switches)
*
* @param sGroup Code of the switch group (refers to DIP switches 1..5 where "1" = on and "0" = off, if all DIP switches are on it's "11111")
* @param nChannelCode Number of the switch itself (1..5)
*/
void RCSwitch::switchOff(const char* sGroup, int nChannel) {
const char* code[6] = { "00000", "10000", "01000", "00100", "00010", "00001" };
this->switchOff(sGroup, code[nChannel]);
}
/**
* Switch a remote switch on (Type A with 10 pole DIP switches)
*
* @param sGroup Code of the switch group (refers to DIP switches 1..5 where "1" = on and "0" = off, if all DIP switches are on it's "11111")
* @param sDevice Code of the switch device (refers to DIP switches 6..10 (A..E) where "1" = on and "0" = off, if all DIP switches are on it's "11111")
*/
void RCSwitch::switchOn(const char* sGroup, const char* sDevice) {
this->sendTriState( this->getCodeWordA(sGroup, sDevice, true) );
}
/**
* Switch a remote switch off (Type A with 10 pole DIP switches)
*
* @param sGroup Code of the switch group (refers to DIP switches 1..5 where "1" = on and "0" = off, if all DIP switches are on it's "11111")
* @param sDevice Code of the switch device (refers to DIP switches 6..10 (A..E) where "1" = on and "0" = off, if all DIP switches are on it's "11111")
*/
void RCSwitch::switchOff(const char* sGroup, const char* sDevice) {
this->sendTriState( this->getCodeWordA(sGroup, sDevice, false) );
}
/**
* Returns a char[13], representing the code word to be send.
*
*/
char* RCSwitch::getCodeWordA(const char* sGroup, const char* sDevice, bool bStatus) {
static char sReturn[13];
int nReturnPos = 0;
for (int i = 0; i < 5; i++) {
sReturn[nReturnPos++] = (sGroup[i] == '0') ? 'F' : '0';
}
for (int i = 0; i < 5; i++) {
sReturn[nReturnPos++] = (sDevice[i] == '0') ? 'F' : '0';
}
sReturn[nReturnPos++] = bStatus ? '0' : 'F';
sReturn[nReturnPos++] = bStatus ? 'F' : '0';
sReturn[nReturnPos] = '\0';
return sReturn;
}
/**
* Encoding for type B switches with two rotary/sliding switches.
*
* The code word is a tristate word and with following bit pattern:
*
* +-----------------------------+-----------------------------+----------+------------+
* | 4 bits address | 4 bits address | 3 bits | 1 bit |
* | switch group | switch number | not used | on / off |
* | 1=0FFF 2=F0FF 3=FF0F 4=FFF0 | 1=0FFF 2=F0FF 3=FF0F 4=FFF0 | FFF | on=F off=0 |
* +-----------------------------+-----------------------------+----------+------------+
*
* @param nAddressCode Number of the switch group (1..4)
* @param nChannelCode Number of the switch itself (1..4)
* @param bStatus Whether to switch on (true) or off (false)
*
* @return char[13], representing a tristate code word of length 12
*/
char* RCSwitch::getCodeWordB(int nAddressCode, int nChannelCode, bool bStatus) {
static char sReturn[13];
int nReturnPos = 0;
if (nAddressCode < 1 || nAddressCode > 4 || nChannelCode < 1 || nChannelCode > 4) {
return 0;
}
for (int i = 1; i <= 4; i++) {
sReturn[nReturnPos++] = (nAddressCode == i) ? '0' : 'F';
}
for (int i = 1; i <= 4; i++) {
sReturn[nReturnPos++] = (nChannelCode == i) ? '0' : 'F';
}
sReturn[nReturnPos++] = 'F';
sReturn[nReturnPos++] = 'F';
sReturn[nReturnPos++] = 'F';
sReturn[nReturnPos++] = bStatus ? 'F' : '0';
sReturn[nReturnPos] = '\0';
return sReturn;
}
/**
* Like getCodeWord (Type C = Intertechno)
*/
char* RCSwitch::getCodeWordC(char sFamily, int nGroup, int nDevice, bool bStatus) {
static char sReturn[13];
int nReturnPos = 0;
int nFamily = (int)sFamily - 'a';
if ( nFamily < 0 || nFamily > 15 || nGroup < 1 || nGroup > 4 || nDevice < 1 || nDevice > 4) {
return 0;
}
// encode the family into four bits
sReturn[nReturnPos++] = (nFamily & 1) ? 'F' : '0';
sReturn[nReturnPos++] = (nFamily & 2) ? 'F' : '0';
sReturn[nReturnPos++] = (nFamily & 4) ? 'F' : '0';
sReturn[nReturnPos++] = (nFamily & 8) ? 'F' : '0';
// encode the device and group
sReturn[nReturnPos++] = ((nDevice-1) & 1) ? 'F' : '0';
sReturn[nReturnPos++] = ((nDevice-1) & 2) ? 'F' : '0';
sReturn[nReturnPos++] = ((nGroup-1) & 1) ? 'F' : '0';
sReturn[nReturnPos++] = ((nGroup-1) & 2) ? 'F' : '0';
// encode the status code
sReturn[nReturnPos++] = '0';
sReturn[nReturnPos++] = 'F';
sReturn[nReturnPos++] = 'F';
sReturn[nReturnPos++] = bStatus ? 'F' : '0';
sReturn[nReturnPos] = '\0';
return sReturn;
}
/**
* Encoding for the REV Switch Type
*
* The code word is a tristate word and with following bit pattern:
*
* +-----------------------------+-------------------+----------+--------------+
* | 4 bits address | 3 bits address | 3 bits | 2 bits |
* | switch group | device number | not used | on / off |
* | A=1FFF B=F1FF C=FF1F D=FFF1 | 1=0FF 2=F0F 3=FF0 | 000 | on=10 off=01 |
* +-----------------------------+-------------------+----------+--------------+
*
* Source: http://www.the-intruder.net/funksteckdosen-von-rev-uber-arduino-ansteuern/
*
* @param sGroup Name of the switch group (A..D, resp. a..d)
* @param nDevice Number of the switch itself (1..3)
* @param bStatus Whether to switch on (true) or off (false)
*
* @return char[13], representing a tristate code word of length 12
*/
char* RCSwitch::getCodeWordD(char sGroup, int nDevice, bool bStatus) {
static char sReturn[13];
int nReturnPos = 0;
// sGroup must be one of the letters in "abcdABCD"
int nGroup = (sGroup >= 'a') ? (int)sGroup - 'a' : (int)sGroup - 'A';
if ( nGroup < 0 || nGroup > 3 || nDevice < 1 || nDevice > 3) {
return 0;
}
for (int i = 0; i < 4; i++) {
sReturn[nReturnPos++] = (nGroup == i) ? '1' : 'F';
}
for (int i = 1; i <= 3; i++) {
sReturn[nReturnPos++] = (nDevice == i) ? '1' : 'F';
}
sReturn[nReturnPos++] = '0';
sReturn[nReturnPos++] = '0';
sReturn[nReturnPos++] = '0';
sReturn[nReturnPos++] = bStatus ? '1' : '0';
sReturn[nReturnPos++] = bStatus ? '0' : '1';
sReturn[nReturnPos] = '\0';
return sReturn;
}
/**
* @param sCodeWord a tristate code word consisting of the letter 0, 1, F
*/
void RCSwitch::sendTriState(const char* sCodeWord) {
// turn the tristate code word into the corresponding bit pattern, then send it
unsigned long code = 0;
unsigned int length = 0;
for (const char* p = sCodeWord; *p; p++) {
code <<= 2L;
switch (*p) {
case '0':
// bit pattern 00
break;
case 'F':
// bit pattern 01
code |= 1L;
break;
case '1':
// bit pattern 11
code |= 3L;
break;
}
length += 2;
}
this->send(code, length);
}
/**
* @param sCodeWord a binary code word consisting of the letter 0, 1
*/
void RCSwitch::send(const char* sCodeWord) {
// turn the tristate code word into the corresponding bit pattern, then send it
unsigned long code = 0;
unsigned int length = 0;
for (const char* p = sCodeWord; *p; p++) {
code <<= 1L;
if (*p != '0')
code |= 1L;
length++;
}
this->send(code, length);
}
/**
* Transmit the first 'length' bits of the integer 'code'. The
* bits are sent from MSB to LSB, i.e., first the bit at position length-1,
* then the bit at position length-2, and so on, till finally the bit at position 0.
*/
void RCSwitch::send(unsigned long code, unsigned int length) {
if (this->nTransmitterPin == -1)
return;
#if not defined( RCSwitchDisableReceiving )
// make sure the receiver is disabled while we transmit
int nReceiverInterrupt_backup = nReceiverInterrupt;
if (nReceiverInterrupt_backup != -1) {
this->disableReceive();
}
#endif
for (int nRepeat = 0; nRepeat < nRepeatTransmit; nRepeat++) {
for (int i = length-1; i >= 0; i--) {
if (code & (1L << i))
this->transmit(protocol.one);
else
this->transmit(protocol.zero);
}
this->transmit(protocol.syncFactor);
}
// Disable transmit after sending (i.e., for inverted protocols)
// digitalWrite(this->nTransmitterPin, LOW);
gpio_put(this->nTransmitterPin, LOW);
#if not defined( RCSwitchDisableReceiving )
// enable receiver again if we just disabled it
if (nReceiverInterrupt_backup != -1) {
this->enableReceive(nReceiverInterrupt_backup);
}
#endif
}
/**
* Transmit a single high-low pulse.
*/
void RCSwitch::transmit(HighLow pulses) {
uint8_t firstLogicLevel = (this->protocol.invertedSignal) ? LOW : HIGH;
uint8_t secondLogicLevel = (this->protocol.invertedSignal) ? HIGH : LOW;
// digitalWrite(this->nTransmitterPin, firstLogicLevel);
// delayMicroseconds( this->protocol.pulseLength * pulses.high);
// digitalWrite(this->nTransmitterPin, secondLogicLevel);
// delayMicroseconds( this->protocol.pulseLength * pulses.low);
gpio_put(this->nTransmitterPin, firstLogicLevel);
sleep_us(this->protocol.pulseLength * pulses.high);
gpio_put(this->nTransmitterPin, secondLogicLevel);
sleep_us(this->protocol.pulseLength * pulses.low);
}
#if not defined( RCSwitchDisableReceiving )
/**
* Enable receiving data
*/
void RCSwitch::enableReceive(int interrupt) {
this->nReceiverInterrupt = interrupt;
this->enableReceive();
}
void RCSwitch::enableReceive() {
if (this->nReceiverInterrupt != -1) {
RCSwitch::nReceivedValue = 0;
RCSwitch::nReceivedBitlength = 0;
gpio_set_irq_enabled_with_callback(this->nReceiverInterrupt, GPIO_IRQ_EDGE_RISE | GPIO_IRQ_EDGE_FALL, true, &gpio_callback);
// attachInterrupt(this->nReceiverInterrupt, handleInterrupt, CHANGE);
}
}
/**
* Disable receiving data
*/
void RCSwitch::disableReceive() {
#if not defined(RaspberryPi) // Arduino
// detachInterrupt(this->nReceiverInterrupt);
#endif // For Raspberry Pi (wiringPi) you can't unregister the ISR
this->nReceiverInterrupt = -1;
}
bool RCSwitch::available() {
return RCSwitch::nReceivedValue != 0;
}
void RCSwitch::resetAvailable() {
RCSwitch::nReceivedValue = 0;
}
unsigned long RCSwitch::getReceivedValue() {
return RCSwitch::nReceivedValue;
}
unsigned int RCSwitch::getReceivedBitlength() {
return RCSwitch::nReceivedBitlength;
}
unsigned int RCSwitch::getReceivedDelay() {
return RCSwitch::nReceivedDelay;
}
unsigned int RCSwitch::getReceivedProtocol() {
return RCSwitch::nReceivedProtocol;
}
unsigned int* RCSwitch::getReceivedRawdata() {
return RCSwitch::timings;
}
/* helper function for the receiveProtocol method */
static inline unsigned int diff(int A, int B) {
return abs(A - B);
}
/**
*
*/
bool RECEIVE_ATTR RCSwitch::receiveProtocol(const int p, unsigned int changeCount) {
#if defined(ESP8266) || defined(ESP32)
const Protocol &pro = proto[p-1];
#else
Protocol pro;
memcpy_P(&pro, &proto[p-1], sizeof(Protocol));
#endif
unsigned long code = 0;
//Assuming the longer pulse length is the pulse captured in timings[0]
const unsigned int syncLengthInPulses = ((pro.syncFactor.low) > (pro.syncFactor.high)) ? (pro.syncFactor.low) : (pro.syncFactor.high);
const unsigned int delay = RCSwitch::timings[0] / syncLengthInPulses;
const unsigned int delayTolerance = delay * RCSwitch::nReceiveTolerance / 100;
/* For protocols that start low, the sync period looks like
* _________
* _____________| |XXXXXXXXXXXX|
*
* |--1st dur--|-2nd dur-|-Start data-|
*
* The 3rd saved duration starts the data.
*
* For protocols that start high, the sync period looks like
*
* ______________
* | |____________|XXXXXXXXXXXXX|
*
* |-filtered out-|--1st dur--|--Start data--|
*
* The 2nd saved duration starts the data
*/
const unsigned int firstDataTiming = (pro.invertedSignal) ? (2) : (1);
for (unsigned int i = firstDataTiming; i < changeCount - 1; i += 2) {
code <<= 1;
if (diff(RCSwitch::timings[i], delay * pro.zero.high) < delayTolerance &&
diff(RCSwitch::timings[i + 1], delay * pro.zero.low) < delayTolerance) {
// zero
} else if (diff(RCSwitch::timings[i], delay * pro.one.high) < delayTolerance &&
diff(RCSwitch::timings[i + 1], delay * pro.one.low) < delayTolerance) {
// one
code |= 1;
} else {
// Failed
return false;
}
}
if (changeCount > 7) { // ignore very short transmissions: no device sends them, so this must be noise
RCSwitch::nReceivedValue = code;
RCSwitch::nReceivedBitlength = (changeCount - 1) / 2;
RCSwitch::nReceivedDelay = delay;
RCSwitch::nReceivedProtocol = p;
return true;
}
return false;
}
void RECEIVE_ATTR RCSwitch::handleInterrupt() {
static unsigned int changeCount = 0;
static unsigned long lastTime = 0;
static unsigned int repeatCount = 0;
// const long time = micros();
const long time = to_us_since_boot(get_absolute_time());
const unsigned int duration = time - lastTime;
if (duration > RCSwitch::nSeparationLimit) {
// A long stretch without signal level change occurred. This could
// be the gap between two transmission.
if ((repeatCount==0) || (diff(duration, RCSwitch::timings[0]) < 200)) {
// This long signal is close in length to the long signal which
// started the previously recorded timings; this suggests that
// it may indeed by a a gap between two transmissions (we assume
// here that a sender will send the signal multiple times,
// with roughly the same gap between them).
repeatCount++;
if (repeatCount == 2) {
for(unsigned int i = 1; i <= numProto; i++) {
if (receiveProtocol(i, changeCount)) {
// receive succeeded for protocol i
break;
}
}
repeatCount = 0;
}
}
changeCount = 0;
}
// detect overflow
if (changeCount >= RCSWITCH_MAX_CHANGES) {
changeCount = 0;
repeatCount = 0;
}
RCSwitch::timings[changeCount++] = duration;
lastTime = time;
}
#endif

170
SOFTWARE/Lib/radio-switch.h Normal file
View File

@@ -0,0 +1,170 @@
/*
RCSwitch - Arduino libary for remote control outlet switches
Copyright (c) 2011 Suat Özgür. All right reserved.
Contributors:
- Andre Koehler / info(at)tomate-online(dot)de
- Gordeev Andrey Vladimirovich / gordeev(at)openpyro(dot)com
- Skineffect / http://forum.ardumote.com/viewtopic.php?f=2&t=46
- Dominik Fischer / dom_fischer(at)web(dot)de
- Frank Oltmanns / <first name>.<last name>(at)gmail(dot)com
- Max Horn / max(at)quendi(dot)de
- Robert ter Vehn / <first name>.<last name>(at)gmail(dot)com
Project home: https://github.com/sui77/rc-switch/
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
#ifndef _RCSwitch_h
#define _RCSwitch_h
// #define RaspberryPi
// Include libraries for RPi:
#include <string.h> /* memcpy */
#include <stdlib.h> /* abs */
#include <stdint.h>
// Number of maximum high/Low changes per packet.
// We can handle up to (unsigned long) => 32 bit * 2 H/L changes per bit + 2 for sync
#define RCSWITCH_MAX_CHANGES 67
class RCSwitch {
public:
RCSwitch();
void switchOn(int nGroupNumber, int nSwitchNumber);
void switchOff(int nGroupNumber, int nSwitchNumber);
void switchOn(const char* sGroup, int nSwitchNumber);
void switchOff(const char* sGroup, int nSwitchNumber);
void switchOn(char sFamily, int nGroup, int nDevice);
void switchOff(char sFamily, int nGroup, int nDevice);
void switchOn(const char* sGroup, const char* sDevice);
void switchOff(const char* sGroup, const char* sDevice);
void switchOn(char sGroup, int nDevice);
void switchOff(char sGroup, int nDevice);
void sendTriState(const char* sCodeWord);
void send(unsigned long code, unsigned int length);
void send(const char* sCodeWord);
#if not defined( RCSwitchDisableReceiving )
void enableReceive(int interrupt);
void enableReceive();
void disableReceive();
bool available();
void resetAvailable();
unsigned long getReceivedValue();
unsigned int getReceivedBitlength();
unsigned int getReceivedDelay();
unsigned int getReceivedProtocol();
unsigned int* getReceivedRawdata();
#endif
void enableTransmit(int nTransmitterPin);
void disableTransmit();
void setPulseLength(int nPulseLength);
void setRepeatTransmit(int nRepeatTransmit);
#if not defined( RCSwitchDisableReceiving )
void setReceiveTolerance(int nPercent);
#endif
/**
* Description of a single pule, which consists of a high signal
* whose duration is "high" times the base pulse length, followed
* by a low signal lasting "low" times the base pulse length.
* Thus, the pulse overall lasts (high+low)*pulseLength
*/
struct HighLow {
uint8_t high;
uint8_t low;
};
/**
* A "protocol" describes how zero and one bits are encoded into high/low
* pulses.
*/
struct Protocol {
/** base pulse length in microseconds, e.g. 350 */
uint16_t pulseLength;
HighLow syncFactor;
HighLow zero;
HighLow one;
/**
* If true, interchange high and low logic levels in all transmissions.
*
* By default, RCSwitch assumes that any signals it sends or receives
* can be broken down into pulses which start with a high signal level,
* followed by a a low signal level. This is e.g. the case for the
* popular PT 2260 encoder chip, and thus many switches out there.
*
* But some devices do it the other way around, and start with a low
* signal level, followed by a high signal level, e.g. the HT6P20B. To
* accommodate this, one can set invertedSignal to true, which causes
* RCSwitch to change how it interprets any HighLow struct FOO: It will
* then assume transmissions start with a low signal lasting
* FOO.high*pulseLength microseconds, followed by a high signal lasting
* FOO.low*pulseLength microseconds.
*/
bool invertedSignal;
};
void setProtocol(Protocol protocol);
void setProtocol(int nProtocol);
void setProtocol(int nProtocol, int nPulseLength);
private:
static void gpio_callback(unsigned int gpio, uint32_t events);
char* getCodeWordA(const char* sGroup, const char* sDevice, bool bStatus);
char* getCodeWordB(int nGroupNumber, int nSwitchNumber, bool bStatus);
char* getCodeWordC(char sFamily, int nGroup, int nDevice, bool bStatus);
char* getCodeWordD(char group, int nDevice, bool bStatus);
void transmit(HighLow pulses);
#if not defined( RCSwitchDisableReceiving )
static void handleInterrupt();
static bool receiveProtocol(const int p, unsigned int changeCount);
int nReceiverInterrupt;
#endif
int nTransmitterPin;
int nRepeatTransmit;
Protocol protocol;
#if not defined( RCSwitchDisableReceiving )
static int nReceiveTolerance;
volatile static unsigned long nReceivedValue;
volatile static unsigned int nReceivedBitlength;
volatile static unsigned int nReceivedDelay;
volatile static unsigned int nReceivedProtocol;
const static unsigned int nSeparationLimit;
/*
* timings[0] contains sync timing, followed by a number of bits
*/
static unsigned int timings[RCSWITCH_MAX_CHANGES];
#endif
};
#endif

View File

@@ -0,0 +1,21 @@
CROSS_COMPILE ?=
CC = $(CROSS_COMPILE)gcc
STRIP := $(CROSS_COMPILE)strip
AR := $(CROSS_COMPILE)ar
CFLAGS += -g -Wall -Os
LDFLAGS += -lwiringPi
MYSQL_LIB := $(shell mysql_config --libs)
MYSQL_CFLAGS := $(shell mysql_config --cflags)
OBJ = hc-12
all: hc-12
hc-12: hc-12.o ../libconf/libconf.o mysql.o
$(CC) $(CFLAGS) $(MYSQL_CFLAGS) -o $(OBJ) $^ $(MYSQL_LIB) $(LDFLAGS)
.c.o:
$(CC) $(CFLAGS) $(MYSQL_CFLAGS) -c $< $@
clean:
rm hc-12 hc-12.o ../libconf/libconf.o mysql.o

BIN
SOFTWARE/Server/hc-12/hc-12 Normal file

Binary file not shown.

View File

@@ -0,0 +1,385 @@
#include "hc-12.h"
#include "mysql.h"
pthread_mutex_t mutex;
void *pull_data_mysql(void *p)
{
char sql_insert[1024] = { 0 };
time_t current_time;
struct tm *time_info;
char timeString[20];
static int r = 0;
Thread *args = (Thread *) p;
if (args->data->co >= 0 && args->data->co2 >= 0 && args->data->ch4_ >= 0) {
time(&current_time); // 获取当前时间
time_info = localtime(&current_time); // 将时间转换为本地时间
strftime(timeString, sizeof(timeString), "%Y-%m-%d %H:%M:%S", time_info); // 格式化时间字符串
sprintf(sql_insert, "INSERT INTO %s (TIME, CO, CO2, CH4, TEMPERATURE, RP2040_TEMPERATURE) VALUES ('%s', '%.0fppm', '%.0fppm', '%.0fppm', '%.3f°C', '%.02f°C');",
args->conf->MYSQL_TABLES, timeString, args->data->co, args->data->co2, args->data->ch4_, args->data->ds18b20, args->data->rp2040);
printf("%s\n", sql_insert);
r = _mysql(sql_insert, args->conf->MYSQL_HOST, args->conf->MYSQL_PORT_, args->conf->MYSQL_USRT, args->conf->MYSQL_PASSWORD, args->conf->MYSQL_DB, args->conf->MYSQL_TABLES);
if (r == -1) {
perror("_mysql");
}
}
return NULL;
}
int send_mail(char *mail, const char *string, CONF *conf, DATA *data)
{
static char *buff;
const char *subject = "厨房危险(火灾)报警!!!";
buff = (char *)alloca(BUFFER * 10);
if (buff == NULL)
perror("out of memory.");
sprintf(buff, MAIL, mail, subject, string);
printf("%s\n", buff);
system(buff);
return 0;
}
void *createSharedMemory(int key, size_t size)
{
static int shm_id;
static void *shared_memory;
shm_id = shmget(key, size, IPC_CREAT | 0666);
if (shm_id == -1) {
perror("shmget");
exit(1);
}
shared_memory = shmat(shm_id, NULL, 0);
if (shared_memory == (void *)-1) {
perror("shmat");
exit(1);
}
return shared_memory;
}
void detachAndDeleteSharedMemory(int key, void *shared_memory)
{
static int shm_id;
if (shmdt(shared_memory) == -1) {
perror("shmdt");
exit(1);
}
shm_id = shmget(key, 0, 0);
if (shmctl(shm_id, IPC_RMID, NULL) == -1) {
perror("shmctl");
exit(1);
}
}
int loop(int fd, CONF *conf, DATA *DATA)
{
static char receivedString[BUFFER];
static int index = 0;
static int timing = 0;
DATA->ds18b20_shm = (int *)createSharedMemory(1, sizeof(int));
DATA->co_shm = (int *)createSharedMemory(2, sizeof(int));
DATA->co2_shm = (int *)createSharedMemory(3, sizeof(int));
*DATA->ds18b20_shm = 0;
*DATA->co_shm = 0;
*DATA->co2_shm = 0;
pid_t pid = fork();
if (pid < 0) {
perror("fork");
exit(1);
}
if (pid == 0) // 子进程
{
int conut = 0;
while (1) {
pthread_mutex_lock(&mutex); // 加锁
if (conut >= DATA->_time) {
*DATA->ds18b20_shm = 1;
*DATA->co_shm = 1;
*DATA->co2_shm = 1;
conut = 0;
}
pthread_mutex_unlock(&mutex); // 解锁
conut++;
sleep(1);
}
} else // 父进程
{
while (1) {
if (serialDataAvail(fd)) {
// 串口有数据可读
char data = serialGetchar(fd);
if (data != '\n') {
// 如果接收到的不是回车符,则添加到接收字符串中
receivedString[index] = data;
index++;
// 检查是否超出数组长度,如果超出则重置索引
if (index >= BUFFER) {
index = 0;
}
} else {
// 如果接收到回车符,则打印接收到的字符串,并清空接收字符串和索引
receivedString[index] = '\0'; // 添加字符串结束符
if (index > 0) {
// RP2040
if (strstr(receivedString, "Onboard")) {
if (2 == (sscanf(receivedString, "Onboard temperature %f°C %f°F\n", &(DATA->rp2040), &(DATA->rp2040_f)))) {
DATA->rp2040_num++;
printf("Onboard temperature %.02f°C %.02f°F\n", DATA->rp2040, DATA->rp2040_f);
}
}
// DS18B20
if (strstr(receivedString, "Temperature")) {
if (1 == (sscanf(receivedString, "Temperature: %f°C\n", &DATA->ds18b20))) {
printf("Temperature: %.3f°C\n", DATA->ds18b20);
if (DATA->ds18b20 >= atoi(conf->temperature)) {
DATA->ds18b20_num++;
printf("请注意室内温度%.3f°C超过%d次!\n", DATA->ds18b20, DATA->ds18b20_num);
if (DATA->ds18b20_num >= 3) {
// 第一次发送
if (DATA->ds18b20_1st == 1) {
DATA->ds18b20_1st = 0;
send_mail(conf->mail, receivedString, conf, DATA);
}
// 如果浓度持续一段时间, (降低发送频率, 若干秒后再次发送)
pthread_mutex_lock(&mutex); // 加锁
if (*DATA->ds18b20_shm == 1) {
send_mail(conf->mail, receivedString, conf, DATA);
*DATA->ds18b20_shm = 0;
}
pthread_mutex_unlock(&mutex); // 解锁
DATA->ds18b20_num = 0;
}
}
}
}
// CH4
if (strstr(receivedString, "CH4 Concentration")) {
if (1 == (sscanf(receivedString, "CH4 Concentration: %f\n", &DATA->ch4_))) {
printf("CH4 Concentration: %.0F ppm\n", DATA->ch4_);
}
}
// CO
if (strstr(receivedString, "CO")) {
if (1 == (sscanf(receivedString, "CO Concentration: %f ppm", &DATA->co))) {
printf("CO Concentration: %.2f ppm\n", DATA->co);
if (DATA->co >= atoi(conf->co)) {
DATA->co_num++;
printf("请注意室内CO浓度%.3f°C超过%d次!\n", DATA->co, DATA->co_num);
if (DATA->co_num >= 3) {
if (DATA->co_1st == 1) {
DATA->co_1st = 0;
send_mail(conf->mail, receivedString, conf, DATA);
}
pthread_mutex_lock(&mutex);
if (*DATA->co_shm == 1) {
send_mail(conf->mail, receivedString, conf, DATA);
*DATA->co_shm = 0;
}
pthread_mutex_unlock(&mutex);
DATA->co_num = 0;
}
}
}
}
// CO2
if (strstr(receivedString, "CO2")) {
if (1 == (sscanf(receivedString, "CO2 Concentration: %f ppm", &DATA->co2))) {
printf("CO2 Concentration: %.2f ppm\n", DATA->co2);
if (DATA->co2 >= atoi(conf->co2)) {
DATA->co2_num++;
printf("请注意室内CO2浓度%.3f°C超过%d次!\n", DATA->co2, DATA->co2_num);
if (DATA->co2_num >= 3) {
if (DATA->co2_1st == 1) {
DATA->co2_1st = 0;
send_mail(conf->mail, receivedString, conf, DATA);
}
pthread_mutex_lock(&mutex);
if (*DATA->co2_shm == 1) {
send_mail(conf->mail, receivedString, conf, DATA);
*DATA->co2_shm = 0;
}
pthread_mutex_unlock(&mutex);
DATA->co2_num = 0;
}
}
}
printf("\n");
}
}
receivedString[0] = '\0';
index = 0;
}
}
// 上传传感器数据到Mysql数据库
timing++;
if (0 == strcasecmp(conf->MYSQL_ON, "on")) {
if (timing >= (atoi(conf->PUSH_MYSQL_DATA_TIME) * 100)) {
Thread args = { conf, DATA };
pthread_t tid;
// 创建线程,并传递包含两个结构体的参数
if (pthread_create(&tid, NULL, pull_data_mysql, &args) != 0) {
perror("pthread_create");
return 1;
}
// 等待线程结束
pthread_join(tid, NULL);
timing = 0;
}
}
delay(10);
}
}
waitpid(pid, NULL, 0);
// 断开共享内存连接
detachAndDeleteSharedMemory(1, DATA->ds18b20_shm);
detachAndDeleteSharedMemory(2, DATA->co_shm);
detachAndDeleteSharedMemory(3, DATA->co2_shm);
return 0;
}
int redirect_stdout_to_file(int fd, const char *filename)
{
fd = open(filename, O_WRONLY | O_CREAT | O_APPEND, 0644);
if (fd == -1) {
perror("open");
return 1;
}
if (dup2(fd, STDOUT_FILENO) == -1) {
perror("dup2");
return 1;
}
return 0;
}
int main()
{
int logfd = -1;
int fd = -1;
if (nice(-20) == -1) {
perror("nice");
return 1;
}
if (0 != daemon(1, 1)) {
perror("daemon");
}
if ((fd = serialOpen("/dev/serial0", 9600)) < 0) {
printf("Unable to open device\n");
return 1;
} else {
printf("Serial port opened\n");
}
CONF *conf = (struct CONF *)malloc(sizeof(struct CONF));
memset(conf, 0, sizeof(struct CONF));
conf->mail = strdup(read_conf("hc-12.conf", "global", "MAIL"));
conf->temperature = strdup(read_conf("hc-12.conf", "global", "TEMPERATURE"));
conf->co = strdup(read_conf("hc-12.conf", "global", "CO"));
conf->co2 = strdup(read_conf("hc-12.conf", "global", "CO2"));
conf->MYSQL_ON = strdup(read_conf("hc-12.conf", "global", "MYSQL"));
if (0 == strcasecmp(conf->MYSQL_ON, "on")) {
conf->PUSH_MYSQL_DATA_TIME = strdup(read_conf("hc-12.conf", "global", "PUSH_MYSQL_DATA_TIME"));
conf->MYSQL_HOST = strdup(read_conf("hc-12.conf", "global", "MYSQL_HOST"));
conf->MYSQL_PORT_ = strdup(read_conf("hc-12.conf", "global", "MYSQL_PORT"));
conf->MYSQL_USRT = strdup(read_conf("hc-12.conf", "global", "MYSQL_USRT"));
conf->MYSQL_PASSWORD = strdup(read_conf("hc-12.conf", "global", "MYSQL_PASSWORD"));
conf->MYSQL_DB = strdup(read_conf("hc-12.conf", "global", "MYSQL_DB"));
conf->MYSQL_TABLES = strdup(read_conf("hc-12.conf", "global", "MYSQL_TABLES"));
}
DATA *data = (struct DATA *)malloc(sizeof(struct DATA));
memset(data, 0, sizeof(struct DATA));
data->ds18b20 = 0;
data->ch4 = 0;
data->rp2040 = 0;
data->rp2040_f = 0;
data->co = 0;
data->co2 = 0;
data->rp2040_num = 0;
data->ch4_num = 0;
data->ds18b20_num = 0;
data->co_num = 0;
data->co2_num = 0;
data->ds18b20_1st = 1;
data->ch4_1st = 1;
data->co_1st = 1;
data->co2_1st = 1;
data->_time = 180;
redirect_stdout_to_file(logfd, "hc-12.log");
pthread_mutex_init(&mutex, NULL); // 初始化互斥锁
loop(fd, conf, data);
pthread_mutex_destroy(&mutex); // 销毁互斥锁
free(conf->mail);
free(conf->temperature);
free(conf->co);
free(conf->co2);
free(conf->PUSH_MYSQL_DATA_TIME);
free(conf->MYSQL_HOST);
free(conf->MYSQL_PORT_);
free(conf->MYSQL_USRT);
free(conf->MYSQL_PASSWORD);
free(conf->MYSQL_DB);
free(conf->MYSQL_TABLES);
free(conf);
free(data);
close(fd);
close(logfd);
return 0;
}

View File

@@ -0,0 +1,16 @@
global {
MAIL="1605227279@qq.com"; // 发送邮箱
TEMPERATURE=60; // 温度上限(单位摄氏度)
CO=200; // CO 上限(单位ppm)
CO2=1500; // CO2 上限(单位ppm)
MYSQL="on"; // 传感器上传到数据库(非on 不上传)
PUSH_MYSQL_DATA_TIME=60; // 上传数据频率单位秒大于等于1
MYSQL_HOST="git.aixiao.me"; // 数据库地址
MYSQL_PORT="3306"; // 数据库端口
MYSQL_USRT="root"; // 数据库账号
MYSQL_PASSWORD="198"; // 数据库密码
MYSQL_DB="raspberrypi"; // 数据库名
MYSQL_TABLES="gas"; // 数据库表
}

View File

@@ -0,0 +1,79 @@
#ifndef HC_12_H
#define HC_12_H
#include <stdio.h>
#include <wiringPi.h>
#include <wiringSerial.h>
#include <unistd.h>
#include <time.h>
#include <string.h>
#include <stdlib.h>
#include <pthread.h>
#include <sys/shm.h>
#include <sys/wait.h>
#include <sys/types.h>
#include <sys/stat.h>
#include <fcntl.h>
#include "../libconf/libconf.h"
#define BUFFER 1024
#define MAIL "gomail -r \"%s\" -s \"%s\" -t \"%s\""
typedef struct CONF {
char *mail;
char *temperature;
char *co;
char *co2;
char *MYSQL_ON;
char *PUSH_MYSQL_DATA_TIME;
char *MYSQL_HOST;
char *MYSQL_PORT_;
char *MYSQL_USRT;
char *MYSQL_PASSWORD;
char *MYSQL_DB;
char *MYSQL_TABLES;
} CONF;
typedef struct DATA {
// 存储实际传感器数据
float ds18b20;
float ch4;
float rp2040;
float rp2040_f;
float co;
float co2;
float ch4_;
// 超过阈值次数
int ds18b20_num;
int ch4_num;
int rp2040_num;
int co_num;
int co2_num;
// 共享内存
int *ds18b20_shm;
int *co_shm;
int *co2_shm;
// 第一次发送Mail标志
int ds18b20_1st;
int ch4_1st;
int co_1st;
int co2_1st;
// 持续浓度时候,等待时间再发送Mail
int _time;
} DATA;
// 定义包含两个结构体的参数结构体
typedef struct {
CONF *conf;
DATA *data;
} Thread;
#endif

View File

@@ -0,0 +1,38 @@
#include "mysql.h"
int _mysql(char *sql, char *MYSQL_HOST, char *MYSQL_PORT_, char *MYSQL_USRT, char *MYSQL_PASSWORD, char *MYSQL_DB, char *MYSQL_TABLES)
{
static MYSQL mysql; // 静态变量,仅初始化一次
static char MYSQL_DB_[270] = { 0 };
if (!mysql_init(&mysql)) {
perror("mysql_init");
return -1;
}
int result = 0;
if (mysql_real_connect(&mysql, MYSQL_HOST, MYSQL_USRT, MYSQL_PASSWORD, "mysql", atoi(MYSQL_PORT_), NULL, 0)) {
if (0 != mysql_set_character_set(&mysql, "utf8")) {
perror("mysql_set_character_set");
result = -1;
goto shutdown;
}
sprintf(MYSQL_DB_, "use %s;", MYSQL_DB);
if (mysql_query(&mysql, MYSQL_DB_) || mysql_query(&mysql, sql)) {
fprintf(stderr, "Query execution failed: %s\n", mysql_error(&mysql));
result = -1;
} else {
// 执行成功的操作
}
} else {
fprintf(stderr, "Connect failed: %s\n", mysql_error(&mysql));
result = -1;
}
shutdown:
mysql_close(&mysql);
return result;
}

View File

@@ -0,0 +1,13 @@
#ifndef MYSQL_H
#define MYSQL_H
#include <stdio.h>
#include <string.h>
#include <stdlib.h>
#include <mysql.h>
#include <mysqld_error.h>
#include <errmsg.h>
extern int _mysql(char *sql, char *MYSQL_HOST, char *MYSQL_PORT_, char *MYSQL_USRT, char *MYSQL_PASSWORD, char *MYSQL_DB, char *MYSQL_TABLES);
#endif

View File

@@ -0,0 +1,35 @@
/*
Navicat Premium Data Transfer
Source Server : git.aixiao.me_3306
Source Server Type : MySQL
Source Server Version : 50740
Source Host : git.aixiao.me:3306
Source Schema : raspberrypi
Target Server Type : MySQL
Target Server Version : 50740
File Encoding : 65001
Date: 21/03/2024 10:57:51
*/
SET NAMES utf8mb4;
SET FOREIGN_KEY_CHECKS = 0;
-- ----------------------------
-- Table structure for gas
-- ----------------------------
DROP TABLE IF EXISTS `gas`;
CREATE TABLE `gas` (
`ID` int(11) NOT NULL AUTO_INCREMENT,
`TIME` datetime NULL DEFAULT NULL,
`CO` varchar(255) CHARACTER SET utf8 COLLATE utf8_croatian_ci NULL DEFAULT NULL,
`CO2` varchar(255) CHARACTER SET utf8 COLLATE utf8_croatian_ci NULL DEFAULT NULL,
`CH4` varchar(255) CHARACTER SET utf8 COLLATE utf8_croatian_ci NULL DEFAULT NULL,
`TEMPERATURE` varchar(255) CHARACTER SET utf8 COLLATE utf8_croatian_ci NULL DEFAULT NULL,
`RP2040_TEMPERATURE` varchar(255) CHARACTER SET utf8 COLLATE utf8_croatian_ci NULL DEFAULT NULL,
PRIMARY KEY (`ID`) USING BTREE
) ENGINE = InnoDB AUTO_INCREMENT = 1 CHARACTER SET = utf8 COLLATE = utf8_croatian_ci ROW_FORMAT = Dynamic;
SET FOREIGN_KEY_CHECKS = 1;

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++);
}
%}

View File

@@ -0,0 +1,62 @@
# This is a copy of <PICO_EXTRAS_PATH>/external/pico_extras_import.cmake
# This can be dropped into an external project to help locate pico-extras
# It should be include()ed prior to project()
if (DEFINED ENV{PICO_EXTRAS_PATH} AND (NOT PICO_EXTRAS_PATH))
set(PICO_EXTRAS_PATH $ENV{PICO_EXTRAS_PATH})
message("Using PICO_EXTRAS_PATH from environment ('${PICO_EXTRAS_PATH}')")
endif ()
if (DEFINED ENV{PICO_EXTRAS_FETCH_FROM_GIT} AND (NOT PICO_EXTRAS_FETCH_FROM_GIT))
set(PICO_EXTRAS_FETCH_FROM_GIT $ENV{PICO_EXTRAS_FETCH_FROM_GIT})
message("Using PICO_EXTRAS_FETCH_FROM_GIT from environment ('${PICO_EXTRAS_FETCH_FROM_GIT}')")
endif ()
if (DEFINED ENV{PICO_EXTRAS_FETCH_FROM_GIT_PATH} AND (NOT PICO_EXTRAS_FETCH_FROM_GIT_PATH))
set(PICO_EXTRAS_FETCH_FROM_GIT_PATH $ENV{PICO_EXTRAS_FETCH_FROM_GIT_PATH})
message("Using PICO_EXTRAS_FETCH_FROM_GIT_PATH from environment ('${PICO_EXTRAS_FETCH_FROM_GIT_PATH}')")
endif ()
if (NOT PICO_EXTRAS_PATH)
if (PICO_EXTRAS_FETCH_FROM_GIT)
include(FetchContent)
set(FETCHCONTENT_BASE_DIR_SAVE ${FETCHCONTENT_BASE_DIR})
if (PICO_EXTRAS_FETCH_FROM_GIT_PATH)
get_filename_component(FETCHCONTENT_BASE_DIR "${PICO_EXTRAS_FETCH_FROM_GIT_PATH}" REALPATH BASE_DIR "${CMAKE_SOURCE_DIR}")
endif ()
FetchContent_Declare(
PICO_EXTRAS
GIT_REPOSITORY https://github.com/raspberrypi/pico-extras
GIT_TAG master
)
if (NOT PICO_EXTRAS)
message("Downloading PICO EXTRAS")
FetchContent_Populate(PICO_EXTRAS)
set(PICO_EXTRAS_PATH ${PICO_EXTRAS_SOURCE_DIR})
endif ()
set(FETCHCONTENT_BASE_DIR ${FETCHCONTENT_BASE_DIR_SAVE})
else ()
if (PICO_SDK_PATH AND EXISTS "${PICO_SDK_PATH}/../pico-extras")
set(PICO_EXTRAS_PATH ${PICO_SDK_PATH}/../pico-extras)
message("Defaulting PICO_EXTRAS_PATH as sibling of PICO_SDK_PATH: ${PICO_EXTRAS_PATH}")
else()
message(FATAL_ERROR
"PICO EXTRAS location was not specified. Please set PICO_EXTRAS_PATH or set PICO_EXTRAS_FETCH_FROM_GIT to on to fetch from git."
)
endif()
endif ()
endif ()
set(PICO_EXTRAS_PATH "${PICO_EXTRAS_PATH}" CACHE PATH "Path to the PICO EXTRAS")
set(PICO_EXTRAS_FETCH_FROM_GIT "${PICO_EXTRAS_FETCH_FROM_GIT}" CACHE BOOL "Set to ON to fetch copy of PICO EXTRAS from git if not otherwise locatable")
set(PICO_EXTRAS_FETCH_FROM_GIT_PATH "${PICO_EXTRAS_FETCH_FROM_GIT_PATH}" CACHE FILEPATH "location to download EXTRAS")
get_filename_component(PICO_EXTRAS_PATH "${PICO_EXTRAS_PATH}" REALPATH BASE_DIR "${CMAKE_BINARY_DIR}")
if (NOT EXISTS ${PICO_EXTRAS_PATH})
message(FATAL_ERROR "Directory '${PICO_EXTRAS_PATH}' not found")
endif ()
set(PICO_EXTRAS_PATH ${PICO_EXTRAS_PATH} CACHE PATH "Path to the PICO EXTRAS" FORCE)
add_subdirectory(${PICO_EXTRAS_PATH} pico_extras)

View File

@@ -0,0 +1,62 @@
# This is a copy of <PICO_SDK_PATH>/external/pico_sdk_import.cmake
# This can be dropped into an external project to help locate this SDK
# It should be include()ed prior to project()
if (DEFINED ENV{PICO_SDK_PATH} AND (NOT PICO_SDK_PATH))
set(PICO_SDK_PATH $ENV{PICO_SDK_PATH})
message("Using PICO_SDK_PATH from environment ('${PICO_SDK_PATH}')")
endif ()
if (DEFINED ENV{PICO_SDK_FETCH_FROM_GIT} AND (NOT PICO_SDK_FETCH_FROM_GIT))
set(PICO_SDK_FETCH_FROM_GIT $ENV{PICO_SDK_FETCH_FROM_GIT})
message("Using PICO_SDK_FETCH_FROM_GIT from environment ('${PICO_SDK_FETCH_FROM_GIT}')")
endif ()
if (DEFINED ENV{PICO_SDK_FETCH_FROM_GIT_PATH} AND (NOT PICO_SDK_FETCH_FROM_GIT_PATH))
set(PICO_SDK_FETCH_FROM_GIT_PATH $ENV{PICO_SDK_FETCH_FROM_GIT_PATH})
message("Using PICO_SDK_FETCH_FROM_GIT_PATH from environment ('${PICO_SDK_FETCH_FROM_GIT_PATH}')")
endif ()
set(PICO_SDK_PATH "${PICO_SDK_PATH}" CACHE PATH "Path to the PICO SDK")
set(PICO_SDK_FETCH_FROM_GIT "${PICO_SDK_FETCH_FROM_GIT}" CACHE BOOL "Set to ON to fetch copy of PICO SDK from git if not otherwise locatable")
set(PICO_SDK_FETCH_FROM_GIT_PATH "${PICO_SDK_FETCH_FROM_GIT_PATH}" CACHE FILEPATH "location to download SDK")
if (NOT PICO_SDK_PATH)
if (PICO_SDK_FETCH_FROM_GIT)
include(FetchContent)
set(FETCHCONTENT_BASE_DIR_SAVE ${FETCHCONTENT_BASE_DIR})
if (PICO_SDK_FETCH_FROM_GIT_PATH)
get_filename_component(FETCHCONTENT_BASE_DIR "${PICO_SDK_FETCH_FROM_GIT_PATH}" REALPATH BASE_DIR "${CMAKE_SOURCE_DIR}")
endif ()
FetchContent_Declare(
pico_sdk
GIT_REPOSITORY https://github.com/raspberrypi/pico-sdk
GIT_TAG master
)
if (NOT pico_sdk)
message("Downloading PICO SDK")
FetchContent_Populate(pico_sdk)
set(PICO_SDK_PATH ${pico_sdk_SOURCE_DIR})
endif ()
set(FETCHCONTENT_BASE_DIR ${FETCHCONTENT_BASE_DIR_SAVE})
else ()
message(FATAL_ERROR
"PICO SDK location was not specified. Please set PICO_SDK_PATH or set PICO_SDK_FETCH_FROM_GIT to on to fetch from git."
)
endif ()
endif ()
get_filename_component(PICO_SDK_PATH "${PICO_SDK_PATH}" REALPATH BASE_DIR "${CMAKE_BINARY_DIR}")
if (NOT EXISTS ${PICO_SDK_PATH})
message(FATAL_ERROR "Directory '${PICO_SDK_PATH}' not found")
endif ()
set(PICO_SDK_INIT_CMAKE_FILE ${PICO_SDK_PATH}/pico_sdk_init.cmake)
if (NOT EXISTS ${PICO_SDK_INIT_CMAKE_FILE})
message(FATAL_ERROR "Directory '${PICO_SDK_PATH}' does not appear to contain the PICO SDK")
endif ()
set(PICO_SDK_PATH ${PICO_SDK_PATH} CACHE PATH "Path to the PICO SDK" FORCE)
include(${PICO_SDK_INIT_CMAKE_FILE})