Add files via upload

This commit is contained in:
1991Patrick 2017-03-31 15:13:24 +02:00 committed by GitHub
parent 966bacb7b3
commit f3262add86
13 changed files with 1093 additions and 0 deletions

BIN
ATxmega_I2C_LCD.jpg Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 2.1 MiB

BIN
ATxmega_I2C_LCD_SHT2x.jpg Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 1.6 MiB

BIN
I2C LCD interface.pdf Normal file

Binary file not shown.

257
I2C_SHT2x.c Normal file
View File

@ -0,0 +1,257 @@
/*!
* \file I2C_SHT2x.c
* \author Patrick Taling (not the original author from the original code of SENSIRION AG)
* \date 31/03/2017
* \version 1.0
*
* \brief Simple I2C SHT2x library to measure relative humidity and temperature and write it to an I2C LCD with the ATxmega256a3u.
*
* \details The file I2C_SHT2x.c is the library for the SHT2x humidity and temperature sensor
*
* The library needs the i2c library from w.e.dolman (<a href="mailto:w.e.dolman@hva.nl">w.e.dolman@hva.nl</a>)
* For i2c.c use code 21.8 from "de taal C en de Xmega tweede druk" http://dolman-wim.nl/xmega/book/index.php
* For i2c.h use code 21.9 from "de taal C en de Xmega tweede druk" http://dolman-wim.nl/xmega/book/index.php
*
* The libraby needs some parts of the the SHT2x library from SENIRION from https://www.sensirion.com/en/products/humidity-sensors/humidity-temperature-sensor-sht2x-digital-i2c-accurate/
* The libraby can be download from: https://www.sensirion.com/en/products/all-documents-of-sensirions-humidity-sensors-for-download/
* Go to SHT2x/ Sample Code SHT21 and download the zip file Sensirion_Humidity_Sensors_SHT21_Sample_Code_C-file
*
* \note the following files aren't fully used. Most parts are used in other .c of .h files or disabled.
* DisplayDip204.C, DisplayDip204.h,
* I2C_HAL.c, I2C_HAL.h,
* System.c, System.h and
* io70f3740.h.
* \note for the use of two SHT2X you should use different IOs for SDA or additional hardware such as I2C multiplexer.
* The adress of the SHT2x cant be changed.
*
*
* \ORIGINAL AUTHOR INFORMATION
* ==============================================================================
* S E N S I R I O N AG, Laubisruetistr. 50, CH-8712 Staefa, Switzerland
* ==============================================================================
* Project : SHT2x Sample Code (V1.2)
* File : SHT2x.c
* Author : MST
* Controller: NEC V850/SG3 (uPD70F3740)
* Compiler : IAR compiler for V850 (3.50A)
* Brief : Sensor layer. Functions for sensor access
* ==============================================================================
*
*
* \verbatim
#include <I2C_SHT2x.h>
#include <i2c.h>
#include <Typedefs.h>
\endverbatim
* \par
*
* \note An AVR-project can use multiple I2C's. One shoud take care that
* in different source files there are no multiple I2C
* definitions for the same I2C.
*/
#define F_CPU 2000000UL
#include "I2C_SHT2x.h"
#include "i2c.h"
#include "Typedefs.h"
#include <util/delay.h>
#include <assert.h>
#include <math.h>
//==============================================================================
uint8_t i2c_SHT2x_CheckCrc(uint8_t data[], uint8_t nbrOfBytes, uint8_t checksum)
//==============================================================================
{
uint8_t crc = 0;
uint8_t byteCtr;
//calculates 8-Bit checksum with given polynomial
for (byteCtr = 0; byteCtr < nbrOfBytes; ++byteCtr)
{ crc ^= (data[byteCtr]);
for (uint8_t bit = 8; bit > 0; --bit)
{ if (crc & 0x80) {crc = (crc << 1) ^ POLYNOMIAL;}
else crc = (crc << 1);
}
}
if (crc != checksum) return CHECKSUM_ERROR;
else return 0;
}
//===========================================================================
uint8_t i2c_SHT2x_ReadUserRegister(uint8_t *pRegisterValue)
//===========================================================================
{
uint8_t checksum;
uint8_t error=0;
error |= i2c_start(&TWIE, I2C_SHT2x_ADR, 0);
error |= i2c_write(&TWIE, USER_REG_R);
i2c_stop(&TWIE);
error |= i2c_start(&TWIE, I2C_SHT2x_ADR, 1);
*pRegisterValue = i2c_read(&TWIE, I2C_ACK);
checksum=i2c_read(&TWIE, I2C_NACK);
error |= i2c_SHT2x_CheckCrc (pRegisterValue,1,checksum);
i2c_stop(&TWIE);
return error;
}
//===========================================================================
uint8_t i2c_SHT2x_WriteUserRegister(uint8_t *pRegisterValue)
//===========================================================================
{
uint8_t error=0;
_delay_ms(2000);
error |= i2c_start(&TWIE, I2C_SHT2x_ADR, 0);
error |= i2c_write(&TWIE, USER_REG_W);
error |= i2c_write(&TWIE, *pRegisterValue);
i2c_stop(&TWIE);
return error;
}
//===========================================================================
uint8_t i2c_SHT2x_MeasureHM(etSHT2xMeasureType eSHT2xMeasureType, nt16 *pMeasurand)
//===========================================================================
{
uint8_t checksum;
uint8_t data[2];
uint8_t error=0;
//-- write I2C sensor address and command --
error |= i2c_start(&TWIE, I2C_SHT2x_ADR, 0);
switch(eSHT2xMeasureType)
{ case HUMIDITY: error |= i2c_write(&TWIE, TRIG_RH_MEASUREMENT_HM); break;
case TEMP: error |= i2c_write(&TWIE, TRIG_T_MEASUREMENT_HM); break;
default: assert(0);
}
i2c_stop(&TWIE);
//-- wait until hold master is released --
error |= i2c_start(&TWIE, I2C_SHT2x_ADR, 1);
//-- read two data bytes and one checksum byte --
pMeasurand->s16.u8H = data[0] = i2c_read(&TWIE, I2C_ACK);
pMeasurand->s16.u8L = data[1] = i2c_read(&TWIE, I2C_ACK);
checksum= i2c_read(&TWIE, I2C_NACK);
//-- verify checksum --
error |= i2c_SHT2x_CheckCrc (data,2,checksum);
i2c_stop(&TWIE);
return error;
}
//===========================================================================
uint8_t i2c_SHT2x_MeasurePoll(etSHT2xMeasureType eSHT2xMeasureType, nt16 *pMeasurand)
//--- Disabled due to error in TEMP ---
//--- measuring TEMP doesn't work after the do while loop ---
//===========================================================================
{
uint8_t checksum;
uint8_t data[2];
uint8_t error=0;
uint16_t i=0;
//-- write I2C sensor address and command --
error |= i2c_start(&TWIE, I2C_SHT2x_ADR, 0); // I2C Adr
switch(eSHT2xMeasureType)
{ case HUMIDITY: error |= i2c_write(&TWIE, TRIG_RH_MEASUREMENT_POLL); break;
case TEMP: error |= i2c_write(&TWIE, TRIG_T_MEASUREMENT_POLL); break;
default: assert(0);
}
_delay_us(20);
i2c_stop(&TWIE);
//-- poll every 10ms for measurement ready. Timeout after 20 retries (200ms)--
do
{
_delay_us(10000); //delay 10ms Max delay is 0.2s (20*10ms = 200ms)
if(i++ >= 20) break;
} while(i2c_start(&TWIE, I2C_SHT2x_ADR, 1) == ACK_ERROR);
if (i>=20) error |= TIME_OUT_ERROR;
//-- read two data bytes and one checksum byte --
pMeasurand->s16.u8H = data[0] = i2c_read(&TWIE, I2C_ACK);
pMeasurand->s16.u8L = data[1] = i2c_read(&TWIE, I2C_ACK);
checksum= i2c_read(&TWIE, I2C_NACK);
//-- verify checksum --
error |= i2c_SHT2x_CheckCrc (data,2,checksum);
i2c_stop(&TWIE);
return error;
}
//===========================================================================
uint8_t i2c_SHT2x_SoftReset()
//===========================================================================
{
uint8_t error=0;
error |= i2c_start(&TWIE, I2C_SHT2x_ADR, 0);
error |= i2c_write(&TWIE, SOFT_RESET);
i2c_stop(&TWIE);
_delay_ms(15);
return error;
}
//==============================================================================
float i2c_SHT2x_CalcRH(uint16_t sRH)
// --- The original formula from SENSIRION is wrong! ---
//==============================================================================
{
float humidityRH;
sRH &= ~0x0003;
//-- calculate relative humidity [%RH] --
humidityRH = (float)sRH / RESOLUTION_16; //RH = -6 + 125 * sRH/2^16;
humidityRH = humidityRH * CONSTANT_125;
humidityRH = humidityRH - CONSTANT_6;
return humidityRH;
}
//==============================================================================
float i2c_SHT2x_CalcTemperatureC(uint16_t sT)
// --- The original formula from SENSIRION is wrong! ---
//==============================================================================
{
float temperatureC;
sT &= ~0x0003;
//-- calculate temperature [°C] --
temperatureC = (float)sT / RESOLUTION_16; //T= -46.85 + 175.72 * ST/2^16
temperatureC = temperatureC * CONSTANT_175_72;
temperatureC = temperatureC - CONSTANT_46_85;
return temperatureC;
}
//==============================================================================
uint8_t i2c_SHT2x_GetSerialNumber(uint8_t SerialNumber[])
//==============================================================================
{
uint8_t error=0; //error variable
//Read from memory location 1
error |= i2c_start(&TWIE, I2C_SHT2x_ADR, 0); //I2C address
error |= i2c_write(&TWIE, CMD_CHIP_MEMORY_LOC_1); //Command for readout on-chip memory
error |= i2c_write(&TWIE, ADR_CHIP_MEMORY_LOC_1); //on-chip memory address
i2c_stop(&TWIE);
error |= i2c_start(&TWIE, I2C_SHT2x_ADR, 1); //I2C read address
SerialNumber[5] = i2c_read(&TWIE, I2C_ACK); //Read SNB_3
i2c_read(&TWIE, I2C_ACK); //Read CRC SNB_3 (CRC is not analyzed)
SerialNumber[4] = i2c_read(&TWIE, I2C_ACK); //Read SNB_2
i2c_read(&TWIE, I2C_ACK); //Read CRC SNB_2 (CRC is not analyzed)
SerialNumber[3] = i2c_read(&TWIE, I2C_ACK); //Read SNB_1
i2c_read(&TWIE, I2C_ACK);; //Read CRC SNB_1 (CRC is not analyzed)
SerialNumber[2] = i2c_read(&TWIE, I2C_ACK); //Read SNB_0
i2c_read(&TWIE, I2C_NACK); //Read CRC SNB_0 (CRC is not analyzed)
i2c_stop(&TWIE);
//Read from memory location 2
error |= i2c_start(&TWIE, I2C_SHT2x_ADR, 0); //I2C address
error |= i2c_write(&TWIE, CMD_CHIP_MEMORY_LOC_2); //Command for readout on-chip memory
error |= i2c_write(&TWIE, ADR_CHIP_MEMORY_LOC_2); //on-chip memory address
i2c_stop(&TWIE);
error |= i2c_start(&TWIE, I2C_SHT2x_ADR, 1); //I2C address
SerialNumber[1] = i2c_read(&TWIE, I2C_ACK); //Read SNC_1
SerialNumber[0] = i2c_read(&TWIE, I2C_ACK); //Read SNC_0
i2c_read(&TWIE, I2C_ACK); //Read CRC SNC0/1 (CRC is not analyzed)
SerialNumber[7] = i2c_read(&TWIE, I2C_ACK); //Read SNA_1
SerialNumber[6] = i2c_read(&TWIE, I2C_ACK); //Read SNA_0
i2c_read(&TWIE, I2C_NACK); //Read CRC SNA0/1 (CRC is not analyzed)
i2c_stop(&TWIE);
return error;
}

127
I2C_SHT2x.h Normal file
View File

@ -0,0 +1,127 @@
/*!
* \file I2C_SHT2x.h
* \author Patrick Taling (not the original author from the original code of SENSIRION AG)
* \date 31/03/2017
* \version 1.0
*
* \brief Simple I2C SHT2x library to measure relative humidity and temperature and write it to an I2C LCD with the ATxmega256a3u.
*
* \details The file I2C_SHT2x.h is the library for the SHT2x humidity and temperature sensor
*
* The library needs the i2c library from w.e.dolman (<a href="mailto:w.e.dolman@hva.nl">w.e.dolman@hva.nl</a>)
* For i2c.c use code 21.8 from "de taal C en de Xmega tweede druk" http://dolman-wim.nl/xmega/book/index.php
* For i2c.h use code 21.9 from "de taal C en de Xmega tweede druk" http://dolman-wim.nl/xmega/book/index.php
*
* The libraby needs some parts of the the SHT2x library from SENIRION from https://www.sensirion.com/en/products/humidity-sensors/humidity-temperature-sensor-sht2x-digital-i2c-accurate/
* The libraby can be download from: https://www.sensirion.com/en/products/all-documents-of-sensirions-humidity-sensors-for-download/
* Go to SHT2x/ Sample Code SHT21 and download the zip file Sensirion_Humidity_Sensors_SHT21_Sample_Code_C-file
*
* \note the following files aren't fully used. Most parts are used in other .c of .h files or disabled.
* DisplayDip204.C, DisplayDip204.h,
* I2C_HAL.c, I2C_HAL.h,
* System.c, System.h and
* io70f3740.h.
* \note for the use of two SHT2X you should use different IOs for SDA or additional hardware such as I2C multiplexer.
* The adress of the SHT2x cant be changed.
*
*
* \ORIGINAL AUTHOR INFORMATION
* ==============================================================================
* S E N S I R I O N AG, Laubisruetistr. 50, CH-8712 Staefa, Switzerland
* ==============================================================================
* Project : SHT2x Sample Code (V1.2)
* File : SHT2x.c
* Author : MST
* Controller: NEC V850/SG3 (uPD70F3740)
* Compiler : IAR compiler for V850 (3.50A)
* Brief : Sensor layer. Functions for sensor access
* ==============================================================================
*
*
* \verbatim
#include <I2C_SHT2x.h>
#include <i2c.h>
#include <Typedefs.h>
\endverbatim
* \par
*
* \note An AVR-project can use multiple I2C's. One shoud take care that
* in different source files there are no multiple I2C
* definitions for the same I2C.
*/
#ifndef SHT2x_H
#define SHT2x_H
#include "i2c.h"
#include "Typedefs.h"
// CRC
#define POLYNOMIAL 0x131; //P(x)=x^8+x^5+x^4+1 = 100110001
#define TRIG_T_MEASUREMENT_HM 0xE3 // command trig. temp meas. hold master
#define TRIG_RH_MEASUREMENT_HM 0xE5 // command trig. humidity meas. hold master
#define TRIG_T_MEASUREMENT_POLL 0xF3 // command trig. temp meas. no hold master
#define TRIG_RH_MEASUREMENT_POLL 0xF5 // command trig. humidity meas. no hold master
#define USER_REG_W 0xE6 // command writing user register
#define USER_REG_R 0xE7 // command reading user register
#define SOFT_RESET 0xFE // command soft reset
#define SHT2x_RES_12_14BIT 0x00 // RH=12bit, T=14bit
#define SHT2x_RES_8_12BIT 0x01 // RH= 8bit, T=12bit
#define SHT2x_RES_10_13BIT 0x80 // RH=10bit, T=13bit
#define SHT2x_RES_11_11BIT 0x81 // RH=11bit, T=11bit
#define SHT2x_RES_MASK 0x81 // Mask for res. bits (7,0) in user reg.
#define SHT2x_EOB_ON 0x40 // end of battery
#define SHT2x_EOB_MASK 0x40 // Mask for EOB bit(6) in user reg.
#define SHT2x_HEATER_ON 0x04 // heater on
#define SHT2x_HEATER_OFF 0x00 // heater off
#define SHT2x_HEATER_MASK 0x04 // Mask for Heater bit(2) in user reg.
#define LOW 0
#define HIGH 1
#define TRUE 1
#define FALSE 0
#define CONSTANT_6 6
#define CONSTANT_125 125
#define CONSTANT_46_85 46.85
#define CONSTANT_175_72 175.72
#define RESOLUTION_16 65536 //2^16
#define ACK_ERROR 0x01
#define TIME_OUT_ERROR 0x02
#define CHECKSUM_ERROR 0x04
#define UNIT_ERROR 0x08
#define CMD_CHIP_MEMORY_LOC_1 0xFA
#define ADR_CHIP_MEMORY_LOC_1 0x0F
#define CMD_CHIP_MEMORY_LOC_2 0xFC
#define ADR_CHIP_MEMORY_LOC_2 0xC9
// #define ACK 0 in i2c.h
// #define NO_ACK 1 in i2c.h
typedef enum{
HUMIDITY,
TEMP
}etSHT2xMeasureType;
#define I2C_SHT2x_ADR 0x40 // 0x80 -> 128 sensor I2C address + write bit 0x81 -> 129 sensor I2C address + read bit
// Watch out for bit shifting with the I2C (TWI) protocol in i2c.c
#define I2C_SHT2x_ADR_W 0x80
#define I2C_SHT2x_ADR_R 0x81
uint8_t i2c_SHT2x_CheckCrc(uint8_t data[], uint8_t nbrOfBytes, uint8_t checksum);
uint8_t i2c_SHT2x_ReadUserRegister(uint8_t *pRegisterValue);
uint8_t i2c_SHT2x_WriteUserRegister(uint8_t *pRegisterValue);
uint8_t i2c_SHT2x_MeasurePoll(etSHT2xMeasureType eSHT2xMeasureType, nt16 *pMeasurand);
uint8_t i2c_SHT2x_MeasureHM(etSHT2xMeasureType eSHT2xMeasureType, nt16 *pMeasurand);
uint8_t i2c_SHT2x_SoftReset();
float i2c_SHT2x_CalcRH(uint16_t sRH);
float i2c_SHT2x_CalcTemperatureC(uint16_t sT);
uint8_t i2c_SHT2x_GetSerialNumber(uint8_t SerialNumber[]);
#endif

Binary file not shown.

Binary file not shown.

59
Typedefs.h Normal file
View File

@ -0,0 +1,59 @@
#ifndef TYPEDEFS_H
#define TYPEDEFS_H
//==============================================================================
// S E N S I R I O N AG, Laubisruetistr. 50, CH-8712 Staefa, Switzerland
//==============================================================================
// Project : SHT2x Sample Code (V1.2)
// File : typedefs.h
// Author : MST
// Controller: NEC V850/SG3 (uPD70F3740)
// Compiler : IAR compiler for V850 (3.50A)
// Brief : Definitions of typedefs for good readability and portability
//==============================================================================
//---------- Defines -----------------------------------------------------------
//Processor endian system
//#define BIG ENDIAN //e.g. Motorola (not tested at this time)
#define LITTLE_ENDIAN //e.g. PIC, 8051, NEC V850
//==============================================================================
// basic types: making the size of types clear
//==============================================================================
typedef unsigned char u8t; ///< range: 0 .. 255
typedef signed char i8t; ///< range: -128 .. +127
typedef unsigned short u16t; ///< range: 0 .. 65535
typedef signed short i16t; ///< range: -32768 .. +32767
typedef unsigned long u32t; ///< range: 0 .. 4'294'967'295
typedef signed long i32t; ///< range: -2'147'483'648 .. +2'147'483'647
typedef float ft; ///< range: +-1.18E-38 .. +-3.39E+38
typedef double dt; ///< range: .. +-1.79E+308
// #########################################################################
// --- BOOLEAN DELETED, AND DEFINE AS TRUE = 1, FALSE = 0 in I2C_SHT2x.h---
// #########################################################################
typedef union {
u16t u16; // element specifier for accessing whole u16
i16t i16; // element specifier for accessing whole i16
struct {
#ifdef LITTLE_ENDIAN // Byte-order is little endian
u8t u8L; // element specifier for accessing low u8
u8t u8H; // element specifier for accessing high u8
#else // Byte-order is big endian
u8t u8H; // element specifier for accessing low u8
u8t u8L; // element specifier for accessing high u8
#endif
} s16; // element spec. for acc. struct with low or high u8
} nt16;
typedef union {
u32t u32; // element specifier for accessing whole u32
i32t i32; // element specifier for accessing whole i32
struct {
#ifdef LITTLE_ENDIAN // Byte-order is little endian
u16t u16L; // element specifier for accessing low u16
u16t u16H; // element specifier for accessing high u16
#else // Byte-order is big endian
u16t u16H; // element specifier for accessing low u16
u16t u16L; // element specifier for accessing high u16
#endif
} s32; // element spec. for acc. struct with low or high u16
} nt32;
#endif

94
i2c.c Normal file
View File

@ -0,0 +1,94 @@
/*!
* \file i2c.c
* \author Wim Dolman (<a href="mailto:w.e.dolman@hva.nl">w.e.dolman@hva.nl</a>)
* \date 11-12-2015
* \version 1.0
*
* \brief Simple I2C function for ATxmega256a3u
*
* \details The files i2c.c and i2c.h are from w.e.dolman (<a href="mailto:w.e.dolman@hva.nl">w.e.dolman@hva.nl</a>)
* For i2c.c code 21.8 is used from: "de taal C en de Xmega tweede druk" http://dolman-wim.nl/xmega/book/index.php
* For i2c.h code 21.9 is used from: "de taal C en de Xmega tweede druk" http://dolman-wim.nl/xmega/book/index.php
*
* \verbatim
#include <i2c.h>
\endverbatim
* \par
*
* \note An AVR-project can use multiple I2C's. One shoud take care that
* in different source files there are no multiple i2c_init
* definitions for the same I2C.
*/
#include "i2c.h"
void i2c_init(TWI_t *twi, uint8_t baudRateRegisterSetting)
{
twi->MASTER.BAUD = baudRateRegisterSetting;
twi->MASTER.CTRLC = 0;
twi->MASTER.CTRLA = TWI_MASTER_ENABLE_bm;
twi->MASTER.STATUS = TWI_MASTER_BUSSTATE_IDLE_gc;
}
uint8_t i2c_start(TWI_t *twi, uint8_t address, uint8_t rw)
{
if ( (twi->MASTER.STATUS & TWI_MASTER_BUSSTATE_gm) != // if bus available
TWI_MASTER_BUSSTATE_IDLE_gc ) return I2C_STATUS_BUSY; //
twi->MASTER.ADDR = (address << 1) | rw; // send slave address
while( ! (twi->MASTER.STATUS & (TWI_MASTER_WIF_bm << rw)) ); // wait until sent
if ( twi->MASTER.STATUS & TWI_MASTER_RXACK_bm ) { // if no ack
twi->MASTER.CTRLC = TWI_MASTER_CMD_STOP_gc;
return I2C_STATUS_NO_ACK;
}
return I2C_STATUS_OK;
}
uint8_t i2c_restart(TWI_t *twi, uint8_t address, uint8_t rw)
{
twi->MASTER.ADDR = (address << 1) | rw; // send slave address
while( ! (twi->MASTER.STATUS & (TWI_MASTER_WIF_bm << rw)) ); // wait until sent
if ( twi->MASTER.STATUS & TWI_MASTER_RXACK_bm ) { // if no ack
twi->MASTER.CTRLC = TWI_MASTER_CMD_STOP_gc;
return I2C_STATUS_NO_ACK;
}
return I2C_STATUS_OK;
}
void i2c_stop(TWI_t *twi)
{
twi->MASTER.CTRLC = TWI_MASTER_CMD_STOP_gc;
twi->MASTER.STATUS = TWI_MASTER_BUSSTATE_IDLE_gc;
}
uint8_t i2c_write(TWI_t *twi, uint8_t data)
{
twi->MASTER.DATA = data; // send data
while( ! (twi->MASTER.STATUS & TWI_MASTER_WIF_bm) ); // wait until sent
if ( twi->MASTER.STATUS & TWI_MASTER_RXACK_bm ) { // if no ack
twi->MASTER.CTRLC = TWI_MASTER_CMD_STOP_gc;
return I2C_STATUS_NO_ACK;
}
return I2C_STATUS_OK;
}
uint8_t i2c_read(TWI_t *twi, uint8_t ack)
{
uint8_t data;
while( ! (twi->MASTER.STATUS & TWI_MASTER_RIF_bm) ); // wait until received
data = twi->MASTER.DATA; // read data
twi->MASTER.CTRLC = ((ack==I2C_ACK) ? TWI_MASTER_CMD_RECVTRANS_gc : // send ack (go on) or
TWI_MASTER_ACKACT_bm|TWI_MASTER_CMD_STOP_gc); // nack (and stop)
if ( ack == I2C_NACK ) {
while( ! (twi->MASTER.STATUS & TWI_MASTER_BUSSTATE_IDLE_gc) );
}
return data;
}

41
i2c.h Normal file
View File

@ -0,0 +1,41 @@
/*!
* \file i2c.c
* \author Wim Dolman (<a href="mailto:w.e.dolman@hva.nl">w.e.dolman@hva.nl</a>)
* \date 11-12-2015
* \version 1.0
*
* \brief Simple I2C function for ATxmega256a3u
*
* \details The files i2c.c and i2c.h are from w.e.dolman (<a href="mailto:w.e.dolman@hva.nl">w.e.dolman@hva.nl</a>)
* For i2c.c code 21.8 is used from: "de taal C en de Xmega tweede druk" http://dolman-wim.nl/xmega/book/index.php
* For i2c.h code 21.9 is used from: "de taal C en de Xmega tweede druk" http://dolman-wim.nl/xmega/book/index.php
*
* \verbatim
#include <i2c.h>
\endverbatim
* \par
*
* \note An AVR-project can use multiple I2C's. One shoud take care that
* in different source files there are no multiple i2c_init
* definitions for the same I2C.
*/
#include <avr/io.h>
#define TWI_BAUD(F_SYS, F_TWI) ((F_SYS / (2 * F_TWI)) - 5)
#define I2C_ACK 0
#define I2C_NACK 1
#define I2C_READ 1
#define I2C_WRITE 0
#define I2C_STATUS_OK 0
#define I2C_STATUS_BUSY 1
#define I2C_STATUS_NO_ACK 2
void i2c_init(TWI_t *twi, uint8_t baudRateRegisterSetting);
uint8_t i2c_start(TWI_t *twi, uint8_t address, uint8_t rw);
uint8_t i2c_restart(TWI_t *twi, uint8_t address, uint8_t rw);
void i2c_stop(TWI_t *twi);
uint8_t i2c_write(TWI_t *twi, uint8_t data);
uint8_t i2c_read(TWI_t *twi, uint8_t ack);

191
i2c_lcd.c Normal file
View File

@ -0,0 +1,191 @@
/*!
* \file i2c_lcd.c
* \author Patrick Taling (not the original author)
* \date 20/02/2017
* \version 1.0
*
* \brief Simple I2C LCD library to write text to a I2C lcd (PCF8574T adress 0x27) with the ATxmega256a3u.
*
* \details The file i2c_lcd.c is the library for a I2C lcd (PCF8574T adress 0x27)
* The library needs some parts of the i2c_lcd library from Noel200 from http://www.elektroda.pl/rtvforum/topic2756081.html.
* The library can be downloaded from: http://www.elektroda.pl/rtvforum/login.php?redirect=download.php&id=670533.
* Go to LCD_PCF8574T/lcd_pcf/ and use i2c_lcd.c and i2c_lcd.h from the pakkage
*
* The library needs the i2c library from w.e.dolman (<a href="mailto:w.e.dolman@hva.nl">w.e.dolman@hva.nl</a>)
* For i2c.c use code 21.8 from "de taal C en de Xmega tweede druk" http://dolman-wim.nl/xmega/book/index.php
* For i2c.h use code 21.9 from "de taal C en de Xmega tweede druk" http://dolman-wim.nl/xmega/book/index.php
*
*
* ## Original author information ##
Obs³uga wyœwietlacza HD44780 po I2C za pomoc¹ PCF8574T.
2015-01-DASEJ , dasej(at)wp.pl
AVR Studio 4.18, programator AVR PROG MKII,
Procesor Atmega328P 16 MHz, +5V.
* ####
*
*
* \verbatim
#include <i2c_lcd.h>
\endverbatim
* \par
*
* \note An AVR-project can use multiple I2C's. One shoud take care that
* in different source files there are no multiple I2C
* definitions for the same I2C.
*/
#define F_CPU 2000000UL
#include "i2c_lcd.h"
#include <util/delay.h>
char i2c_lcd_status = 0X00;
volatile uint8_t lcd_line = 0;
void i2c_lcd_write_status(void)
{
i2c_start(&TWIE, i2c_lcd_ADDR, 0);
i2c_write(&TWIE, i2c_lcd_status);
i2c_stop(&TWIE);
}
void i2c_lcd_data_part(char data_part)
{
i2c_lcd_status &= ~i2c_lcd_DB4 & ~i2c_lcd_DB5 & ~i2c_lcd_DB6 & ~i2c_lcd_DB7;
if(data_part & 0x01) i2c_lcd_status |= i2c_lcd_DB4;
if(data_part & 0x02) i2c_lcd_status |= i2c_lcd_DB5;
if(data_part & 0x04) i2c_lcd_status |= i2c_lcd_DB6;
if(data_part & 0x08) i2c_lcd_status |= i2c_lcd_DB7;
}
void i2c_lcd_write(char data)
{
i2c_lcd_e_hi();
i2c_lcd_data_part(data >> 4);
i2c_lcd_write_status();
i2c_lcd_e_lo();
i2c_lcd_write_status();
i2c_lcd_e_hi();
i2c_lcd_data_part(data);
i2c_lcd_write_status();
i2c_lcd_e_lo();
i2c_lcd_write_status();
_delay_ms(2);
}
void i2c_lcd_write_instruction(char instruction)
{
i2c_lcd_rw_lo();
i2c_lcd_rs_lo();
i2c_lcd_write(instruction);
}
void i2c_lcd_write_data(char data)
{
i2c_lcd_rs_hi();
switch (data) {
case '\f':
i2c_lcd_clear();
lcd_line = 0;
break;
case '\n':
if (++lcd_line==LCD_LINES) lcd_line = 0;
i2c_lcd_set_cursor(0, lcd_line);
break;
default:
i2c_lcd_write(data);
break;
}
}
void i2c_lcd_write_text(char *text)
{
while(*text) i2c_lcd_write_data(*text++);
}
void i2c_lcd_clear(void)
{
lcd_line = 0;
i2c_lcd_write_instruction(0x01);
}
void i2c_lcd_set_cursor(char x, char y)
{
uint8_t address;
#if LCD_LINES==1
address = LCD_START_LINE1;
#elif LCD_LINES==2
if ( y==0 ) {
address = LCD_START_LINE1;
} else {
address = LCD_START_LINE2;
}
#else
if ( y==0 ) {
address = LCD_START_LINE1;
} else if ( y==1) {
address = LCD_START_LINE2;
} else if ( y==2) {
address = LCD_START_LINE3;
} else {
address = LCD_START_LINE4;
}
#endif
i2c_lcd_write_instruction(HD44780_DDRAM_SET | (x + (address * y)));
}
void i2c_lcd_led_on(void)
{
i2c_lcd_led_hi();
i2c_lcd_write_status();
}
void i2c_lcd_led_off(void)
{
i2c_lcd_led_lo();
i2c_lcd_write_status();
}
void i2c_lcd_home(void)
{
lcd_line = 0;
i2c_lcd_set_cursor(0,0);
}
void i2c_lcd_init(void)
{
char i;
_delay_ms(15);
for(i = 0; i < 3; i++)
{
i2c_lcd_data_part(0x03);
i2c_lcd_e_hi();
i2c_lcd_write_status();
i2c_lcd_e_lo();
i2c_lcd_write_status();
_delay_ms(4);
}
i2c_lcd_data_part(0x02);
i2c_lcd_e_hi();
i2c_lcd_write_status();
i2c_lcd_e_lo();
i2c_lcd_write_status();
_delay_ms(1);
i2c_lcd_write_instruction(HD44780_FUNCTION_SET | HD44780_FONT5x10 | HD44780_TWO_LINE | HD44780_4_BIT); // interfejs 4-bity, 2-linie, znak 5x7
i2c_lcd_write_instruction(HD44780_DISPLAY_ONOFF | HD44780_DISPLAY_OFF); // wy³¹czenie wyswietlacza
i2c_lcd_write_instruction(HD44780_CLEAR); // czyszczenie zawartosæi pamieci DDRAM
_delay_ms(2);
i2c_lcd_write_instruction(HD44780_ENTRY_MODE | HD44780_EM_SHIFT_CURSOR | HD44780_EM_INCREMENT);// inkrementaja adresu i przesuwanie kursora
i2c_lcd_write_instruction(HD44780_DISPLAY_ONOFF | HD44780_DISPLAY_ON | HD44780_CURSOR_OFF | HD44780_CURSOR_NOBLINK); // w³¹cz LCD, bez kursora i mrugania
}

133
i2c_lcd.h Normal file
View File

@ -0,0 +1,133 @@
/*!
* \file i2c_lcd.h
* \author Patrick Taling (not the original author)
* \date 20/02/2017
* \version 1.0
*
* \brief Simple I2C LCD library to write text to a I2C lcd (PCF8574T adress 0x27) with the ATxmega256a3u.
*
* \details The file i2c_lcd.h is the library for a I2C lcd (PCF8574T adress 0x27)
* The library needs some parts of the i2c_lcd library from Noel200 from http://www.elektroda.pl/rtvforum/topic2756081.html.
* The library can be downloaded from: http://www.elektroda.pl/rtvforum/login.php?redirect=download.php&id=670533.
* Go to LCD_PCF8574T/lcd_pcf/ and use i2c_lcd.c and i2c_lcd.h from the pakkage
*
* The library needs the i2c library from w.e.dolman (<a href="mailto:w.e.dolman@hva.nl">w.e.dolman@hva.nl</a>)
* For i2c.c use code 21.8 from "de taal C en de Xmega tweede druk" http://dolman-wim.nl/xmega/book/index.php
* For i2c.h use code 21.9 from "de taal C en de Xmega tweede druk" http://dolman-wim.nl/xmega/book/index.php
*
*
* ## Original author information ##
Obs³uga wyœwietlacza HD44780 po I2C za pomoc¹ PCF8574T.
2015-01-DASEJ , dasej(at)wp.pl
AVR Studio 4.18, programator AVR PROG MKII,
Procesor Atmega328P 16 MHz, +5V.
* ####
*
*
* \verbatim
#include <i2c.h>
\endverbatim
* \par
*
* \note An AVR-project can use multiple I2C's. One shoud take care that
* in different source files there are no multiple I2C
* definitions for the same I2C.
*/
#include <util/delay.h>
#include "i2c.h"
#define LCD_LINES 2 //!< Number of visible lines of the display
#define LCD_DISP_LENGTH 16 //!< Visible characters per line of the display
#if LCD_DISP_LENGTH==16
#define LCD_START_LINE1 0x00 //!< DDRAM address of first char of line 1
#define LCD_START_LINE2 0x40 //!< DDRAM address of first char of line 2
#define LCD_START_LINE3 0x10 //!< DDRAM address of first char of line 3
#define LCD_START_LINE4 0x50 //!< DDRAM address of first char of line 4
#else
#define LCD_START_LINE1 0x00 //!< DDRAM address of first char of line 1
#define LCD_START_LINE2 0x40 //!< DDRAM address of first char of line 2
#define LCD_START_LINE3 0x14 //!< DDRAM address of first char of line 3
#define LCD_START_LINE4 0x54 //!< DDRAM address of first char of line 4
#endif
#define i2c_lcd_RS (1 << 0)
#define i2c_lcd_RW (1 << 1)
#define i2c_lcd_E (1 << 2)
#define i2c_lcd_LED (1 << 3)
#define i2c_lcd_DB4 (1 << 4)
#define i2c_lcd_DB5 (1 << 5)
#define i2c_lcd_DB6 (1 << 6)
#define i2c_lcd_DB7 (1 << 7)
#define i2c_lcd_rs_lo() i2c_lcd_status &= ~i2c_lcd_RS
#define i2c_lcd_rs_hi() i2c_lcd_status |= i2c_lcd_RS
#define i2c_lcd_rw_lo() i2c_lcd_status &= ~i2c_lcd_RW
#define i2c_lcd_rw_hi() i2c_lcd_status |= i2c_lcd_RW
#define i2c_lcd_e_lo() i2c_lcd_status &= ~i2c_lcd_E
#define i2c_lcd_e_hi() i2c_lcd_status |= i2c_lcd_E
#define i2c_lcd_led_lo() i2c_lcd_status &= ~i2c_lcd_LED
#define i2c_lcd_led_hi() i2c_lcd_status |= i2c_lcd_LED
#define HD44780_ENTRY_MODE 0x04
#define HD44780_EM_SHIFT_CURSOR 0
#define HD44780_EM_SHIFT_DISPLAY 1
#define HD44780_EM_DECREMENT 0
#define HD44780_EM_INCREMENT 2
#define HD44780_DISPLAY_ONOFF 0x08
#define HD44780_DISPLAY_OFF 0
#define HD44780_DISPLAY_ON 4
#define HD44780_CURSOR_OFF 0
#define HD44780_CURSOR_ON 2
#define HD44780_CURSOR_NOBLINK 0
#define HD44780_CURSOR_BLINK 1
#define HD44780_DISPLAY_CURSOR_SHIFT 0x10
#define HD44780_SHIFT_CURSOR 0
#define HD44780_SHIFT_DISPLAY 8
#define HD44780_SHIFT_LEFT 0
#define HD44780_SHIFT_RIGHT 4
#define HD44780_FUNCTION_SET 0x20
#define HD44780_FONT5x7 0
#define HD44780_FONT5x10 4
#define HD44780_ONE_LINE 0
#define HD44780_TWO_LINE 8
#define HD44780_4_BIT 0
#define HD44780_8_BIT 16
#define HD44780_CGRAM_SET 0x40
#define HD44780_DDRAM_SET 0x80
#define HD44780_CLEAR 0x01
#define i2c_lcd_ADDR 0x27 //I2C LCD adres.
char i2c_lcd_status;
void i2c_lcd_write_status(void);
void i2c_lcd_data_part(char data_part);
void i2c_lcd_write(char data);
void i2c_lcd_write_instruction(char instruction);
void i2c_lcd_write_data(char data);
void i2c_lcd_write_text(char *text);
void i2c_lcd_clear(void);
void i2c_lcd_set_cursor(char x, char y);
void i2c_lcd_led_on(void);
void i2c_lcd_led_off(void);
void i2c_lcd_init(void);

191
main.c Normal file
View File

@ -0,0 +1,191 @@
/*!
* \file main.c
* \author Patrick Taling
* \date 31/03/2017
* \version 1.0
*
* \brief
* Simple I2C SHT2x library to measure relative humidity and temperature and write it to an I2C LCD with the ATxmega256a3u.
* Rights are owned by the original authors (Atmel, w.e.dolman, Noel200 (Elektroda) and Sensirion)
*
* \Hardware
* # 1602 I2c HD44780 LCD from HobbyElectronica https://www.hobbyelectronica.nl/product/1602-lcd-i2c-blauw-backlight/
* # HvA Xmega-bord (ATxmega256a3u with programmer/ USB-RS232-interface ATxmega32a4u)
* # 3.3V - 5V levelshifter with two BS170 N-channel MOSFET
* # Humidity/ temperature sensor module (EBM016) https://www.elektor.nl/humidity-sensor-module-ebm016
*
* \development
* # Atmel Studio 7 (version: 7.0.118)
* # OS Version: Microsoft Windows NT 6.2.9200.0 (Platform: Win32NT)
* # Atmel Gallary (7.8)
*
* \details
* #The file main.c is the main to write text to a I2C lcd (PCF8574T adress 0x27) with the ATxmega256a3u.
* #For the use of the main code you need the i2c library from w.e.dolman (<a href="mailto:w.e.dolman@hva.nl">w.e.dolman@hva.nl</a>)
* #For i2c.c use code 21.8 from "de taal C en de Xmega tweede druk" http://dolman-wim.nl/xmega/book/index.php
* #For i2c.h use code 21.9 from "de taal C en de Xmega tweede druk" http://dolman-wim.nl/xmega/book/index.php
*
* #The main code needs some parts of the i2c_lcd library from Noel200 from http://www.elektroda.pl/rtvforum/topic2756081.html.
* #The library can be downloaded from: http://www.elektroda.pl/rtvforum/login.php?redirect=download.php&id=670533.
* #Go to LCD_PCF8574T/lcd_pcf/ and use i2c_lcd.c and i2c_lcd.h from the pakkage
*
* #The libraby needs some parts of the the SHT2x library from SENIRION from https://www.sensirion.com/en/products/humidity-sensors/humidity-temperature-sensor-sht2x-digital-i2c-accurate/
* #The libraby can be download from: https://www.sensirion.com/en/products/all-documents-of-sensirions-humidity-sensors-for-download/
* # Go to SHT2x/ Sample Code SHT21 and download the zip file Sensirion_Humidity_Sensors_SHT21_Sample_Code_C-file
* \note the following files aren't fully used. Most parts are used in other .c of .h files or disabled.
* DisplayDip204.C, DisplayDip204.h,
* I2C_HAL.c, I2C_HAL.h,
* System.c, System.h and
* io70f3740.h.
* \note for the use of two SHT2X you should use different IOs for SDA or additional hardware such as I2C multiplexer.
* The adress of the SHT2x cant be changed.
*
* \verbatim
* #include <i2c_lcd.h>
* #include <I2C_SHT2x.h>
* #include <Typedefs.h>
\endverbatim
* \par
*
* \note An AVR-project can use multiple I2C's. One shoud take care that
* in different source files there are no multiple i2c_init
* definitions for the same I2C.
*/
#define F_CPU 2000000UL
#include <avr/io.h>
#include <avr/interrupt.h>
#include <util/delay.h>
#include <stdio.h>
#include <stdlib.h>
#define BAUD_100K 100000UL
#include "I2C_SHT2x.h"
#include "Typedefs.h"
#include "i2c_lcd.h"
//==============================================================================
int main()
//==============================================================================
{ // variables
uint8_t error = 0;
uint8_t userRegister;
int endOfBattery;
nt16 sRH;
float humidityRH = 0;
nt16 sT;
float temperatureC = 0;
uint8_t SerialNumber_SHT2x[8];
char buffer[20];
uint16_t h;
i2c_init(&TWIE, TWI_BAUD(F_CPU, BAUD_100K));
PORTE.DIRSET = PIN1_bm|PIN0_bm; //SDA 0 SCL 1
i2c_lcd_init();
i2c_lcd_led_on();
i2c_lcd_set_cursor(0,0);
_delay_ms(15); //initialization powerUp SHT2x (15ms)
i2c_lcd_clear();
_delay_us(1500); //initialization powerUp LCD (1.5ms)
i2c_lcd_set_cursor(0,0);
i2c_lcd_write_text("T :");
i2c_lcd_write_text("--.-- C");
i2c_lcd_set_cursor(0,1);
i2c_lcd_write_text("RH:");
i2c_lcd_write_text("--.-- %");
while(1)
{
error = 0; // reset error status
//=====================================================
// --- Reset sensor by command ---
//=====================================================
error |= i2c_SHT2x_SoftReset();
//=====================================================
// --- Read the sensors serial number (64bit) ---
//=====================================================
error |= i2c_SHT2x_GetSerialNumber(SerialNumber_SHT2x);
//=====================================================
// --- Set Resolution e.g. RH 10bit, Temp 13bit ---
//=====================================================
error |= i2c_SHT2x_ReadUserRegister(&userRegister);
userRegister = (userRegister & ~SHT2x_RES_MASK) | SHT2x_RES_10_13BIT;
error |= i2c_SHT2x_WriteUserRegister(&userRegister);
//=====================================================
// --- measure humidity with "Hold Master Mode (HM)" ---
//=====================================================
error |= i2c_SHT2x_MeasureHM(TEMP, &sT);
error |= i2c_SHT2x_MeasureHM(HUMIDITY, &sRH);
//=====================================================
// --- measure temperature with "Polling Mode" (no hold master) ---
// --- Disabled due to error in TEMP ----
//=====================================================
//error |= i2c_SHT2x_MeasurePoll(HUMIDITY, &sRH); //works fine
//error |= i2c_SHT2x_MeasurePoll(TEMP, &sT); // Has an error in reading measuring
//=====================================================
//-- calculate humidity and temperature --
//=====================================================
temperatureC = i2c_SHT2x_CalcTemperatureC(sT.u16);
humidityRH = i2c_SHT2x_CalcRH(sRH.u16);
//=====================================================
// --- check end of battery status (eob)---
//=====================================================
error |= i2c_SHT2x_ReadUserRegister(&userRegister); //get actual user reg
if( (userRegister & SHT2x_EOB_MASK) == SHT2x_EOB_ON ) endOfBattery = TRUE;
else endOfBattery = FALSE;
//=====================================================
//-- write humidity, temperature or error values on LCD --
//=====================================================
if(error != 0){
i2c_lcd_clear();
_delay_us(1500);
i2c_lcd_write_text("An ERROR");
i2c_lcd_set_cursor(0,1);
i2c_lcd_write_text("has occurred");
}
else if (endOfBattery){
i2c_lcd_clear();
_delay_us(1500);
i2c_lcd_write_text("LOW BATTERY");
}
else{
i2c_lcd_clear();
_delay_us(1500);
i2c_lcd_set_cursor(0,0);
h= temperatureC;
i2c_lcd_write_text("T :");
utoa(temperatureC, buffer, 10);
i2c_lcd_write_text(buffer);
i2c_lcd_write_text(".");
utoa((temperatureC-h)*100, buffer, 10);
i2c_lcd_write_text(buffer);
i2c_lcd_write_text(" C");
i2c_lcd_set_cursor(0,1);
h= humidityRH;
i2c_lcd_write_text("RH:");
utoa(humidityRH, buffer, 10);
i2c_lcd_write_text(buffer);
i2c_lcd_write_text(".");
utoa((humidityRH-h)*100, buffer, 10);
i2c_lcd_write_text(buffer);
i2c_lcd_write_text(" %");
}
_delay_ms(300); // wait 3s for next measurement
}
}