first sketch of the dht22 sensor driver

pull/2/head
Mateusz Lubecki 2018-04-18 00:05:02 +02:00
rodzic 06e970e5d7
commit 8329a94b52
13 zmienionych plików z 2036 dodań i 1190 usunięć

Plik diff jest za duży Load Diff

Wyświetl plik

@ -4,31 +4,40 @@
# Add inputs and outputs from these tool invocations to the build variables
C_SRCS += \
../system/src/drivers/_dht22.c \
../system/src/drivers/dallas.c \
../system/src/drivers/dht22.c \
../system/src/drivers/flash.c \
../system/src/drivers/gpio_conf.c \
../system/src/drivers/i2c.c \
../system/src/drivers/ms5611.c \
../system/src/drivers/sensirion_sht3x.c \
../system/src/drivers/serial.c \
../system/src/drivers/tx20.c \
../system/src/drivers/user_interf.c
OBJS += \
./system/src/drivers/_dht22.o \
./system/src/drivers/dallas.o \
./system/src/drivers/dht22.o \
./system/src/drivers/flash.o \
./system/src/drivers/gpio_conf.o \
./system/src/drivers/i2c.o \
./system/src/drivers/ms5611.o \
./system/src/drivers/sensirion_sht3x.o \
./system/src/drivers/serial.o \
./system/src/drivers/tx20.o \
./system/src/drivers/user_interf.o
C_DEPS += \
./system/src/drivers/_dht22.d \
./system/src/drivers/dallas.d \
./system/src/drivers/dht22.d \
./system/src/drivers/flash.d \
./system/src/drivers/gpio_conf.d \
./system/src/drivers/i2c.d \
./system/src/drivers/ms5611.d \
./system/src/drivers/sensirion_sht3x.d \
./system/src/drivers/serial.d \
./system/src/drivers/tx20.d \
./system/src/drivers/user_interf.d

Wyświetl plik

@ -5,6 +5,7 @@
# Add inputs and outputs from these tool invocations to the build variables
C_SRCS += \
../system/src/stm32f1-stdperiph/misc.c \
../system/src/stm32f1-stdperiph/stm32f10x_exti.c \
../system/src/stm32f1-stdperiph/stm32f10x_gpio.c \
../system/src/stm32f1-stdperiph/stm32f10x_i2c.c \
../system/src/stm32f1-stdperiph/stm32f10x_rcc.c \
@ -13,6 +14,7 @@ C_SRCS += \
OBJS += \
./system/src/stm32f1-stdperiph/misc.o \
./system/src/stm32f1-stdperiph/stm32f10x_exti.o \
./system/src/stm32f1-stdperiph/stm32f10x_gpio.o \
./system/src/stm32f1-stdperiph/stm32f10x_i2c.o \
./system/src/stm32f1-stdperiph/stm32f10x_rcc.o \
@ -21,6 +23,7 @@ OBJS += \
C_DEPS += \
./system/src/stm32f1-stdperiph/misc.d \
./system/src/stm32f1-stdperiph/stm32f10x_exti.d \
./system/src/stm32f1-stdperiph/stm32f10x_gpio.d \
./system/src/stm32f1-stdperiph/stm32f10x_i2c.d \
./system/src/stm32f1-stdperiph/stm32f10x_rcc.d \

6
WIRING
Wyświetl plik

@ -20,8 +20,12 @@ PB8 - DTR line from TX20 aneometr - green wire in original cable but it can be j
PC6 - Dallas One Wire pin to DS termometer. Only one termometer can be used and it should be powered via separate +5V line,
parasite power is not recommended.
PC4 - DHT22 pin
LEDS:
Blue LED - DCD - lights up while controller is receiving APRS packet from radio.
Green LED - If meteo is enabled this blinks when transmission from TX20 anemometr is correctly received.
In 'non-meteo' mode it works as TX indicator and lights up when controler is transmitting data.
In 'non-meteo' mode it works as TX indicator and lights up when controler is transmitting data.

43
asm 100644
Wyświetl plik

@ -0,0 +1,43 @@
ConfigPath:
0800242c: push {r4, lr}
0800242e: mov r4, r0
14 memcpy(p[0].call, "AKLPRZ", 6), p[0].ssid = 0;
08002430: movs r2, #6
08002432: ldr r1, [pc, #44] ; (0x8002460 <ConfigPath+52>)
08002434: bl 0x8005d90 <memcpy>
08002438: movs r3, #0
0800243a: strb r3, [r4, #6]
20 memcpy(p[1].call, _CALL, 6), p[1].ssid = _SSID;
0800243c: movs r2, #6
0800243e: ldr r1, [pc, #36] ; (0x8002464 <ConfigPath+56>)
08002440: adds r0, r4, #7
08002442: bl 0x8005d90 <memcpy>
08002446: movs r3, #12
08002448: strb r3, [r4, #13]
21 memcpy(p[2].call, "WIDE2", 6), p[2].ssid = 1;
0800244a: movs r2, #6
0800244c: ldr r1, [pc, #24] ; (0x8002468 <ConfigPath+60>)
0800244e: add.w r0, r4, #14
08002452: bl 0x8005d90 <memcpy>
08002456: movs r3, #1
08002458: strb r3, [r4, #20]
30 }
0800245a: movs r0, #3
0800245c: pop {r4, pc}
0800245e: nop
08002460: strh r4, [r5, #26]
08002462: lsrs r0, r0, #32
08002464: strh r0, [r3, #22]
08002466: lsrs r0, r0, #32
08002468: strh r4, [r6, #26]
0800246a: lsrs r0, r0, #32
path_len = ConfigPath(path);
0800278e: ldr.w r8, [pc, #428] ; 0x800293c <main(int, char**)+468>
08002792: mov r0, r8
08002794: bl 0x800242c <ConfigPath>
08002798: ldr r3, [pc, #332] ; (0x80028e8 <main(int, char**)+384>)
0800279a: strb r0, [r3, #0]
98 LedConfig();
0800279c: bl 0x80023c8 <LedConfig>

Wyświetl plik

@ -12,7 +12,7 @@
//#define _DBG_TRACE
// Uncomment to enable all meteo functionality. TX20 anemometer, dallas termometer, MS5611 pressure sens
//#define _METEO
#define _METEO
//#define _DIGI // Comment this do disable WIDE1-1 digipeating
#define _MUTE_RF // TODO: Not yet implemented - This will make station RXonly and disable all data transmission

Wyświetl plik

@ -36,6 +36,7 @@
#include "drivers/ms5611.h"
#include "drivers/i2c.h"
#include "drivers/tx20.h"
#include "drivers/_dht22.h"
#include "aprs/wx.h"
#endif
@ -73,6 +74,8 @@ float temperature;
float td;
double pressure = 0.0;
dht22Values dht;
static void message_callback(struct AX25Msg *msg) {
}
@ -93,7 +96,8 @@ main(int argc, char* argv[])
path_len = ConfigPath(path);
#ifdef _METEO
i2cConfigure();
// DHT22_Init();
// i2cConfigure();
#endif
LedConfig();
AFSK_Init(&a);
@ -102,6 +106,7 @@ main(int argc, char* argv[])
TimerConfig();
#ifdef _METEO
dht22_init();
DallasInit(GPIOC, GPIO_Pin_6, GPIO_PinSource6);
TX20Init();
#endif
@ -115,10 +120,11 @@ main(int argc, char* argv[])
TelemInterval = 10;
#ifdef _METEO
SensorReset(0xEC);
// volatile uint32_t dht22_status = DHT22_GetReadings();
// SensorReset(0xEC);
td = DallasQuery();
SensorReadCalData(0xEC, SensorCalData);
SensorStartMeas(0);
// SensorReadCalData(0xEC, SensorCalData);
// SensorStartMeas(0);
#endif
aprs_msg_len = sprintf(aprs_msg, "=%07.2f%c%c%08.2f%c%c %s\0", (float)_LAT, _LATNS, _SYMBOL_F, (float)_LON, _LONWE, _SYMBOL_S, _COMMENT);
@ -137,10 +143,11 @@ main(int argc, char* argv[])
#ifdef _METEO
temperature = SensorBringTemperature();
dht22_comm(&dht);
// temperature = SensorBringTemperature();
td = DallasQuery();
trace_printf("temperatura DS: %d\r\n", (int)td);
pressure = (float)SensorBringPressure();
// pressure = (float)SensorBringPressure();
trace_printf("cisnienie MS: %d\r\n", (int)pressure);
#endif

Wyświetl plik

@ -0,0 +1,43 @@
/*
* _dht22.h
*
* Created on: 17.04.2018
* Author: mateusz
*/
#ifndef INCLUDE_DRIVERS__DHT22_H_
#define INCLUDE_DRIVERS__DHT22_H_
#define DHT22_START_SIG_DURATION 200
#define DHT22_WAITING_FOR_START_RESP_DURATION 12
#define DHT22_LOW_LEVEL_BEFORE_BIT 10
#define DHT22_MAX_ZERO_DURATION 6
#define DHT22_MIN_ONE_DURATION 10
#define DHT22_INTERRUPT_DURATION 40
#define DHT22_PIN_PORT GPIOC
#define DHT22_PIN_CLOCK RCC_APB2Periph_GPIOC
#define DHT22_PIN_PIN GPIO_Pin_4
typedef enum dht22QF {
DHT22_QF_FULL,
DHT22_QF_DEGRADATED,
DHT22_QF_UNAVALIABLE
} dht22QF;
typedef struct dht22Values {
uint8_t humidity;
uint16_t scaledTemperature;
dht22QF qf;
}dht22Values;
#ifdef __cplusplus
extern "C" {
#endif
void dht22_init(void);
void dht22_comm(dht22Values *data);
#ifdef __cplusplus
}
#endif
#endif /* INCLUDE_DRIVERS__DHT22_H_ */

Wyświetl plik

@ -0,0 +1,23 @@
/* Port and pin with DHT22 sensor*/
#define DHT22_GPIO_PORT GPIOC
#define DHT22_GPIO_CLOCK RCC_APB2Periph_GPIOC
#define DHT22_GPIO_PIN GPIO_Pin_4
/* DHT22_GetReadings response codes */
#define DHT22_RCV_OK 0 // Return with no error
#define DHT22_RCV_NO_RESPONSE 1 // No response from sensor
#define DHT22_RCV_BAD_ACK1 2 // Bad first half length of ACK impulse
#define DHT22_RCV_BAD_ACK2 3 // Bad second half length of ACK impulse
#define DHT22_RCV_RCV_TIMEOUT 4 // It was timeout while receiving bits
#ifdef __cplusplus
extern "C" {
#endif
void DHT22_Init(void);
uint32_t DHT22_GetReadings(void);
uint16_t DHT22_DecodeReadings(void);
uint16_t DHT22_GetHumidity(void);
uint16_t DHT22_GetTemperature(void);
#ifdef __cplusplus
}
#endif

Wyświetl plik

@ -0,0 +1,32 @@
/*
* sensirion_sht3x.h
*
* Created on: 02.01.2018
* Author: mateusz
*/
#ifndef INCLUDE_DRIVERS_SENSIRION_SHT3X_H_
#define INCLUDE_DRIVERS_SENSIRION_SHT3X_H_
#include "drivers/i2c.h"
#include <stdint.h>
#define SHT3X_RADDR ((0x44 << 1) | 1 )
#define SHT3X_WADDR (0x44 << 1)
#define SHT3X_SS_LOW_NOSTREACH 0x2416
/* C++ detection */
#ifdef __cplusplus
extern "C" {
#endif
void sht3x_start_measurement(void);
void sht3x_read_measurements(uint16_t *temperature, uint16_t *humidity);
/* C++ detection */
#ifdef __cplusplus
}
#endif
#endif /* INCLUDE_DRIVERS_SENSIRION_SHT3X_H_ */

Wyświetl plik

@ -0,0 +1,107 @@
/*
* _dht22.c
*
* Created on: 17.04.2018
* Author: mateusz
*/
#include <stm32f10x_gpio.h>
#include <stm32f10x_exti.h>
#include "../drivers/_dht22.h"
#include "../drivers/dallas.h" // for delay
#include <stdint.h>
#include <stdio.h>
uint8_t bitsDuration[40];
uint8_t currentBit;
GPIO_InitTypeDef PORT_out, PORT_in;
EXTI_InitTypeDef exti, exti_disable;
void dht22_init(void) {
memset(bitsDuration, 0x00, 40);
currentBit = 0;
/*
* Initializing of the GPIO pin used to communicatie with sensor
*/
GPIO_StructInit(&PORT_out);
GPIO_StructInit(&PORT_in);
PORT_out.GPIO_Mode = GPIO_Mode_Out_OD;
PORT_out.GPIO_Pin = DHT22_PIN_PIN;
PORT_out.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_Init(DHT22_PIN_PORT,&PORT_out);
PORT_in.GPIO_Mode = GPIO_Mode_IN_FLOATING;
PORT_in.GPIO_Pin = DHT22_PIN_PIN;
PORT_in.GPIO_Speed = GPIO_Speed_50MHz;
EXTI_StructInit(&exti);
exti.EXTI_Line = EXTI_Line4;
exti.EXTI_Mode = EXTI_Mode_Interrupt;
exti.EXTI_Trigger = EXTI_Trigger_Falling;
exti.EXTI_LineCmd = ENABLE;
EXTI_StructInit(&exti_disable);
exti.EXTI_Line = EXTI_Line4;
exti.EXTI_Mode = EXTI_Mode_Interrupt;
exti.EXTI_Trigger = EXTI_Trigger_Falling;
exti.EXTI_LineCmd = DISABLE;
}
void dht22_comm(dht22Values *in) {
GPIO_Init(DHT22_PIN_PORT,&PORT_out);
GPIO_SetBits(DHT22_PIN_PORT, DHT22_PIN_PIN);
DallasConfigTimer();
/*
* Setting pin logic-low to initialize transfer.
*/
GPIO_ResetBits(DHT22_PIN_PORT, DHT22_PIN_PIN);
delay_5us = DHT22_START_SIG_DURATION;
while (delay_5us != 0);
GPIO_SetBits(DHT22_PIN_PORT, DHT22_PIN_PIN);
/*
* Waiting for the response pulse from sensor
*/
GPIO_Init(DHT22_PIN_PORT,&PORT_in);
delay_5us = DHT22_WAITING_FOR_START_RESP_DURATION;
while (delay_5us != 0);
uint8_t sensorResp = GPIO_ReadInputDataBit(DHT22_PIN_PORT, DHT22_PIN_PIN);
if (sensorResp == Bit_SET) {
in->qf = DHT22_QF_UNAVALIABLE;
return; // if pin is still high it usually means that there is a problem with comm with the sensor
}
else;
/*
* Starting the edge detected interrupt on this pin (EXTI)
*/
GPIO_EXTILineConfig(GPIO_PortSourceGPIOC, GPIO_PinSource4);
EXTI_Init(&exti);
EXTI->FTSR |= 1 << 4;
EXTI->IMR |= 1 << 4;
NVIC_EnableIRQ(EXTI4_IRQn);
delay_5us = DHT22_INTERRUPT_DURATION;
return;
/*
* Now
*/
}
void EXTI4_IRQHandler(void) {
EXTI->PR |= EXTI_PR_PR4;
bitsDuration[currentBit++] = delay_5us;
delay_5us = DHT22_INTERRUPT_DURATION;
if (currentBit >= 40) {
EXTI_Init(&exti_disable);
currentBit = 0;
}
}

Wyświetl plik

@ -0,0 +1,124 @@
#include <stm32f10x_rcc.h>
#include <stm32f10x_gpio.h>
#include "../drivers/dallas.h"
#include "../drivers/dht22.h"
uint16_t bits[40];
uint8_t hMSB = 0;
uint8_t hLSB = 0;
uint8_t tMSB = 0;
uint8_t tLSB = 0;
uint8_t parity_rcv = 0;
static GPIO_InitTypeDef PORT;
void DHT22_Init(void) {
RCC_APB2PeriphClockCmd(DHT22_GPIO_CLOCK,ENABLE);
PORT.GPIO_Mode = GPIO_Mode_Out_PP;
PORT.GPIO_Pin = DHT22_GPIO_PIN;
PORT.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_Init(DHT22_GPIO_PORT,&PORT);
}
uint32_t DHT22_GetReadings(void) {
uint32_t wait;
uint8_t i;
DallasConfigTimer();
// Generate start impulse for sensor
DHT22_GPIO_PORT->BRR = DHT22_GPIO_PIN; // Pull down SDA (Bit_SET)
delay_5us = 175; // delay 875us
while (delay_5us != 0);
DHT22_GPIO_PORT->BSRR = DHT22_GPIO_PIN; // Release SDA (Bit_RESET)
// Switch pin to input with Pull-Up
PORT.GPIO_Mode = GPIO_Mode_IPU;
GPIO_Init(DHT22_GPIO_PORT,&PORT);
// Wait for AM2302 to start communicate
delay_5us = 80;
while ((DHT22_GPIO_PORT->IDR & DHT22_GPIO_PIN) && (delay_5us > 0));
if (delay_5us < 10) return DHT22_RCV_NO_RESPONSE;
// Check ACK strobe from sensor
delay_5us = 20;
while (!(DHT22_GPIO_PORT->IDR & DHT22_GPIO_PIN) && (delay_5us > 0));
if ((delay_5us > 1) || (delay_5us < 3)) return DHT22_RCV_BAD_ACK1;
delay_5us = 20;
while ((DHT22_GPIO_PORT->IDR & DHT22_GPIO_PIN) && (delay_5us > 0));
if ((wait > 1) || (wait < 3)) return DHT22_RCV_BAD_ACK2;
// ACK strobe received --> receive 40 bits
i = 0;
while (i < 40) {
// Measure bit start impulse (T_low = 50us)
delay_5us = 4;
while (!(DHT22_GPIO_PORT->IDR & DHT22_GPIO_PIN) && (delay_5us > 0));
if (delay_5us <= 3) {
// invalid bit start impulse length
bits[i] = 0xffff;
delay_5us = 4;
while ((DHT22_GPIO_PORT->IDR & DHT22_GPIO_PIN) && (delay_5us > 0));
} else {
// Measure bit impulse length (T_h0 = 25us, T_h1 = 70us)
delay_5us = 4;
while ((DHT22_GPIO_PORT->IDR & DHT22_GPIO_PIN) && (delay_5us > 0));
bits[i] = (delay_5us <= 3) ? delay_5us * 5 : 0xffff;
}
i++;
}
DallasDeConfigTimer();
for (i = 0; i < 40; i++) if (bits[i] == 0xffff) return DHT22_RCV_RCV_TIMEOUT;
return DHT22_RCV_OK;
}
uint16_t DHT22_DecodeReadings(void) {
uint8_t parity;
uint8_t i = 0;
hMSB = 0;
for (; i < 8; i++) {
hMSB <<= 1;
if (bits[i] > 7) hMSB |= 1;
}
hLSB = 0;
for (; i < 16; i++) {
hLSB <<= 1;
if (bits[i] > 7) hLSB |= 1;
}
tMSB = 0;
for (; i < 24; i++) {
tMSB <<= 1;
if (bits[i] > 7) tMSB |= 1;
}
tLSB = 0;
for (; i < 32; i++) {
tLSB <<= 1;
if (bits[i] > 7) tLSB |= 1;
}
for (; i < 40; i++) {
parity_rcv <<= 1;
if (bits[i] > 7) parity_rcv |= 1;
}
parity = hMSB + hLSB + tMSB + tLSB;
return (parity_rcv << 8) | parity;
}
uint16_t DHT22_GetHumidity(void) {
return (hMSB << 8) + hLSB;
}
uint16_t DHT22_GetTemperature(void) {
return (tMSB << 8) + tLSB;
}

Wyświetl plik

@ -0,0 +1,44 @@
/*
* sensirion_sht3x.c
*
* Created on: 02.01.2018
* Author: mateusz
*/
#include "drivers/sensirion_sht3x.h"
void sht3x_start_measurement(void) {
uint32_t txbuff[3] = {0, 0, 0};
txbuff[0] = (uint32_t)(SHT3X_SS_LOW_NOSTREACH & 0xFF00) >> 8;
txbuff[1] = (uint32_t)SHT3X_SS_LOW_NOSTREACH & 0xFF;
while(i2cTXing != 0 && i2cRXing !=0); // je<6A>eli magistala i2c nie jest zaj<61>ta, tj nie nadaj<61> i nie odbiera
i2cSendData(SHT3X_WADDR, txbuff, 0); // wys<79>anie danych pod adres 0xEC czyli do czujnika
while(i2cTXing != 0);
}
void sht3x_read_measurements(uint16_t *temperature, uint16_t *humidity) {
// int rxbuff[6];
// memset(rxbuff, 0x00, 6);
uint16_t temperature_raw = 0;
uint16_t humidity_raw = 0;
float temperature_phy = 0;
float himidity_phy = 0;
while(i2cTXing != 0 && i2cRXing !=0); // je<6A>eli magistala i2c nie jest zaj<61>ta, tj nie nadaj<61> i nie odbiera
i2cReceiveData(SHT3X_RADDR, 0, 9); // odbi<62>r danych z czujnika
while(i2cRXing !=0); // je<6A>eli magistala i2c nie jest zaj<61>ta, tj nie nadaj<61> i nie odbiera
temperature_raw = ((i2cRXData[0] << 8) | i2cRXData[1]);
humidity_raw = ((i2cRXData[3] << 8) | i2cRXData[4]);
temperature_phy = -45.0f + 175.0f * (float)( temperature_raw / 65535.0f);
*temperature = (uint16_t)temperature_phy;
return;
}