Commit e152aa5b authored by Grzegorz Daniluk's avatar Grzegorz Daniluk

acc/mag: wip

parent 38da8b67
# 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-2014q1
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/pp_printf \
-I../common
####################################################################
# Files #
####################################################################
C_SRC += \
../common/Device/EnergyMicro/EFM32GG/Source/system_efm32gg.c \
../common/drivers/lcd.c \
../common/drivers/i2cdrv.c \
../common/drivers/max17047.c \
../common/drivers/LSM303C/lsm303c.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/pp_printf/vsprintf-xint.c \
../common/udelay.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
/*
* 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 <em_device.h>
#include <em_cmu.h>
#include <em_gpio.h>
#include <drivers/lcd.h>
#include <drivers/i2cdrv.h>
#include <drivers/max17047.h>
#include <gfx/graphics.h>
#include <stdio.h>
#include <pp-printf.h>
#include <LSM303C/lsm303c.h>
#define ACC_DEMO 0
#define MAG_DEMO 1
/* 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)
{
int x, y, t, but, calibrated=0;
char buf[30];
I2C_Init_TypeDef i2c_init = I2C_INIT_DEFAULT;
//uint8_t ret = 0;
//int16_t acc_x[2], acc_y[2], acc_z[2];
lsm303_smpl smpl, smpl2, mag_max, mag_min;
/* 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);
GPIO_PinModeSet(gpioPortC, 7, gpioModeInput, 1);
lcd_init();
I2CDRV_Init(&i2c_init);
lsm303_init();
/* Infinite blink loop */
while (1) {
lcd_clear();
but = GPIO_PinInGet(gpioPortC, 7);
//#if MAG_DEMO
/*make the calibration*/
if(!but) {
text(&font_helv17, 10, 70, "go!");
lcd_update();
lsm303_mag_calibrate(&mag_max, &mag_min);
calibrated = 1;
}
//#endif
//if(calibrated) {
// compass_xy(&mag_max, &mag_min, &x, &y);
// line(60, 60, x, y, 1);
//}
#if ACC_DEMO
spi_read(DEV_ACC, LSM303_WHO_AM_I_REG, (uint8_t*) &t);
pp_sprintf(buf, "who: 0x%x", (int8_t)t);
text(&font_helv17b, 5, 10, buf);
lsm303_get_sample(DEV_ACC, &smpl);
pp_sprintf(buf, "x:%d", smpl.x);
text(&font_helv17b, 5, 50, buf);
pp_sprintf(buf, "y:%d", smpl.y);
text(&font_helv17b, 5, 70, buf);
pp_sprintf(buf, "z:%d", smpl.z);
text(&font_helv17b, 5, 90, buf);
#endif
#if MAG_DEMO
//spi_read(DEV_MAG, LSM303_WHO_AM_I_REG, (uint8_t*) &t);
//pp_sprintf(buf, "who: 0x%x", (int8_t)t & 0xFF);
//text(&font_helv17, 5, 10, buf);
sprintf(buf, "min: %d ; %d ; %d", mag_min.x, mag_min.y, mag_min.z);
text(&font_helv11, 5, 5, buf);
sprintf(buf, "max: %d ; %d ; %d", mag_max.x, mag_max.y, mag_max.z);
text(&font_helv11, 5, 15, buf);
lsm303_get_sample(DEV_ACC, &smpl2);
sprintf(buf, "xa: %d, ya: %d", smpl2.x, smpl2.y);
text(&font_helv11, 5, 25, buf);
//lsm303_selftest(DEV_MAG, 0, 1);
//Delay(100);
lsm303_selftest(DEV_MAG, 0, 0);
Delay(10);
lsm303_get_sample(DEV_MAG, &smpl);
//sprintf(buf, "x: %f", smpl.x*0.58/10.0);
//sprintf(buf, "y: %f", smpl.y*0.58/10.0);
//sprintf(buf, "z: %f", smpl.z*0.58/10.0);
sprintf(buf, "x: %d", smpl.x);
text(&font_helv17, 5, 50, buf);
sprintf(buf, "y: %d", smpl.y);
text(&font_helv17, 5, 70, buf);
sprintf(buf, "z: %d", smpl.z);
text(&font_helv17, 5, 90, buf);
#endif
lcd_update();
Delay(10);
}
}
sudo openocd -s ../common/openocd -f interface/stlink-v2-1.cfg -f init.cfg &
/opt/gcc-arm-none-eabi-4_8-2014q1/bin/arm-none-eabi-gdb -ex "target remote localhost:3333" exe/freewatch.out
#include <em_cmu.h>
//#include <em_device.h>
#include <em_gpio.h>
#include <em_usart.h>
//#include <efm32gg_usart.h>
#include <efm32gg330f1024.h>
#include "cpu_calls.h"
#include "LSM303C_ACC_driver.h"
#include "LSM303C_MAG_driver.h"
#define HFRCO_FREQUENCY 14000000
#define SPI_PERCLK_FREQUENCY HFRCO_FREQUENCY
#define SPI_BAUDRATE 1000000
#define SPI_LOC USART_ROUTE_LOCATION_LOC2 //2
#define BUFSIZE 80
#define SPI_USART USART0
#define ACC_CS_PIN 8
#define MAG_CS_PIN 10
char spi_txbuf[BUFSIZE];
char spi_rxbuf[BUFSIZE];
volatile int spi_txbuf_idx; /* index of spi_txbuf, used by Tx irq handler, must
* be initialized to 0 before tx data written to buffer */
volatile int spi_rxbuf_idx; /* index of spi_rxbuf, used by Rx irq handler, must
* be initialized to 0 before expected data reception */
int txbuf_sz;
// Based on
// http://community.silabs.com/t5/tkb/articleprintpage/tkb-id/1000/article-id/1985
/*TODO: move away from here*/
int temp_lsm303_init()
{
uint8_t dat = 0;
AxesRaw_t meas;
spi_init();
//LSM303C_ACC_Reboot();
/*setup 3-wire SPI for Accelerometer & Magnetometer*/
LSM303C_ACC_SerialInterfaceMode(LSM303C_ACC_SIM_3WIRE_INTERFACE);
// LSM303C_MAG_SerialInterfaceMode(LSM303C_MAG_SIM_3_WIRE);
LSM303C_ACC_ReadReg(LSM303C_ACC_WHO_AM_I_REG, &dat); /* read WHO_AM_I_A */
/*ACC self test*/
//LSM303C_ACC_SelfTest(LSM303C_ACC_ST_POSITIVE);
return dat;
}
int spi_init()
{
USART_InitSync_TypeDef cfg = USART_INITSYNC_DEFAULT;
USART_TypeDef *spi = SPI_USART;
//CHIP_Init();
/*Enable clock to USART0 and GPIO*/
CMU_ClockEnable(cmuClock_USART0, true);
/* basic configuration */
cfg.baudrate = SPI_BAUDRATE;
cfg.clockMode = usartClockMode3; //Clock idle high, sample on rising edge
cfg.msbf = true; //MSB first
USART_InitSync(SPI_USART, &cfg);
/* signals routing to location 2 and loopback for half-duplex */
spi->CTRL |= USART_CTRL_LOOPBK; /* use half-duplex */
spi->ROUTE = USART_ROUTE_CLKPEN |
USART_ROUTE_TXPEN |
// USART_ROUTE_CSPEN /* don't know yet about CS, I'll try to drive it 'by hand' */
SPI_LOC;
CMU_ClockEnable(cmuClock_GPIO, true);
/* GPIO configuration */
GPIO_PinModeSet(gpioPortC, 11, gpioModePushPull, 0); /* MOSI/MISO */
GPIO_PinModeSet(gpioPortC, MAG_CS_PIN, gpioModePushPull, 1); /* CS Mag*/
GPIO_PinModeSet(gpioPortC, ACC_CS_PIN, gpioModePushPull, 1); /* CS Acc*/
GPIO_PinModeSet(gpioPortC, 9, gpioModePushPull, 1); /* Clock */
GPIO_PinModeSet(gpioPortD, 4, gpioModeInput, 0); /* Mag drdy */
/* buffers init */
spi_txbuf_idx = 0;
spi_rxbuf_idx = 0;
/* finally enable USART (Tx & RX)*/
//USART_Enable(spi, usartEnable);
/*setup Rx irq*/
//spi->CMD = USART_CMD_CLEARRX;
//NVIC_ClearPendingIRQ(USART0_RX_IRQn);
//NVIC_EnableIRQ(USART0_RX_IRQn);
//spi->IEN |= USART_IEN_RXDATAV;
/*setup Tx irq*/
//spi->CMD = USART_CMD_CLEARTX;
//NVIC_ClearPendingIRQ(USART0_TX_IRQn);
//NVIC_EnableIRQ(USART0_TX_IRQn);
//spi->IEN |= USART_IEN_TXBL;
return 0;
}
void spi_send(uint8_t dev, uint8_t adr, uint8_t dat)
{
USART_TypeDef *spi = SPI_USART;
if (dev == DEV_ACC) {
/* drive ACC CS down */
GPIO_PinOutClear(gpioPortC, ACC_CS_PIN);
GPIO_PinOutSet(gpioPortC, MAG_CS_PIN);
}
else if (dev == DEV_MAG) {
/* drive MAG CS down */
GPIO_PinOutSet(gpioPortC, ACC_CS_PIN);
GPIO_PinOutClear(gpioPortC, MAG_CS_PIN);
}
//spi->TXDOUBLE = adr << _USART_TXDOUBLE_TXDATA0_SHIFT |
// dat << _USART_TXDOUBLE_TXDATA1_SHIFT;
USART_TxDouble(spi, adr << _USART_TXDOUBLE_TXDATA0_SHIFT |
dat << _USART_TXDOUBLE_TXDATA1_SHIFT);
/* wait until it's done */
while (!(USART_StatusGet(spi) & USART_STATUS_TXC)) ;
/* both CS up */
GPIO_PinOutSet(gpioPortC, ACC_CS_PIN);
GPIO_PinOutSet(gpioPortC, MAG_CS_PIN);
}
/* read byte from given address */
uint8_t spi_read(uint8_t dev, uint8_t adr)
{
USART_TypeDef *spi = SPI_USART;
if (dev == DEV_ACC) {
/* drive ACC CS down */
GPIO_PinOutClear(gpioPortC, ACC_CS_PIN);
GPIO_PinOutSet(gpioPortC, MAG_CS_PIN);
}
else if (dev == DEV_MAG) {
/* drive MAG CS down */
GPIO_PinOutSet(gpioPortC, ACC_CS_PIN);
GPIO_PinOutClear(gpioPortC, MAG_CS_PIN);
}
spi->CMD = USART_CMD_RXBLOCKEN; /* Block loopbacked RX while we send adr to Slave */
spi->CMD = USART_CMD_CLEARRX; /* Clear old data, if any */
spi->TXDOUBLEX = (adr | 1<< 7) << _USART_TXDOUBLEX_TXDATA0_SHIFT |
USART_TXDOUBLEX_TXTRIAT0 | /* tristate Tx */
USART_TXDOUBLEX_UBRXAT0 | /* unblock Rx */
0x00 << _USART_TXDOUBLEX_TXDATA1_SHIFT | /* dummy Tx data for reading Slave */
USART_TXDOUBLEX_TXTRIAT1 | /* once again, errata USART_E101 */
USART_TXDOUBLEX_UBRXAT1;
/* wait for valid rx data */
while( !(USART_StatusGet(spi) & USART_STATUS_RXDATAV) );
/* we have new data, turn off tristate Tx */
spi->CMD = USART_CMD_TXTRIDIS;
/* both CS up */
GPIO_PinOutSet(gpioPortC, ACC_CS_PIN);
GPIO_PinOutSet(gpioPortC, MAG_CS_PIN);
return spi->RXDATA & 0xff;
}
//void spi_send(char* buf, int size)
//{
// USART_TypeDef *spi = SPI_USART;
// int i;
//
// for (i = 0; i<size; i++) {
// /* Waiting for the usart to be ready */
// while (!(uart->STATUS & USART_STATUS_TXBL)) ;
//
// if (buf) {
// /* Writing next byte to USART */
// uart->TXDATA = *buf;
// buf++;
// }
// else
// uart->TXDATA = 0;
// }
//
// /*Waiting for transmission of last byte */
// while (!(uart->STATUS & USART_STATUS_TXC)) ;
//}
/* Rx IRQ handler, receives byte from SPI, and writes to next position in
* the rxbuf */
//void spi_rx_irq()
//{
// USART_TypeDef *spi = SPI_USART;
//
// if (spi->STATUS & USART_STATUS_RXDATAV) {
// /*we have valid data received from SPI*/
// if (spi_rxbuf_idx < BUFSIZE)
// spi_rxbuf[spi_rxbuf_idx++] = spi->RXDATA;
// }
//}
/* Tx IRQ handler, sends txbuf byte by byte for a given rxbuf_sz, using
* spi_txbuf_idx to mark subsequent bytes between calls */
//void spi_tx_irq()
//{
// USART_TypeDef *spi = SPI_USART;
//
// if (spi->STATUS & USART_STATUS_TXBL) {
// if (spi_txbuf_idx < txbuf_sz)
// /* there is next byte in the buffer to be sent */
// spi->TXDATA = spi_txbuf_idx[spi_txbuf_idx++];
// else
// spi->TXDATA = 0;
// }
//}
//void spi_setup(uint8_t spiNumber, uint8_t location)
//{
// USART_TypeDef *spi;
//
// /* Determining USART */
// switch (spiNumber)
// {
// case 0:
// spi = USART0;
// break;
// case 1:
// spi = USART1;
// break;
// case 2:
// spi = USART2;
// break;
// default:
// return;
// }
//
// /* Setting baudrate */
// //spi->CLKDIV = 128 * (SPI_PERCLK_FREQUENCY / SPI_BAUDRATE - 2);
//
// /* Configure SPI */
// spi->CTRL = USART_CTRL_SYNC | /* synchronous (SPI) mode */
// USART_CTRL_LOOPBK; /* use half-duplex */
// /* Clearing old transfers/receptions, and disabling interrupts */
// spi->CMD = USART_CMD_CLEARRX | USART_CMD_CLEARTX;
// spi->IEN = 0;
// /* Enabling pins and setting location */
// spi->ROUTE = USART_ROUTE_TXPEN | USART_ROUTE_RXPEN | USART_ROUTE_CLKPEN | USART_ROUTE_CSPEN | (location << 8);
//
// /* Enabling Master, TX and RX */
// spi->CMD = USART_CMD_MASTEREN | USART_CMD_TXEN | USART_CMD_RXEN;
// //spi->CTRL |= USART_CTRL_AUTOCS; /* sorry, no AUTOCS, because ACC and MAG
// /* have separete CS signals and we have
// * to choose witch whom to speak */
//
// /* Clear previous interrupts */
// spi->IFC = _USART_IFC_MASK;
//
// /* fuck the rest of the USARTs and locations, our case is simple, USART0 & Loc 2 */
// GPIO_PinModeSet(gpioPortC, 11, gpioModePushPull, 0); /* MOSI/MISO */
// GPIO_PinModeSet(gpioPortC, 10, gpioModePushPull, 1); /* CS Mag*/
// GPIO_PinModeSet(gpioPortC, 8, gpioModePushPull, 1); /* CS Acc*/
// GPIO_PinModeSet(gpioPortC, 9, gpioModePushPull, 1); /* Clock */
// GPIO_PinModeSet(gpioPortD, 4, gpioModeInput, 0); /* Mag drdy */
//
//}
......@@ -4,6 +4,9 @@
#include <efm32gg330f1024.h>
#include "lsm303c.h"
extern volatile uint32_t msTicks;
void Delay(uint32_t dlyTicks);
/************************************************/
/* First functions to initialize and access SPI */
/************************************************/
......@@ -29,7 +32,9 @@ static void spi_init()
/* GPIO configuration */
GPIO_PinModeSet(gpioPortC, 11, gpioModePushPull, 0); /* MOSI/MISO */
GPIO_PinModeSet(gpioPortC, MAG_CS_PIN, gpioModePushPull, 1); /* CS Mag*/
GPIO_PinModeSet(gpioPortC, MAG_CS_PIN, gpioModePushPull, 1); //InputPull, 0); /* CS Mag*/
//GPIO_PinModeSet(gpioPortC, MAG_CS_PIN, gpioModeWiredAndPullUp, 1); // gpioModePushPull, 1); /* CS Mag*/
//GPIO_PinModeSet(gpioPortC, ACC_CS_PIN, gpioModeWiredAndPullUp, 1); //gpioModePushPull, 1); /* CS Acc*/
GPIO_PinModeSet(gpioPortC, ACC_CS_PIN, gpioModePushPull, 1); /* CS Acc*/
GPIO_PinModeSet(gpioPortC, 9, gpioModePushPull, 1); /* Clock */
GPIO_PinModeSet(gpioPortD, 4, gpioModeInput, 0); /* Mag drdy */
......@@ -112,12 +117,17 @@ int lsm303_init()
/*setup 3-wire SPI for Accelerometer & Magnetometer*/
//LSM303_ACC_SerialInterfaceMode(LSM303_ACC_SIM_3WIRE_INTERFACE);
lsm303_serialmode(DEV_ACC, LSM303_ACC_3WIRE);
//lsm303_serialmode(DEV_MAG, LSM303_ACC_3WIRE);
lsm303_serialmode(DEV_MAG, LSM303_MAG_3WIRE);
lsm303_enableaxis(DEV_ACC, 0x7);
lsm303_fifo_mode(DEV_ACC, LSM303_FMODE_BYPASS, 1);
lsm303_fifo_mode(DEV_ACC, LSM303_FMODE_BYPASS, 0);
lsm303_odr(DEV_ACC, LSM303_ACC_ODR_10_Hz);
lsm303_odr(DEV_MAG, LSM303_MAG_ODR_1_25_Hz);
lsm303_opmode(DEV_MAG, LSM303_MAG_OPM_MED, LSM303_MAG_CONV_CONT);
lsm303_fullscale(DEV_MAG, LSM303_16Ga);
lsm303_selftest(DEV_MAG, 0, 0);
return LSM303_SUCCESS;
}
......@@ -171,18 +181,29 @@ int lsm303_odr(int dev, LSM303_ODR_t odr)
/* set operation mode
* dev: DEV_ACC/DEV_MAG
* opm: constant from lsm303.h */
int lsm303_opmode(int dev, LSM303_OPM_t opm)
int lsm303_opmode(int dev, LSM303_OPM_t opm, LSM303_CONV_t conv)
{
uint8_t val;
if (!spi_read(dev, LSM303_CTRL1, &val))
return LSM303_ERROR;
if (!spi_read(dev, LSM303_CTRL1, &val)) return LSM303_ERROR;
val &= ~( dev==DEV_ACC ? LSM303_ACC_OPM_MASK : LSM303_MAG_OPM_MASK );
val |= opm;
if( !spi_send(dev, LSM303_CTRL1, val) )
return LSM303_ERROR;
if( !spi_send(dev, LSM303_CTRL1, val) ) return LSM303_ERROR;
if (dev==DEV_ACC) return LSM303_SUCCESS;
/* only for MAG, set conversion mode and opmode for Z axis*/
if (!spi_read(dev, LSM303_CTRL4, &val)) return LSM303_ERROR;
val &= ~(LSM303_MAG_OPM_MASK>>3);
val |= (opm>>3);
if (!spi_send(dev, LSM303_CTRL4, val)) return LSM303_ERROR;
if (!spi_read(dev, LSM303_CTRL3, &val)) return LSM303_ERROR;
val &= ~LSM303_MAG_CONV_MASK;
val |= conv;
if (!spi_send(dev, LSM303_CTRL3, val)) return LSM303_ERROR;
return LSM303_SUCCESS;
}
......@@ -274,6 +295,9 @@ int lsm303_serialmode(int dev, LSM303_SMODE_t mode)
(dev==DEV_MAG && !spi_read(dev, LSM303_CTRL3, &val)) )
return LSM303_ERROR;
/* we'll use SPI, disable I2c */
val |= (dev==DEV_ACC ? LSM303_ACC_NOI2C : LSM303_MAG_NOI2C);
/* now set SPI mode */
val &= ~(dev==DEV_ACC ? LSM303_ACC_3WIRE : LSM303_MAG_3WIRE);
val |= mode;
......@@ -334,24 +358,73 @@ int lsm303_fifo_mode(int dev, LSM303_FMODE_t mode, int en)
return LSM303_SUCCESS;
}
int lsm303_get_sample(int dev, int16_t *x, int16_t *y, int16_t *z)
int lsm303_get_sample(int dev, lsm303_smpl *smpl)
{
uint8_t val_l, val_h;
if( !spi_read(dev, LSM303_OUT_X_L, &val_l) ||
!spi_read(dev, LSM303_OUT_X_H, &val_h) )
return LSM303_ERROR;
*x = (int16_t) ((val_h << 8) | val_l);
smpl->x = (int16_t) ((val_h << 8) | val_l);
if( !spi_read(dev, LSM303_OUT_Y_L, &val_l) ||
!spi_read(dev, LSM303_OUT_Y_H, &val_h) )
return LSM303_ERROR;
*y = (int16_t) ((val_h << 8) | val_l);
smpl->y = (int16_t) ((val_h << 8) | val_l);
if( !spi_read(dev, LSM303_OUT_Z_L, &val_l) ||
!spi_read(dev, LSM303_OUT_Z_H, &val_h) )
return LSM303_ERROR;
*z = (int16_t) ((val_h << 8) | val_l);
smpl->z = (int16_t) ((val_h << 8) | val_l);
return LSM303_SUCCESS;
}
int lsm303_mag_calibrate(lsm303_smpl *max, lsm303_smpl *min)
{
int i = 1000;
lsm303_smpl val;
max->x = -0x7fff;
max->y = -0x7fff;
max->z = -0x7fff;
min->x = 0x7fff;
min->y = 0x7fff;
min->z = 0x7fff;
while(i--) {
lsm303_get_sample(DEV_MAG, &val);
if(val.x > max->x) max->x = val.x;
if(val.x < min->x) min->x = val.x;
if(val.y > max->y) max->y = val.y;
if(val.y < min->y) min->y = val.y;
if(val.z > max->z) max->z = val.z;
if(val.z < min->z) min->z = val.z;
Delay(10);
}
}
#define LCD_W 100
#define LCD_0 60
int compass_xy(lsm303_smpl *max, lsm303_smpl *min, int *x, int *y)
{
lsm303_smpl val;
lsm303_get_sample(DEV_MAG, &val);
if(val.x >= 0) {
*y = LCD_0 - (((val.x*1000)/(float)(max->x)) * LCD_W)/2000.0;
} else if(val.x < 0) {
*y = LCD_0 + (((val.x*1000)/(float)(min->x)) * LCD_W)/2000.0;
}
if(val.y >= 0) {
*x = LCD_0 + (((val.y*1000)/(float)(max->y)) * LCD_W)/2000.0;
} else if(val.x < 0) {
*x = LCD_0 - (((val.y*1000)/(float)(min->y)) * LCD_W)/2000.0;
}
if(*x > LCD_0 + LCD_W/2) *x = LCD_0+LCD_W/2;
if(*x < LCD_0 - LCD_W/2) *x = LCD_0-LCD_W/2;
if(*y > LCD_0 + LCD_W/2) *y = LCD_0+LCD_W/2;
if(*y < LCD_0 - LCD_W/2) *y = LCD_0-LCD_W/2;
}
......@@ -61,6 +61,10 @@
#define LSM303_ZREF_L 0x3E /* ACC only */
#define LSM303_ZREF_H 0x3F /* ACC only */
typedef struct {
int16_t x, y, z
} lsm303_smpl;
/* Accelerometer config */
#define LSM303_ACC_ST_MASK 0x0C
#define LSM303_ACC_ST_POS 0x04
......@@ -98,6 +102,13 @@ typedef enum {
LSM303_MAG_OPM_MASK = 0x60
} LSM303_OPM_t;
typedef enum {
LSM303_MAG_CONV_CONT = 0x00,
LSM303_MAG_CONV_SING = 0x01,
LSM303_MAG_CONV_PDOWN = 0x03,
LSM303_MAG_CONV_MASK = 0x03
} LSM303_CONV_t;
#define LSM303_ACC_SRST 0x40
#define LSM303_MAG_SRST 0x04
......@@ -117,8 +128,10 @@ typedef enum {
LSM303_ACC_4WIRE = 0x00,
LSM303_MAG_4WIRE = 0x00,
LSM303_ACC_3WIRE = 0x01,
LSM303_MAG_3WIRE = 0x04
LSM303_MAG_3WIRE = 0x04,
} LSM303_SMODE_t;
#define LSM303_ACC_NOI2C 0x02
#define LSM303_MAG_NOI2C 0x80
typedef enum {
LEM303_ACC_XEN = 0x01,
......@@ -147,14 +160,16 @@ typedef enum {
int lsm303_init();
int lsm303_selftest(int dev, int en, int dir);
int lsm303_odr(int dev, LSM303_ODR_t odr);
int lsm303_opmode(int dev, LSM303_OPM_t opm);
int lsm303_opmode(int dev, LSM303_OPM_t opm, LSM303_CONV_t conv);
int lsm303_rst(int dev, int hard);
int lsm303_temp(int16_t *temp);
int lsm303_fullscale(int dev, LSM303_FS_t fs);
int lsm303_serialmode(int dev, LSM303_SMODE_t mode);
int lsm303_enableaxis(int dev, int mask);
int lsm303_fifo_mode(int dev, LSM303_FMODE_t mode, int en);
int lsm303_get_sample(int dev, int16_t *x, int16_t *y, int16_t *z);
int lsm303_get_sample(int dev, lsm303_smpl *smpl);
int lsm303_mag_calibrate(lsm303_smpl *max, lsm303_smpl *min);
int compass_xy(lsm303_smpl *max, lsm303_smpl *min, int *x, int *y);
int spi_read(uint8_t dev, uint8_t adr, uint8_t *dat);
......
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