Commit 6ff10b69 authored by Matthieu Cattin's avatar Matthieu Cattin

sw: Work on altimeter driver, can read calibration data and print on screen but…

sw: Work on altimeter driver, can read calibration data and print on screen but doesn't look good...
parent 88d6164e
# Copyright (C) 2014 Julian Lewis
# @author Maciej Suminski <maciej.suminski@cern.ch>
#
# This program is free software; you can redistribute it and/or
# modify it under the terms of the GNU General Public License
# as published by the Free Software Foundation; either version 2
# of the License, or (at your option) any later version.
#
# This program 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 General Public License for more details.
#
# You should have received a copy of the GNU General Public License
# along with this program; if not, you may find one here:
# http://www.gnu.org/licenses/old-licenses/gpl-2.0.html
# or you may search the http://www.gnu.org website for the version 2 license,
# or you may write to the Free Software Foundation, Inc.,
# 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301, USA
####################################################################
# Makefile #
####################################################################
.SUFFIXES: # ignore builtin rules
.PHONY: all debug release clean flash
####################################################################
# Definitions #
####################################################################
DEVICE = EFM32GG330F1024
PROJECTNAME = freewatch
# Name of interface configuration file used by OpenOCD
OOCD_IFACE ?= stlink-v2-1
OBJ_DIR = build
EXE_DIR = exe
LST_DIR = lst
####################################################################
# Definitions of toolchain. #
# You might need to do changes to match your system setup #
####################################################################
# Change path to the tools according to your system configuration
# DO NOT add trailing whitespace chars, they do matter !
WINDOWSCS ?= GNU Tools ARM Embedded\4.7 2012q4
LINUXCS ?= /opt/gcc-arm-none-eabi-4_8-2014q2
RMDIRS := rm -rf
RMFILES := rm -rf
ALLFILES := /*.*
NULLDEVICE := /dev/null
SHELLNAMES := $(ComSpec)$(COMSPEC)
# Try autodetecting the environment
ifeq ($(SHELLNAMES),)
# Assume we are making on a Linux platform
TOOLDIR := $(LINUXCS)
else
QUOTE :="
ifneq ($(COMSPEC),)
# Assume we are making on a mingw/msys/cygwin platform running on Windows
# This is a convenient place to override TOOLDIR, DO NOT add trailing
# whitespace chars, they do matter !
TOOLDIR := $(PROGRAMFILES)/$(WINDOWSCS)
ifeq ($(findstring cygdrive,$(shell set)),)
# We were not on a cygwin platform
NULLDEVICE := NUL
endif
else
# Assume we are making on a Windows platform
# This is a convenient place to override TOOLDIR, DO NOT add trailing
# whitespace chars, they do matter !
SHELL := $(SHELLNAMES)
TOOLDIR := $(ProgramFiles)/$(WINDOWSCS)
RMDIRS := rd /s /q
RMFILES := del /s /q
ALLFILES := \*.*
NULLDEVICE := NUL
endif
endif
# Create directories and do a clean which is compatible with parallel make
$(shell mkdir $(OBJ_DIR)>$(NULLDEVICE) 2>&1)
$(shell mkdir $(EXE_DIR)>$(NULLDEVICE) 2>&1)
$(shell mkdir $(LST_DIR)>$(NULLDEVICE) 2>&1)
ifeq (clean,$(findstring clean, $(MAKECMDGOALS)))
ifneq ($(filter $(MAKECMDGOALS),all debug release),)
$(shell $(RMFILES) $(OBJ_DIR)$(ALLFILES)>$(NULLDEVICE) 2>&1)
$(shell $(RMFILES) $(EXE_DIR)$(ALLFILES)>$(NULLDEVICE) 2>&1)
$(shell $(RMFILES) $(LST_DIR)$(ALLFILES)>$(NULLDEVICE) 2>&1)
endif
endif
CC = $(QUOTE)$(TOOLDIR)/bin/arm-none-eabi-gcc$(QUOTE)
LD = $(QUOTE)$(TOOLDIR)/bin/arm-none-eabi-ld$(QUOTE)
AR = $(QUOTE)$(TOOLDIR)/bin/arm-none-eabi-ar$(QUOTE)
OBJCOPY = $(QUOTE)$(TOOLDIR)/bin/arm-none-eabi-objcopy$(QUOTE)
DUMP = $(QUOTE)$(TOOLDIR)/bin/arm-none-eabi-objdump$(QUOTE)
####################################################################
# Flags #
####################################################################
# -MMD : Don't generate dependencies on system header files.
# -MP : Add phony targets, useful when a h-file is removed from a project.
# -MF : Specify a file to write the dependencies to.
DEPFLAGS = -MMD -MP -MF $(@:.o=.d)
#
# Add -Wa,-ahld=$(LST_DIR)/$(@F:.o=.lst) to CFLAGS to produce assembly list files
#
override CFLAGS += -D$(DEVICE) -Wall -Wextra -mcpu=cortex-m3 -mthumb \
-mfix-cortex-m3-ldrd -ffunction-sections \
-fdata-sections -fomit-frame-pointer -DDEBUG_EFM \
$(DEPFLAGS)
override ASMFLAGS += -x assembler-with-cpp -D$(DEVICE) -Wall -Wextra -mcpu=cortex-m3 -mthumb
#
# NOTE: The -Wl,--gc-sections flag may interfere with debugging using gdb.
#
override LDFLAGS += -Xlinker -Map=$(LST_DIR)/$(PROJECTNAME).map -mcpu=cortex-m3 \
-mthumb -T../common/Device/EnergyMicro/EFM32GG/Source/GCC/efm32gg.ld \
-Wl,--gc-sections
LIBS = -Wl,--start-group -lgcc -lc -lnosys -Wl,--end-group
INCLUDEPATHS += \
-I../common/CMSIS/Include \
-I../common/Device/EnergyMicro/EFM32GG/Include \
-I../common/emlib/inc \
-I../common/drivers \
-I../common/glib \
-I../common
####################################################################
# Files #
####################################################################
C_SRC += \
../common/Device/EnergyMicro/EFM32GG/Source/system_efm32gg.c \
../common/drivers/lcd.c \
../common/emlib/src/em_assert.c \
../common/emlib/src/em_cmu.c \
../common/emlib/src/em_emu.c \
../common/emlib/src/em_gpio.c \
../common/emlib/src/em_i2c.c \
../common/emlib/src/em_int.c \
../common/emlib/src/em_system.c \
../common/emlib/src/em_rtc.c \
../common/emlib/src/em_usart.c \
../common/gfx/graphics.c \
../common/gfx/font_helv11.c \
../common/gfx/font_helv17.c \
../common/gfx/font_helv17b.c \
../common/gfx/font_xm4x5.c \
../common/gfx/font_xm4x6.c \
../common/udelay.c \
../common/drivers/i2cdrv.c \
../common/drivers/altimeter.c \
main.c
#../common/drivers/display.c \
#../common/drivers/displayls013b7dh03.c \
#../common/drivers/displaypalemlib.c \
s_SRC +=
S_SRC += \
../common/Device/EnergyMicro/EFM32GG/Source/GCC/startup_efm32gg.S
####################################################################
# Rules #
####################################################################
C_FILES = $(notdir $(C_SRC) )
S_FILES = $(notdir $(S_SRC) $(s_SRC) )
#make list of source paths, sort also removes duplicates
C_PATHS = $(sort $(dir $(C_SRC) ) )
S_PATHS = $(sort $(dir $(S_SRC) $(s_SRC) ) )
C_OBJS = $(addprefix $(OBJ_DIR)/, $(C_FILES:.c=.o))
S_OBJS = $(if $(S_SRC), $(addprefix $(OBJ_DIR)/, $(S_FILES:.S=.o)))
s_OBJS = $(if $(s_SRC), $(addprefix $(OBJ_DIR)/, $(S_FILES:.s=.o)))
C_DEPS = $(addprefix $(OBJ_DIR)/, $(C_FILES:.c=.d))
OBJS = $(C_OBJS) $(S_OBJS) $(s_OBJS)
vpath %.c $(C_PATHS)
vpath %.s $(S_PATHS)
vpath %.S $(S_PATHS)
# Default build is debug build
all: debug
debug: CFLAGS += -DDEBUG -O0 -g
debug: $(EXE_DIR)/$(PROJECTNAME).bin
release: CFLAGS += -DNDEBUG -O0 -g
release: $(EXE_DIR)/$(PROJECTNAME).bin
# Create objects from C SRC files
$(OBJ_DIR)/%.o: %.c
@echo "Building file: $<"
$(CC) $(CFLAGS) $(INCLUDEPATHS) -c -o $@ $<
# Assemble .s/.S files
$(OBJ_DIR)/%.o: %.s
@echo "Assembling $<"
$(CC) $(ASMFLAGS) $(INCLUDEPATHS) -c -o $@ $<
$(OBJ_DIR)/%.o: %.S
@echo "Assembling $<"
$(CC) $(ASMFLAGS) $(INCLUDEPATHS) -c -o $@ $<
# Link
$(EXE_DIR)/$(PROJECTNAME).out: $(OBJS)
@echo "Linking target: $@"
$(CC) $(LDFLAGS) $(OBJS) $(LIBS) -o $(EXE_DIR)/$(PROJECTNAME).out
# Create binary file
$(EXE_DIR)/$(PROJECTNAME).bin: $(EXE_DIR)/$(PROJECTNAME).out
@echo "Creating binary file"
$(OBJCOPY) -O binary $(EXE_DIR)/$(PROJECTNAME).out $(EXE_DIR)/$(PROJECTNAME).bin
# Uncomment next line to produce assembly listing of entire program
# $(DUMP) -h -S -C $(EXE_DIR)/$(PROJECTNAME).out>$(LST_DIR)/$(PROJECTNAME)out.lst
clean:
ifeq ($(filter $(MAKECMDGOALS),all debug release),)
$(RMDIRS) $(OBJ_DIR) $(LST_DIR) $(EXE_DIR)
endif
flash: $(EXE_DIR)/$(PROJECTNAME).bin
openocd -s ../common/openocd -f interface/$(OOCD_IFACE).cfg -f init.cfg -c "program $(EXE_DIR)/$(PROJECTNAME).bin 0 verify reset"
# include auto-generated dependency files (explicit rules)
ifneq (clean,$(findstring clean, $(MAKECMDGOALS)))
-include $(C_DEPS)
endif
#! /bin/sh
sudo OOCD_IFACE=stlink-v2 make flash
/*
* Copyright (C) 2014 Julian Lewis
* @author Maciej Suminski <maciej.suminski@cern.ch>
*
* This program is free software; you can redistribute it and/or
* modify it under the terms of the GNU General Public License
* as published by the Free Software Foundation; either version 2
* of the License, or (at your option) any later version.
*
* This program 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 General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, you may find one here:
* http://www.gnu.org/licenses/old-licenses/gpl-2.0.html
* or you may search the http://www.gnu.org website for the version 2 license,
* or you may write to the Free Software Foundation, Inc.,
* 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301, USA
*/
/**
* @brief Main file.
*/
#include <stdio.h>
#include <udelay.h>
#include <i2cdrv.h>
#include <em_device.h>
#include <em_cmu.h>
#include <em_gpio.h>
#include <drivers/lcd.h>
#include <gfx/graphics.h>
#include <drivers/altimeter.h>
/* Counts 1ms timeTicks */
volatile uint32_t msTicks;
/*
* @brief SysTick_Handler
* Interrupt Service Routine for system tick counter
*/
void SysTick_Handler(void)
{
msTicks++; /* increment counter necessary in Delay()*/
}
/*
* @brief Delays number of msTick Systicks (typically 1 ms)
* @param dlyTicks Number of ticks to delay
*/
void Delay(uint32_t dlyTicks)
{
uint32_t curTicks;
curTicks = msTicks;
while ((msTicks - curTicks) < dlyTicks);
}
/**
* @brief Main function
*/
int main(void)
{
I2C_Init_TypeDef i2cInit = I2C_INIT_DEFAULT;
int x, y, i;
char str[20];
uint8_t cmd;
uint8_t buf[16];
uint16_t calib_data[8];
/* Setup SysTick Timer for 1 msec interrupts */
if (SysTick_Config(CMU_ClockFreqGet(cmuClock_CORE) / 1000)) while (1);
CMU_ClockEnable(cmuClock_HFPER, true);
CMU_ClockEnable(cmuClock_GPIO, true);
// Backlight LEDs
GPIO_PinModeSet(gpioPortE, 11, gpioModePushPull, 0);
GPIO_PinModeSet(gpioPortE, 12, gpioModePushPull, 0);
lcd_init();
UDELAY_Calibrate();
I2CDRV_Init(&i2cInit);
ms5806_write_cmd(MS5806_CMD_RESET);
GPIO_PinOutSet(gpioPortE, 11);
for(i=0; i<MS5806_PROM_SIZE; i++)
{
cmd = MS5806_CMD_READ_PROM + (MS5806_PROM_ADR_MASK & (i << 1));
ms5806_read_reg(cmd, 2, &buf[2*i]);
//ms5806_read_reg(cmd, 2, (uint8_t*) calib_data);
//sprintf(str, "C%d:0x%x",i,calib_data[i]);
sprintf(str, "C%d:0x%x%x",i,buf[2*i],buf[2*i+1]);
text(&font_helv17, 5, 15*i, str);
lcd_update();
}
GPIO_PinOutSet(gpioPortE, 12);
/* Infinite blink loop */
while (1) {
Delay(200);
GPIO_PinOutClear(gpioPortE, 11);
GPIO_PinOutClear(gpioPortE, 12);
}
}
......@@ -26,22 +26,61 @@
#include "altimeter.h"
#include "i2cdrv.h"
#include <udelay.h>
static uint16_t calib_data[8];
// Only send a command (no reply expected)
uint8_t ms5806_write_cmd(uint8_t command)
uint8_t ms5806_write_cmd(uint8_t cmd)
{
// MS5806_ADDRESS
I2C_TransferSeq_TypeDef seq;
I2C_TransferReturn_TypeDef ret;
seq.addr = MS5806_ADDRESS;
seq.flags = I2C_FLAG_WRITE; // sequence: write command (1 byte)
// Add command to buffer
seq.buf[0].data = cmd;
seq.buf[0].len = 1;
// Initiate transfer
ret = I2CDRV_Transfer(&seq);
if(ret != i2cTransferDone)
{
return((uint8_t) ret);
}
return 0;
}
// Send a command and reads the reply
uint8_t ms5806_read_reg(uint8_t command, uint8_t length, uint8_t* buffer)
uint8_t ms5806_read_reg(uint8_t cmd, uint8_t length, uint8_t* buffer)
{
// MS5806_ADDRESS
I2C_TransferSeq_TypeDef seq;
I2C_TransferReturn_TypeDef ret;
seq.addr = MS5806_ADDRESS;
seq.flags = I2C_FLAG_WRITE_READ; // sequence: write command (1 byte), read (n bytes)
// Add command to sequence
seq.buf[0].data = cmd;
seq.buf[0].len = 1;
//
seq.buf[1].data = buffer;
seq.buf[1].len = length;
// Initiate transfer
ret = I2CDRV_Transfer(&seq);
if(ret != i2cTransferDone)
{
return((uint8_t) ret);
}
return 0;
}
......@@ -52,14 +91,17 @@ void alti_init(void)
{
uint8_t i, cmd, ret;
// calibrate udelay, TODO: move it out of altimeter driver
UDELAY_Calibrate();
// Reset
ret = ms5806_write_cmd(MS5806_CMD_RESET); // TODO: do something with the return value
// Reads calibration data and store them in static variable
for(i=0; i<MS5806_PROM_SIZE; i++)
{
cmd = MS5806_CMD_READ_PROM + (MS5906_PROM_ADR_MASK & (i << 1));
ret = ms5806_read_reg(cmd, 2, calib_data[i]); // TODO: do something with the return value
cmd = MS5806_CMD_READ_PROM + (MS5806_PROM_ADR_MASK & (i << 1));
ret = ms5806_read_reg(cmd, 2, (uint8_t*) calib_data); // TODO: do something with the return value
}
}
......@@ -68,19 +110,38 @@ void alti_init(void)
* @brief Reads and compensate pressure value.
* @return Pressure in hundredth of millibars (e.g. 110002 = 1100.02mbar).
*/
sint32_t alti_get_pressure(void)
int32_t alti_get_pressure(void)
{
// Initiate temperature conversion
uint8_t ret;
uint8_t cmd;
uint32_t adc_val;
int32_t temp;
int32_t pressure;
int64_t tmp;
// ADC read (3 bytes)
// Reads temperature
temp = alti_get_temperature();
// Calculate temperature
// Initiate pressure conversion
cmd = MS5806_CMD_CONV_PRESSURE + (MS5806_OSR_4096 & MS5806_OSR_MASK);
ret = ms5806_write_cmd(cmd); // TODO: do something with the return value
// Initiate temperature conversion
// Wait for conversion time (max time 9ms @ OSR=4096)
UDELAY_Delay(10000); // 10ms
// ADC read (3 bytes)
ret = ms5806_read_reg(MS5806_CMD_READ_ADC, 3, (uint8_t*) &adc_val); // TODO: do something with the return value
// Calulate compensated pressure
// OFF = OFFT1 + TCO * dT = C2 * 2^17 + (C4 * dT) / 2^6
// SENS = SENST1 + TCS * dT = C1 * 2^16 + (C3 * dT) / 2^7
// P = D1 * SENS - OFF = (D1 * SENS / 2^21 - OFF) / 2^15
// D1 = adc pressure value
// C1-C4 = calibration data
pressure = 0;
return pressure;
}
......@@ -88,12 +149,31 @@ sint32_t alti_get_pressure(void)
* @brief Reads temperature value.
* @return Temperature in hundredth of celsuis degrees (e.g. 2000 = 20.00 C).
*/
sint32_t alti_get_temperature(void)
int32_t alti_get_temperature(void)
{
uint8_t ret;
uint8_t cmd;
uint32_t adc_val;
int32_t temp;
int64_t tmp;
// Initiate temperature conversion
cmd = MS5806_CMD_CONV_TEMP + (MS5806_OSR_4096 & MS5806_OSR_MASK);
ret = ms5806_write_cmd(cmd); // TODO: do something with the return value
// ADC read (3 bytes)
// Wait for conversion time (max time 9ms @ OSR=4096)
UDELAY_Delay(10000); // 10ms
// ADC read (3 bytes)
ret = ms5806_read_reg(MS5806_CMD_READ_ADC, 3, (uint8_t*) &adc_val); // TODO: do something with the return value
// Calculate temperature
// dT = D2 - TREF = D2 - C5 * 2^8
// TEMP = 20C + dT * TEMPSENS = 2000 + dT * C6 / 2^23
// D2 = adc temperature value
// C5, C6 = calibration data
temp = adc_val - calib_data[5] * 256;
tmp = 2000 + temp * calib_data[6];
temp = tmp/8388608;
return temp;
}
......@@ -27,6 +27,8 @@
#ifndef ALTIMETER_H
#define ALTIMETER_H
#include <stdint.h>
// I2C address
#define MS5806_ADDRESS 0x77
......@@ -37,8 +39,8 @@
#define MS5806_CMD_CONV_TEMP 0x50
#define MS5806_CMD_READ_PROM 0xA0
#define MS5906_PROM_SIZE 0x08
#define MS5906_PROM_ADR_MASK 0x0E
#define MS5806_PROM_SIZE 0x08
#define MS5806_PROM_ADR_MASK 0x0E
// Oversampling ratio
#define MS5806_OSR_256 0x00
......@@ -49,6 +51,9 @@
#define MS5806_OSR_MASK 0x0E
uint8_t ms5806_write_cmd(uint8_t cmd);
uint8_t ms5806_read_reg(uint8_t cmd, uint8_t length, uint8_t* buffer);
/**
* @brief Resets and reads the calibration data from the altimeter.
*/
......@@ -58,13 +63,13 @@ void alti_init(void);
* @brief Reads and compensate pressure value.
* @return Pressure in hundredth of millibars (e.g. 110002 = 1100.02mbar).
*/
sint32_t alti_get_pressure(void);
int32_t alti_get_pressure(void);
/**
* @brief Reads temperature value.
* @return Temperature in hundredth of celsuis degrees (e.g. 2000 = 20.00 C).
*/
sint32_t alti_get_temperature(void);
int32_t alti_get_temperature(void);
#endif /* ALTIMETER_H */
/***************************************************************************//**
* @file
* @brief I2C0 poll based driver for master mode operation on FreeWatch.
* @author Energy Micro AS
* @version 3.20.0
*******************************************************************************
* @section License
* <b>(C) Copyright 2012 Energy Micro AS, http://www.energymicro.com</b>
*******************************************************************************
*
* Permission is granted to anyone to use this software for any purpose,
* including commercial applications, and to alter it and redistribute it
* freely, subject to the following restrictions:
*
* 1. The origin of this software must not be misrepresented; you must not
* claim that you wrote the original software.
* 2. Altered source versions must be plainly marked as such, and must not be
* misrepresented as being the original software.
* 3. This notice may not be removed or altered from any source distribution.
* 4. The source and compiled code may only be used on Energy Micro "EFM32"
* microcontrollers and "EFR4" radios.
*
* DISCLAIMER OF WARRANTY/LIMITATION OF REMEDIES: Energy Micro AS has no
* obligation to support this Software. Energy Micro AS is providing the
* Software "AS IS", with no express or implied warranties of any kind,
* including, but not limited to, any implied warranties of merchantability
* or fitness for any particular purpose or warranties against infringement
* of any proprietary rights of a third party.
*
* Energy Micro AS will not be liable for any consequential, incidental, or
* special damages, or any other relief, or for any claim by any third party,
* arising from your use of this Software.
*
*****************************************************************************/
#include <stddef.h>
#include "em_cmu.h"
#include "em_gpio.h"
#include "i2cdrv.h"
/*******************************************************************************
************************** GLOBAL FUNCTIONS *******************************
******************************************************************************/
/***************************************************************************//**
* @brief
* Initalize basic I2C master mode driver for use on the DK.
*
* @details
* This driver only supports master mode, single bus-master. In addition
* to configuring the EFM32 I2C peripheral module, it also configures DK
* specific setup in order to use the I2C bus.
*
* @param[in] init
* Pointer to I2C initialization structure.
******************************************************************************/
void I2CDRV_Init(const I2C_Init_TypeDef *init)
{
int i;
// BSP_PeripheralAccess(BSP_I2C, true); TODO
CMU_ClockEnable(cmuClock_HFPER, true);
CMU_ClockEnable(cmuClock_I2C0, true);
/* Use location #1: SDA - Pin B11, SCL - Pin B12 */
/* Output value must be set to 1 to not drive lines low... We set */
/* SCL first, to ensure it is high before changing SDA. */
GPIO_PinModeSet(gpioPortB, 11, gpioModeWiredAnd, 1);
GPIO_PinModeSet(gpioPortB, 12, gpioModeWiredAnd, 1);
/* In some situations (after a reset during an I2C transfer), the slave */
/* device may be left in an unknown state. Send 9 clock pulses just in case. */
for (i = 0; i < 9; i++)
{
/*
* TBD: Seems to be clocking at appr 80kHz-120kHz depending on compiler
* optimization when running at 14MHz. A bit high for standard mode devices,
* but DK only has fast mode devices. Need however to add some time
* measurement in order to not be dependable on frequency and code executed.
*/
GPIO_PinModeSet(gpioPortD, 12, gpioModeWiredAnd, 0);
GPIO_PinModeSet(gpioPortD, 12, gpioModeWiredAnd, 1);
}
/* Enable pins at location 1 */
I2C1->ROUTE = I2C_ROUTE_SDAPEN |
I2C_ROUTE_SCLPEN |
(1 << _I2C_ROUTE_LOCATION_SHIFT);
I2C_Init(I2C1, init);
}
/***************************************************************************//**
* @brief
* Perform I2C transfer.
*
* @details
* This driver only supports master mode, single bus-master. It does not
* return until the transfer is complete, polling for completion.
*
* @param[in] seq
* Pointer to sequence structure defining the I2C transfer to take place. The
* referenced structure must exist until the transfer has fully completed.
******************************************************************************/
I2C_TransferReturn_TypeDef I2CDRV_Transfer(I2C_TransferSeq_TypeDef *seq)
{
I2C_TransferReturn_TypeDef ret;
uint32_t timeout = 300000;
/* Do a polled transfer */
ret = I2C_TransferInit(I2C1, seq);
while (ret == i2cTransferInProgress && timeout--)
{
ret = I2C_Transfer(I2C1);
}
return(ret);
}
/***************************************************************************//**
* @file
* @brief I2C0 poll based driver for master mode operation on DK.
* @author Energy Micro AS
* @version 3.20.0
*******************************************************************************
* @section License
* <b>(C) Copyright 2012 Energy Micro AS, http://www.energymicro.com</b>
*******************************************************************************
*
* Permission is granted to anyone to use this software for any purpose,
* including commercial applications, and to alter it and redistribute it
* freely, subject to the following restrictions:
*
* 1. The origin of this software must not be misrepresented; you must not
* claim that you wrote the original software.
* 2. Altered source versions must be plainly marked as such, and must not be
* misrepresented as being the original software.
* 3. This notice may not be removed or altered from any source distribution.
* 4. The source and compiled code may only be used on Energy Micro "EFM32"
* microcontrollers and "EFR4" radios.
*
* DISCLAIMER OF WARRANTY/LIMITATION OF REMEDIES: Energy Micro AS has no
* obligation to support this Software. Energy Micro AS is providing the
* Software "AS IS", with no express or implied warranties of any kind,
* including, but not limited to, any implied warranties of merchantability
* or fitness for any particular purpose or warranties against infringement
* of any proprietary rights of a third party.
*
* Energy Micro AS will not be liable for any consequential, incidental, or
* special damages, or any other relief, or for any claim by any third party,
* arising from your use of this Software.
*
*****************************************************************************/
#ifndef __I2CDRV_H
#define __I2CDRV_H
#include "em_i2c.h"
/***************************************************************************//**
* @addtogroup Drivers
* @{
******************************************************************************/
/***************************************************************************//**
* @addtogroup I2c
* @{
******************************************************************************/
#ifdef __cplusplus
extern "C" {
#endif
/*******************************************************************************
***************************** PROTOTYPES **********************************
******************************************************************************/
void I2CDRV_Init(const I2C_Init_TypeDef *init);
I2C_TransferReturn_TypeDef I2CDRV_Transfer(I2C_TransferSeq_TypeDef *seq);
#ifdef __cplusplus
}
#endif
/** @} (end group I2c) */
/** @} (end group Drivers) */
#endif /* __I2CDRV_H */
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment