Commit bd81c945 authored by Theodor-Adrian Stana's avatar Theodor-Adrian Stana

Pulled drivers from Orson's branch

parent 48099e75
/*
* Copyright (C) 2014 Julian Lewis
* @author Matthieu Cattin <matthieu.cattin@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 MS5806-02BA altimeter sensor driver
*/
#include "altimeter.h"
#include "i2cdrv.h"
#include <math.h>
#include <delay.h>
// Calibration data storage
static uint16_t calib_data[8];
// Coefficients for pressure to altitude convserion
static int16_t p2a_coeff[P2A_COEFF_SIZE][4] = {
{1000,1130,12256,16212},
{1130,1300,10758,15434},
{1300,1500,9329,14541},
{1500,1730,8085,13630},
{1730,2000,7001,12722},
{2000,2300,6069,11799},
{2300,2650,5360,10910},
{2650,3000,4816,9994},
{3000,3350,4371,9171},
{3350,3700,4020,8424},
{3700,4100,3702,7737},
{4100,4500,3420,7014},
{4500,5000,3158,6346},
{5000,5500,2908,5575},
{5500,6000,2699,4865},
{6000,6500,2523,4206},
{6500,7100,2359,3590},
{7100,7800,2188,2899},
{7800,8500,2033,2151},
{8500,9200,1905,1456},
{9200,9700,1802,805},
{9700,10300,1720,365},
{10300,11000,1638,-139}};
// Only send a command (no reply expected)
uint8_t ms5806_write_cmd(uint8_t cmd)
{
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 cmd, uint8_t length, uint8_t* buffer)
{
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)
//seq.flags = I2C_FLAG_READ; // sequence: read (n bytes)
// Add command to sequence
seq.buf[0].data = &cmd;
seq.buf[0].len = 1;
// Read value in buffer
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;
}
// Check PROM CRC
uint8_t ms5806_crc_chk(uint16_t* data)
{
uint8_t word, bit;
uint16_t rem, crc;
rem = 0x00;
crc = data[7]; // save crc
data[7] = (0xFF00 & data[7]); // replace crc byte by 0
for(word=0; word<16; word++)
{
// choose LSB or MSB byte
if(word%2 == 1)
{
rem ^= (uint8_t)(data[word>>1] & 0xFF);
}
else
{
rem ^= (uint8_t)(data[word>>1] >> 8);
}
for(bit=8; bit>0;bit--)
{
if(rem & 0x8000)
{
rem = (rem << 1) ^ 0x3000;
}
else
{
rem = (rem << 1);
}
}
}
rem = 0xF & (rem >> 12);
data[7] = crc; // restore crc
return (rem ^ 0x0);
}
/**
* @brief Resets and reads the calibration data from the altimeter.
* @return i2c error code or crc error, 0 if no errors.
*/
uint8_t alti_init(void)
{
uint8_t i, err, cmd, crc;
uint8_t buf[2*MS5806_PROM_SIZE];
// Reset the sensor
err = ms5806_write_cmd(MS5806_CMD_RESET);
if(err)
{
return err;
}
// Wait for the sensor to be ready
Delay(10); // 10ms
// Reads calibration data and store them in static variable
for(i=0; i<MS5806_PROM_SIZE; i++)
{
cmd = MS5806_CMD_READ_PROM + (MS5806_PROM_ADR_MASK & (i << 1));
err = ms5806_read_reg(cmd, 2, &buf[2*i]);
if(err)
{
return err;
}
calib_data[i] = (buf[2*i] << 8) + buf[2*i+1];
}
// CRC check
crc = ms5806_crc_chk(calib_data);
if(crc /= (calib_data[7] & 0xF))
{
return -1;
}
return 0;
}
/**
* @brief Reads temperature value.
* @param temp : Temperature in celsius degrees.
* @param pressure : Pressure in millibars.
* @param filter : Enables pressure value filter if true.
* @return i2c error code, 0 if no errors.
*/
uint8_t alti_get_temp_pressure(double* temp, double* pressure, bool filter)
{
uint8_t err, cmd;
uint8_t buf[3];
uint32_t d1, d2;
double dt, off, sens, p;
static double prev_p = 0;
float k = 0.125;
// Initiate temperature conversion
cmd = MS5806_CMD_CONV_TEMP + (MS5806_OSR_4096 & MS5806_OSR_MASK);
err = ms5806_write_cmd(cmd);
if(err)
{
return err;
}
// Wait for conversion time (max time 9ms @ OSR=4096)
Delay(10); // 10ms
// ADC read (3 bytes), raw temperature value
err = ms5806_read_reg(MS5806_CMD_READ_ADC, 3, buf);
if(err)
{
return err;
}
d2 = (buf[0] << 16) + (buf[1] << 8) + buf[2];
// Initiate pressure conversion
cmd = MS5806_CMD_CONV_PRESSURE + (MS5806_OSR_4096 & MS5806_OSR_MASK);
err = ms5806_write_cmd(cmd);
if(err)
{
return err;
}
// Wait for conversion time (max time 9ms @ OSR=4096)
Delay(10); // 10ms
// ADC read (3 bytes), raw pressure value
err = ms5806_read_reg(MS5806_CMD_READ_ADC, 3, buf);
if(err)
{
return err;
}
d1 = (buf[0] << 16) + (buf[1] << 8) + buf[2];
// Calculate compensated temperature and pressure values
dt = d2 - calib_data[5] * pow(2,8);
off = calib_data[2] * pow(2,17) + dt * calib_data[4]/pow(2,6);
sens = calib_data[1] * pow(2,16) + dt * calib_data[3]/pow(2,7);
*temp = (2000 + (dt * calib_data[6])/pow(2,23))/100;
p = (((d1 * sens)/pow(2,21) - off)/pow(2,15))/100;
if(filter)
{
if(prev_p == 0)
{
prev_p = p;
}
*pressure = prev_p * (1 - k) + p * k;
}
else
{
*pressure = p;
}
return 0;
}
/**
* @brief Helper function to convert from mbar to altitude.
*
* Uses piecewise interpolation of pressure to altitude conversion formula (troposhere model)
* h = 288.15/0.065 * (1 - (p/1013.25)^(0.065*287.052/9.81))
* source: Intersema (Meas-spec), AN501 - Using MS5534 for Altimeters and Barometers
*
* @param pressure : Pressure in millibars.
* @param altitude : Altitude in merters.
* @return i2c error code or crc error (-1), 0 if no errors.
*/
uint8_t alti_mbar2altitude(double pressure, double* altitude)
{
uint8_t i;
for(i=0; i<P2A_COEFF_SIZE; i++)
{
if((pressure*10) < p2a_coeff[i][1])
{
break;
}
}
*altitude = p2a_coeff[i][3] - (pressure*10 - p2a_coeff[i][0]) * p2a_coeff[i][2]/pow(2,11);
return i;
}
/*
* Copyright (C) 2014 Julian Lewis
* @author Matthieu Cattin <matthieu.cattin@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 MS5806-02BA altimeter sensor driver
*/
#ifndef ALTIMETER_H
#define ALTIMETER_H
#include <stdint.h>
#include <stdbool.h>
// I2C address
#define MS5806_ADDRESS 0xEE // 0x77 << 1
// Commands
#define MS5806_CMD_READ_ADC 0x00
#define MS5806_CMD_RESET 0x1E
#define MS5806_CMD_CONV_PRESSURE 0x40
#define MS5806_CMD_CONV_TEMP 0x50
#define MS5806_CMD_READ_PROM 0xA0
#define MS5806_PROM_SIZE 0x08
#define MS5806_PROM_ADR_MASK 0x0E
// Oversampling ratio
#define MS5806_OSR_256 0x00
#define MS5806_OSR_512 0x02
#define MS5806_OSR_1024 0x04
#define MS5806_OSR_2048 0x06
#define MS5806_OSR_4096 0x08
#define MS5806_OSR_MASK 0x0E
// Pressure to altitude conversion coefficent table size
#define P2A_COEFF_SIZE 23
uint8_t ms5806_write_cmd(uint8_t cmd);
uint8_t ms5806_read_reg(uint8_t cmd, uint8_t length, uint8_t* buffer);
uint8_t ms5806_crc_chk(uint16_t* data);
/**
* @brief Resets and reads the calibration data from the altimeter.
* @return i2c error code or crc error (-1), 0 if no errors.
*/
uint8_t alti_init(void);
/**
* @brief Reads temperature value.
* @param temp : Temperature in celsius degrees.
* @param pressure : Pressure in millibars.
* @param filter : Enables pressure value filter if true.
* @return i2c error code, 0 if no errors.
*/
uint8_t alti_get_temp_pressure(double* temp, double* pressure, bool filter);
/**
* @brief Helper function to convert from mbar to altitude.
*
* Uses piecewise interpolation of pressure to altitude conversion formula (troposhere model)
* h = 288.15/0.065 * (1 - (p/1013.25)^(0.065*287.052/9.81))
* source: Intersema (Meas-spec), AN501 - Using MS5534 for Altimeters and Barometers
*
* @param pressure : Pressure in millibars.
* @param altitude : Altitude in merters.
* @return i2c error code or crc error (-1), 0 if no errors.
*/
uint8_t alti_mbar2altitude(double pressure, double* altitude);
#endif /* ALTIMETER_H */
/*
* 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 Button routines
*/
#include "buttons.h"
__attribute__((weak))
void GPIO_EVEN_IRQHandler(void)
{
uint32_t iflags;
// Get all even interrupts
iflags = GPIO_IntGetEnabled() & 0x00005555;
// Clean only even interrupts
GPIO_IntClear(iflags);
}
__attribute__((weak))
void GPIO_ODD_IRQHandler(void)
{
uint32_t iflags;
// Get all odd interrupts
iflags = GPIO_IntGetEnabled() & 0x0000AAAA;
// Clean only odd interrupts
GPIO_IntClear(iflags);
}
void buttons_init(void)
{
// Configure interrupt pin as input with pull-up
// TODO there are external pull-ups - we should disable either int or ext
GPIO_PinModeSet(BUT_TL_PORT, BUT_TL_PIN, gpioModeInputPull, 1);
GPIO_PinModeSet(BUT_TR_PORT, BUT_TR_PIN, gpioModeInputPull, 1);
GPIO_PinModeSet(BUT_BL_PORT, BUT_BL_PIN, gpioModeInputPull, 1);
GPIO_PinModeSet(BUT_BR_PORT, BUT_BR_PIN, gpioModeInputPull, 1);
// Set falling edge interrupt and clear/enable it
GPIO_IntConfig(BUT_TL_PORT, BUT_TL_PIN, false, true, true);
GPIO_IntConfig(BUT_TR_PORT, BUT_TR_PIN, false, true, true);
GPIO_IntConfig(BUT_BL_PORT, BUT_BL_PIN, false, true, true);
GPIO_IntConfig(BUT_BR_PORT, BUT_BR_PIN, false, true, true);
NVIC_ClearPendingIRQ(GPIO_ODD_IRQn);
NVIC_EnableIRQ(GPIO_ODD_IRQn);
NVIC_ClearPendingIRQ(GPIO_EVEN_IRQn);
NVIC_EnableIRQ(GPIO_EVEN_IRQn);
}
/*
* 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 Button routines
*/
#ifndef BUTTONS_H
#define BUTTONS_H
#include "em_gpio.h"
// Top left button
#define BUT_TL_PORT gpioPortC
#define BUT_TL_PIN 7
// Top right button
#define BUT_TR_PORT gpioPortA
#define BUT_TR_PIN 0
// Bottom left button
#define BUT_BL_PORT gpioPortC
#define BUT_BL_PIN 6
// Bottom right button
#define BUT_BR_PORT gpioPortA
#define BUT_BR_PIN 8
/**
* @TODO desc
*/
void buttons_init(void);
#endif /* BUTTONS_H */
/***************************************************************************//**
* @file
* @brief I2C1 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;
CMU_ClockEnable(cmuClock_HFPER, true);
CMU_ClockEnable(cmuClock_I2C1, 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, 12, gpioModeWiredAnd, 1);
GPIO_PinModeSet(gpioPortB, 11, 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(gpioPortB, 12, gpioModeWiredAnd, 0);
GPIO_PinModeSet(gpioPortB, 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 I2C1 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.
*
*****************************************************************************/
#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 */
/*
* 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 LS013B7DH03 LCD driver
*/
#include "lcd.h"
#include <em_cmu.h>
#include <em_usart.h>
#include <em_rtc.h>
#include <udelay.h>
// Enable 90* rotation
#define LCD_ROTATE
// Do not use DMA for frame transfer
#define LCD_NODMA
// Additional bytes to control the LCD; required for DMA transfers
#ifdef LCD_NODMA
#define CONTROL_BYTES 0
#else
#define CONTROL_BYTES 2
#endif
// Number of bytes to store one line
#define LCD_STRIDE (LCD_WIDTH / 8 + CONTROL_BYTES)
// Framebuffer - pixels are stored as consecutive rows
static uint8_t buffer[LCD_STRIDE * LCD_HEIGHT];
static void spi_init(void)
{
USART_InitSync_TypeDef usartInit = USART_INITSYNC_DEFAULT;
CMU_ClockEnable(LCD_SPI_CLOCK, true);
usartInit.baudrate = LCD_SPI_BAUDRATE;
USART_InitSync(LCD_SPI_UNIT, &usartInit);
LCD_SPI_UNIT->ROUTE = (USART_ROUTE_CLKPEN | USART_ROUTE_TXPEN | LCD_SPI_LOCATION);
}
static void spi_transmit(uint8_t *data, uint16_t length)
{
while(length > 0)
{
// Send only one byte if len==1 or data pointer is not aligned at a 16 bit
// word location in memory.
if((length == 1) || ((unsigned int)data & 0x1))
{
USART_Tx(LCD_SPI_UNIT, *(uint8_t*)data);
length--;
data++;
}
else
{
USART_TxDouble(LCD_SPI_UNIT, *(uint16_t*)data);
length -= 2;
data += 2;
}
}
// Be sure that all transfer have finished
while(!(LCD_SPI_UNIT->STATUS & USART_STATUS_TXC));
}
static void timer_init(void)
{
UDELAY_Calibrate();
}
static void timer_delay(uint16_t usecs)
{
UDELAY_Delay(usecs);
}
static void rtc_setup(unsigned int frequency)
{
RTC_Init_TypeDef rtc_init = RTC_INIT_DEFAULT;
// Enable LE domain registers
if(!(CMU->HFCORECLKEN0 & CMU_HFCORECLKEN0_LE))
CMU_ClockEnable(cmuClock_CORELE, true);
if(cmuSelect_LFXO != CMU_ClockSelectGet(cmuClock_LFA))
CMU_ClockSelectSet(cmuClock_LFA, cmuSelect_LFXO);
CMU_ClockDivSet(cmuClock_RTC, cmuClkDiv_2);
CMU_ClockEnable(cmuClock_RTC, true);
// Initialize RTC
rtc_init.enable = false; // Do not start RTC after initialization is complete
rtc_init.debugRun = false; // Halt RTC when debugging
rtc_init.comp0Top = true; // Wrap around on COMP0 match
RTC_Init(&rtc_init);
RTC_CompareSet(0, (CMU_ClockFreqGet(cmuClock_RTC) / frequency) - 1);
NVIC_EnableIRQ(RTC_IRQn);
RTC_IntEnable(RTC_IEN_COMP0);
RTC_Enable(true);
}
void RTC_IRQHandler(void)
{
RTC_IntClear(RTC_IF_COMP0);
GPIO_PinOutToggle(LCD_PORT_EXTCOMIN, LCD_PIN_EXTCOMIN);
}
void lcd_init(void)
{
uint16_t cmd;
timer_init();
spi_init();
// TODO I am pretty sure, it will be already initialized somewhere..
CMU_ClockEnable(cmuClock_GPIO, true);
// Setup IOs
GPIO_PinModeSet(LCD_PORT_SCLK, LCD_PIN_SCLK, gpioModePushPull, 0);
GPIO_PinModeSet(LCD_PORT_SI, LCD_PIN_SI, gpioModePushPull, 0);
GPIO_PinModeSet(LCD_PORT_SCS, LCD_PIN_SCS, gpioModePushPull, 0);
GPIO_PinModeSet(LCD_PORT_DISP_SEL, LCD_PIN_DISP_SEL, gpioModePushPull, 0);
GPIO_PinModeSet(LCD_PORT_DISP_PWR, LCD_PIN_DISP_PWR, gpioModePushPull, 0);
GPIO_PinModeSet(LCD_PORT_EXTCOMIN, LCD_PIN_EXTCOMIN, gpioModePushPull, 0);
// EXTMODE is hardwired
// GPIO_PinModeSet(LCD_PORT_EXTMODE, LCD_PIN_EXTMODE, gpioModePushPull, 0);
// Setup RTC to generate interrupts at given frequency
rtc_setup(LCD_POL_INV_FREQ);
lcd_power(1);
// Send command to clear the display
GPIO_PinOutSet(LCD_PORT_SCS, LCD_PIN_SCS);
timer_delay(6);
cmd = LCD_CMD_ALL_CLEAR;
spi_transmit((uint8_t*) &cmd, 2);
timer_delay(2);
GPIO_PinOutClear(LCD_PORT_SCS, LCD_PIN_SCS);
lcd_clear();
lcd_enable(1);
}
void lcd_enable(uint8_t enable)
{
if(enable)
GPIO_PinOutSet(LCD_PORT_DISP_SEL, LCD_PIN_DISP_SEL);
else
GPIO_PinOutClear(LCD_PORT_DISP_SEL, LCD_PIN_DISP_SEL);
}
void lcd_power(uint8_t enable)
{
if(enable)
GPIO_PinOutSet(LCD_PORT_DISP_PWR, LCD_PIN_DISP_PWR);
else
GPIO_PinOutClear(LCD_PORT_DISP_PWR, LCD_PIN_DISP_PWR);
}
void lcd_clear(void)
{
// Using uint32_t instead of uint8_t reduces the number of writes 4 times
uint32_t *p = (uint32_t*)buffer;
uint16_t i;
// Clear pixel buffer
for(i = 0; i < sizeof(buffer) / sizeof(uint32_t); ++i)
*p++ = 0x00;
#ifndef LCD_NODMA
// Add control codes
for(i = 1; i < LCD_HEIGHT; ++i)
{
buffer[i * LCD_STRIDE - 2] = 0xff; // Dummy
buffer[i * LCD_STRIDE - 1] = (i + 1); // Address of next line
}
#endif
}
void lcd_update(void)
{
// Need to adjust start row by one because LS013B7DH03 starts counting lines
// from 1, while the DISPLAY interface starts from 0.
const uint8_t START_ROW = 1;
// TODO use DMA
uint16_t cmd;
uint16_t i;
uint8_t *p = (uint8_t*) buffer;
GPIO_PinOutSet(LCD_PORT_SCS, LCD_PIN_SCS);
timer_delay(6);
// Send update command and first line address
cmd = LCD_CMD_UPDATE | (START_ROW << 8);
spi_transmit((uint8_t*) &cmd, 2);
#ifdef LCD_NODMA
for(i = 0; i < LCD_HEIGHT; ++i)
{
// Send pixels for this line
spi_transmit(p, LCD_WIDTH / 8);
p += (LCD_WIDTH / 8);
// TODO seems unnecessary
// if(i == LCD_HEIGHT - 1)
// cmd = 0xffff;
// else
cmd = 0xff | ((START_ROW + i + 1) << 8);
spi_transmit((uint8_t*) &cmd, 2);
}
#else
// TODO here the DMA transfer should run in the end
spi_transmit(p, LCD_STRIDE * LCD_HEIGHT);
#endif
timer_delay(2);
GPIO_PinOutClear(LCD_PORT_SCS, LCD_PIN_SCS);
}
void lcd_set_pixel(uint8_t x, uint8_t y, uint8_t value)
{
x %= LCD_WIDTH;
y %= LCD_HEIGHT;
#ifdef LCD_ROTATE
uint8_t mask = 1 << (y & 0x07);
uint16_t offset = ((LCD_WIDTH - x) * LCD_STRIDE) + (y >> 3);
#else
uint8_t mask = 1 << (x & 0x07); // == 1 << (x % 8)
uint16_t offset = (y * LCD_STRIDE) + (x >> 3); // == y * LCD_STRIDE + x / 8
#endif /* else LCD_ROTATE */
if(value)
buffer[offset] |= mask;
else
buffer[offset] &= ~mask;
}
void lcd_toggle_pixel(uint8_t x, uint8_t y)
{
x %= LCD_WIDTH;
y %= LCD_HEIGHT;
#ifdef LCD_ROTATE
uint8_t mask = 1 << (y & 0x07);
uint16_t offset = ((LCD_WIDTH - x) * LCD_STRIDE) + (y >> 3);
#else
uint8_t mask = 1 << (x & 0x07); // == 1 << (x % 8)
uint16_t offset = (y * LCD_STRIDE) + (x >> 3); // == y * LCD_STRIDE + x / 8
#endif /* else LCD_ROTATE */
buffer[offset] ^= mask;
}
uint8_t lcd_get_pixel(uint8_t x, uint8_t y)
{
x %= LCD_WIDTH;
y %= LCD_HEIGHT;
#ifdef LCD_ROTATE
uint8_t mask = 1 << (y & 0x07);
uint16_t offset = ((LCD_WIDTH - x) * LCD_STRIDE) + (y >> 3);
#else
uint8_t mask = 1 << (x & 0x07); // == 1 << (x % 8)
uint16_t offset = (y * LCD_STRIDE) + (x >> 3); // == y * LCD_STRIDE + x / 8
#endif /* else LCD_ROTATE */
return buffer[offset] & mask;
}
/*
* 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 LS013B7DH03 LCD driver
*/
#ifndef LCD_H
#define LCD_H
#include "em_gpio.h"
// Dimensions
#define LCD_HEIGHT 128
#define LCD_WIDTH 128
// Pinout
#define LCD_PORT_SCLK gpioPortC
#define LCD_PIN_SCLK 4
#define LCD_PORT_SI gpioPortC
#define LCD_PIN_SI 2
#define LCD_PORT_SCS gpioPortC
#define LCD_PIN_SCS 5
#define LCD_PORT_EXTCOMIN gpioPortA
#define LCD_PIN_EXTCOMIN 2
#define LCD_PORT_DISP_SEL gpioPortC
#define LCD_PIN_DISP_SEL 0
#define LCD_PORT_DISP_PWR gpioPortC
#define LCD_PIN_DISP_PWR 1
// Types of SPI commands
#define LCD_CMD_UPDATE 0x01
#define LCD_CMD_ALL_CLEAR 0x04
// Peripherals
#define LCD_SPI_UNIT USART2
#define LCD_SPI_CLOCK cmuClock_USART2
#define LCD_SPI_LOCATION 0
#define LCD_SPI_BAUDRATE 500000
#define LCD_POL_INV_FREQ 64
/**
* @brief LCD initialization routine.
*/
void lcd_init(void);
/**
* @brief Controls DISP_EN pin - it allows to turn off the display, but preserve the memory.
* @param uint8_t enable enables the display if greater than 0.
*/
void lcd_enable(uint8_t enable);
/**
* @brief Controls power for the display.
* @param uint8_t enable turns on the power if greater than 0.
*/
void lcd_power(uint8_t enable);
/**
* @brief Clears the LCD and the framebuffer.
*/
void lcd_clear(void);
/**
* @brief Refreshes the screen with the framebuffer contents.
*/
void lcd_update(void);
/**
* @brief Switches on/off a single pixel.
* @param uint8_t x is the x coordinate of the pixel.
* @param uint8_t y is the y coordinate of the pixel.
* @param uint8_t value turns off the pixel if 0, turns on otherwise.
*/
void lcd_set_pixel(uint8_t x, uint8_t y, uint8_t value);
/**
* @brief Toggles a single pixel.
* @param uint8_t x is the x coordinate of the pixel.
* @param uint8_t y is the y coordinate of the pixel.
*/
void lcd_toggle_pixel(uint8_t x, uint8_t y);
/**
* @brief Returns the state of a single pixel.
* @param uint8_t x is the x coordinate of the pixel.
* @param uint8_t y is the y coordinate of the pixel.
*/
uint8_t lcd_get_pixel(uint8_t x, uint8_t y);
#endif /* LCD_H */
/*
* Copyright (C) 2014 Julian Lewis
* @author Matthieu Cattin <matthieu.cattin@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 MAX44009 ambient light sensor driver
*/
#include "light_sensor.h"
#include <math.h>
#include <stdio.h>
#include "i2cdrv.h"
// Writes a register
uint8_t max44009_write_reg(uint8_t reg_add, uint8_t value)
{
I2C_TransferSeq_TypeDef seq;
I2C_TransferReturn_TypeDef ret;
seq.addr = MAX44009_ADDRESS;
seq.flags = I2C_FLAG_WRITE_WRITE; // sequence: write register address (1 byte), write value (1 byte)
// Add register address to buffer
seq.buf[0].data = &reg_add;
seq.buf[0].len = 1;
// Add value to buffer
seq.buf[1].data = &value;
seq.buf[1].len = 1;
// Initiate transfer
ret = I2CDRV_Transfer(&seq);
if(ret != i2cTransferDone)
{
return((uint8_t) ret);
}
return 0;
}
// Reads a register
uint8_t max44009_read_reg(uint8_t reg_add, uint8_t* value)
{
I2C_TransferSeq_TypeDef seq;
I2C_TransferReturn_TypeDef ret;
seq.addr = MAX44009_ADDRESS;
seq.flags = I2C_FLAG_WRITE_READ; // sequence: write register address (1 byte), read value (1 bytes)
// Add command to sequence
seq.buf[0].data = &reg_add;
seq.buf[0].len = 1;
// Read value in buffer
seq.buf[1].data = value;
seq.buf[1].len = 1;
// Initiate transfer
ret = I2CDRV_Transfer(&seq);
if(ret != i2cTransferDone)
{
return((uint8_t) ret);
}
return 0;
}
uint8_t light_sensor_set_int(uint8_t enable)
{
return 0;
}
uint8_t light_sensor_get_isr(uint8_t* isr)
{
return 0;
}
uint8_t light_sensor_set_cfg(Light_Sensor_Conf_TypeDef *cfg)
{
return 0;
}
uint8_t light_sensor_get_lux(double* lux)
{
uint8_t err, high_b, low_b, m, e;
/* TODO
* For accurate reading, high and low registers have to
* be read during the same i2c transfer.
* => Apparently not possible with the current i2cdrvr!
*
* For now, only read high byte
*/
// Read Lux registers high byte
err = max44009_read_reg(MAX44009_REG_LUX_H, &high_b);
if(err)
{
return err;
}
/*
// Read Lux register low byte
err = max44009_read_reg(MAX44009_REG_LUX_L, &low_b);
if(err)
{
return err;
}
*/
// Extract mantissa and exponent
m = high_b & 0xff;
//m = ((high_b & 0xff) << 4) + (low_b & 0xff);
e = ((high_b & 0xff00) >> 4);
// Calculate Lux value
*lux = pow(2,(double) e) * m * 0.72;
//*lux = pow(2,(double) e) * m * 0.045;
return 0;
}
uint8_t light_sensor_set_thres(double thres)
{
return 0;
}
uint8_t light_sensor_set_thres_timer(uint8_t timer)
{
return 0;
}
/*
* Copyright (C) 2014 Julian Lewis
* @author Matthieu Cattin <matthieu.cattin@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 MAX44009 ambient light sensor driver
*/
#ifndef __LIGHT_SENSOR_H_
#define __LIGHT_SENSOR_H_
#include <stdint.h>
#include <stdbool.h>
// I2C address
#define MAX44009_ADDRESS 0x94
// MAX44009 registers
#define MAX44009_REG_INT_STAT 0x00
#define MAX44009_REG_INT_EN 0x01
#define MAX44009_REG_CONFIG 0x02
#define MAX44009_REG_LUX_H 0x03
#define MAX44009_REG_LUX_L 0x04
#define MAX44009_REG_THRES_H 0x05
#define MAX44009_REG_THRES_L 0x06
#define MAX44009_REG_THRES_TIME 0x07
// Configuration register bits
#define MAX44009_CFG_CONT 0x80 // Continuous mode
#define MAX44009_CFG_MAN 0x40 // Manual configuration
#define MAX44009_CFG_CDR 0x08 // Current division ratio
#define MAX44009_CFG_TIM 0x07 // Integration time
/** Ambient light sensor configuration structure. */
typedef struct
{
bool cont;
bool manual;
bool cdr;
uint8_t timer;
} Light_Sensor_Conf_TypeDef;
uint8_t light_sensor_set_int(uint8_t enable);
uint8_t light_sensor_get_isr(uint8_t* isr);
uint8_t light_sensor_set_cfg(Light_Sensor_Conf_TypeDef *cfg);
uint8_t light_sensor_get_lux(double* lux);
uint8_t light_sensor_set_thres(double thres);
uint8_t light_sensor_set_thres_timer(uint8_t timer);
#endif /* LIGHT_SENSOR_H */
/*
* Copyright (C) 2014 Julian Lewis
* @author Maciej Suminski <maciej.suminski@cern.ch>
* @author Matthieu Cattin <matthieu.cattin@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 Fuel gauge driver (MAX17047)
*/
#include "max17047.h"
#include "i2cdrv.h"
#include "delay.h"
uint8_t max17047_read_reg(uint8_t address, uint8_t length, uint8_t* buffer)
{
I2C_TransferSeq_TypeDef seq;
I2C_TransferReturn_TypeDef ret;
seq.addr = MAX17047_ADDRESS;
seq.flags = I2C_FLAG_WRITE_READ; // write/read sequence
// Select offset to start reading from
seq.buf[0].data = &address;
seq.buf[0].len = 1;
// Select location/length of data to be read
seq.buf[1].data = buffer;
seq.buf[1].len = length;
ret = I2CDRV_Transfer(&seq);
if(ret != i2cTransferDone)
{
return((uint8_t) ret);
}
return length;
}
uint8_t max17047_write_reg(uint8_t address, uint8_t length, uint8_t* buffer)
{
I2C_TransferSeq_TypeDef seq;
I2C_TransferReturn_TypeDef ret;
seq.addr = MAX17047_ADDRESS;
seq.flags = I2C_FLAG_WRITE_WRITE; // write/write sequence
// Select offset to start reading from
seq.buf[0].data = &address;
seq.buf[0].len = 1;
// Select location/length of data to be read
seq.buf[1].data = buffer;
seq.buf[1].len = length;
ret = I2CDRV_Transfer(&seq);
if(ret != i2cTransferDone)
{
return((uint8_t) ret);
}
return length;
// TODO ack polling to determine if the write operation is finished?
}
uint8_t max17047_init(void)
{
uint16_t status;
// Check if POR bit is set
status = max17047_get_status();
if(status & MAX17047_STS_POR)
{
Delay(600); // 600ms
// restore saved register (learned-values, application registers)
// TODO: use the eeprom emulator from AN0019
// clear POR bit
status &= ~MAX17047_STS_POR;
max17047_write_reg(MAX17047_REG_STATUS, 2, (uint8_t*) &status);
}
return 0;
}
uint8_t max17047_save_regs(void)
{
// TODO: use the eeprom emulator from AN0019
return 0;
}
uint16_t max17047_get_status(void)
{
uint16_t status;
max17047_read_reg(MAX17047_REG_STATUS, 2, (uint8_t*) &status);
return status;
}
uint16_t max17047_get_config(void)
{
uint16_t config;
max17047_read_reg(MAX17047_REG_CONFIG, 2, (uint8_t*) &config);
return config;
}
uint8_t max17047_set_config(uint16_t config)
{
uint8_t err;
err = max17047_write_reg(MAX17047_REG_CONFIG, 2, (uint8_t*) &config);
return err;
}
uint16_t max17047_get_voltage(void)
{
uint16_t tmp;
max17047_read_reg(MAX17047_REG_VCELL, 2, (uint8_t*) &tmp);
// convert to mV
uint32_t volt = tmp * 80 >> 10;
return (uint16_t) volt;
}
int16_t max17047_get_current(void)
{
int16_t tmp;
max17047_read_reg(MAX17047_REG_CURRENT, 2, (uint8_t*) &tmp);
// convert to mA
int32_t curr = tmp * 160 >> 10;
return (int16_t) curr;
}
int8_t max17047_get_temperature(void)
{
int8_t temperature[2];
max17047_read_reg(MAX17047_REG_TEMPERATURE, 2, (uint8_t*) temperature);
return temperature[1];
}
uint8_t max17047_get_charge(void)
{
uint8_t charge[2];
max17047_read_reg(MAX17047_REG_SOC_REP, 2, charge);
return charge[1];
}
uint16_t max17047_get_time_left(void)
{
uint16_t time;
max17047_read_reg(MAX17047_REG_TIME_TO_EMPTY, 2, (uint8_t*) &time);
// convert to minutes
time >>= 5;
time *= 3;
return time;
}
/*
* Copyright (C) 2014 Julian Lewis
* @author Maciej Suminski <maciej.suminski@cern.ch>
* @author Matthieu Cattin <matthieu.cattin@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 Fuel gauge driver (MAX17047)
*/
#ifndef __MAX17047_H_
#define __MAX17047_H_
#include <stdint.h>
// Two-wire protocol address
#define MAX17047_ADDRESS 0x6C
// Register addresses
#define MAX17047_REG_STATUS 0x00
#define MAX17047_REG_VALRT_TH 0x01
#define MAX17047_REG_TALRT_TH 0x02
#define MAX17047_REG_SALRT_TH 0x03
#define MAX17047_REG_AT_RATE 0x04
#define MAX17047_REG_REM_CAP_REP 0x05
#define MAX17047_REG_SOC_REP 0x06
#define MAX17047_REG_AGE 0x07
#define MAX17047_REG_TEMPERATURE 0x08
#define MAX17047_REG_VCELL 0x09
#define MAX17047_REG_CURRENT 0x0A
#define MAX17047_REG_AVR_CURRENT 0x0B
#define MAX17047_REG_SOC_MIX 0x0D
#define MAX17047_REG_SOC_AV 0x0E
#define MAX17047_REG_REM_CAP_MIX 0x0F
#define MAX17047_REG_FULL_CAP 0x10
#define MAX17047_REG_TIME_TO_EMPTY 0x11
#define MAX17047_REG_QRESIDUAL_00 0x12
#define MAX17047_REG_FULL_SOC_THR 0x13
#define MAX17047_REG_AVG_TEMP 0x16
#define MAX17047_REG_CYCLES 0x17
#define MAX17047_REG_DESIGN_CAP 0x18
#define MAX17047_REG_AVG_VCELL 0x19
#define MAX17047_REG_MAX_MIN_TEMP 0x1A
#define MAX17047_REG_MAX_MIN_VCELL 0z1B
#define MAX17047_REG_MAX_MIN_CURRENT 0x1C
#define MAX17047_REG_CONFIG 0x1D
#define MAX17047_REG_ICHG_TERM 0x1E
#define MAX17047_REG_REM_CAP_AV 0x1F
#define MAX17047_REG_VERSION 0x21
#define MAX17047_REG_QRESIDUAL_10 0x22
#define MAX17047_REG_FULL_CAP_NOM 0x23
#define MAX17047_REG_TEMP_NOM 0x24
#define MAX17047_REG_TEMP_LIM 0x25
#define MAX17047_REG_AIN 0x27
#define MAX17047_REG_LEARN_CFG 0x28
#define MAX17047_REG_FILTER_CFG 0x29
#define MAX17047_REG_RELAX_CFG 0x30
#define MAX17047_REG_MISC_CFG 0x2B
#define MAX17047_REG_TGAIN 0x2C
#define MAX17047_REG_TOFF 0x2D
#define MAX17047_REG_CGAIN 0x2E
#define MAX17047_REG_COFF 0x2F
#define MAX17047_REG_QRESIDUAL_20 0x32
#define MAX17047_REG_IAVG_EMPTY 0x36
#define MAX17047_REG_FCTC 0x37
#define MAX17047_REG_RCOMP 0x38
#define MAX17047_REG_TEMP_CO 0x39
#define MAX17047_REG_V_EMPTY 0x3A
#define MAX17047_REG_FSTAT 0x3D
#define MAX17047_REG_TIMER 0x3E
#define MAX17047_REG_SHDN_TIMER 0x3F
#define MAX17047_REG_QRESIDUAL_30 0x42
#define MAX17047_REG_DQACC 0x45
#define MAX17047_REG_DPACC 0x46
#define MAX17047_REG_QH 0x4D
#define MAX17047_REG_CHAR_TABLE_START 0x80
#define MAX17047_REG_CHAR_TABLE_END 0xAF
#define MAX17047_REG_VFOCV 0xFB
#define MAX17047_REG_SOC_VF 0xFF
// Status register bits
// Power-On Reset (1 == hw/sw POR event occurred; needs reconfig)
#define MAX17047_STS_POR 0x0002
// Battery Status (0 == present, 1 == absent)
#define MAX17047_STS_BST 0x0008
// Minimum Valrt Threshold Exceeded (1 == Vcell < min Valrt)
#define MAX17047_STS_VMN 0x0100
// Minimum Talrt Threshold Exceeded (1 == temperature < min Talrt)
#define MAX17047_STS_TMN 0x0200
// Minimum SOCalrt Threshold Exceeded (1 == SOC < min SOCalrt)
#define MAX17047_STS_SMN 0x0400
// Battery Insertion (1 == battery has been inserted; has to be cleared manually)
#define MAX17047_STS_BI 0x0800
// Maximum Valrt Threshold Exceeded (1 == Vcell > max Valrt)
#define MAX17047_STS_VMX 0x1000
// Maximum Talrt Threshold Exceeded (1 == temperature > max Talrt)
#define MAX17047_STS_TMX 0x2000
// Maximum SOC Threshold Exceeded (1 == SOC > max SOCalrt)
#define MAX17047_STS_SMX 0x4000
// Battery Removal (1 == battery has been removed; has to be cleared manually)
#define MAX17047_STS_BR 0x8000
// Configuration register bits
// Enables battery removal alert (default 0)
#define MAX17047_CFG_BER 0x0001
// Enables battery insertion alert (default 0)
#define MAX17047_CFG_BEI 0x0002
// Enables alerts on outputs (default 0)
#define MAX17047_CFG_AEN 0x0004
// Forces thermistor bias switch (default 0)
#define MAX17047_CFG_FTHRM 0x0008
// Enables thermistor (default 1)
#define MAX17047_CFG_ETHRM 0x0010
// ALRT pin as shutdown input (default 0)
#define MAX17047_CFG_ALSH 0x0020
// I2C shutdown, if SDA and SCL are low for more than SHDNTIMER (default 1)
#define MAX17047_CFG_I2CSH 0x0040
// Shutdown (default 0)
#define MAX17047_CFG_SHDN 0x0080
// External temperature measurement written from host (default 1)
#define MAX17047_CFG_TEX 0x0100
// Enables temperature measurement (default 1)
#define MAX17047_CFG_TEN 0x0200
// Enables shutdown when battery is removed (default 0)
#define MAX17047_CFG_AINSH 0x0400
// ALRT pin polarity, 0=active low (default 0)
#define MAX17047_CFG_ALRTP 0x0800
// Voltage ALRT sticky, voltage alerts can only be cleared by sw if 1 (default 0)
#define MAX17047_CFG_VS 0x1000
// Temperature ALRT sticky, temperature alerts can only be cleared by sw if 1 (default 1)
#define MAX17047_CFG_TS 0x2000
// SOC ALRT sticky, SOC alerts can only be cleared by sw if 1 (default 0)
#define MAX17047_CFG_SS 0x4000
/**
* @brief Reads a register from max17047.
* @param uint8_t reg Register number (the starting one, if you read more than one).
* @param uint8_t length Number of bytes to read.
* @param uint8_t* buffer Buffer to save the read data.
* @return Length of the read data in case of success, error code otherwise.
* @see I2C_TransferSeq_TypeDef
*/
uint8_t max17047_read_reg(uint8_t address, uint8_t length, uint8_t* buffer);
/**
* @brief Writes a register to max17047.
* @param uint8_t reg Register number (the starting one, if you write more than one).
* @param uint8_t length Number of bytes to write.
* @param uint8_t* buffer Buffer with data to be written.
* @return Length of the written data in case of success, error code otherwise.
* @see I2C_TransferSeq_TypeDef
*/
uint8_t max17047_write_reg(uint8_t address, uint8_t length, uint8_t* buffer);
/**
* @brief Initialises the max17047, restores the saved registers in case of a POR.
* @return 0 if no errors.
*/
uint8_t max17047_init(void);
/**
* @brief Saves the leared-value and application register.
*
* This function should be called periodically (e.g. End-of-charge, End-of-discharge,
* prior to entering shutdown state).
*
+ @return 0 if regiters saved successfully.
*/
uint8_t max17047_save_regs(void);
/**
* @brief Reads the status.
* @return Status of max17047. Check MAX170474_STS_xxx defines for details.
*/
uint16_t max17047_get_status(void);
/**
* @brief Reads the configuration.
* @return Configuration of max17047. Check MAX170474_CFG_xxx defines for details.
*/
uint16_t max17047_get_config(void);
/**
* @brief Writes the configuration.
* @param Configuration of max17047. Check MAX170474_CFG_xxx defines for details.
* @return 0 if no error.
*/
uint8_t max17047_set_config(uint16_t config);
/**
* @brief Reads the battery voltage.
* @return Battery voltage (in millivolts).
*/
uint16_t max17047_get_voltage(void);
/**
* @brief Reads current drawn from the battery.
* @return Current (in milliampers). Negative values represent discharging,
* positive values represent charging.
*/
int16_t max17047_get_current(void);
/**
* @brief Reads temperature sensor.
* @return Temperature (*C).
*/
int8_t max17047_get_temperature(void);
/**
* @brief Reads state of charge.
* @return State of charge (expressed as percentage: 0-100).
*/
uint8_t max17047_get_charge(void);
/**
* @brief Reads remaining time to empty the battery.
* @return Time to empty (in minutes).
*/
uint16_t max17047_get_time_left(void);
#endif /*__MAX17047_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