Commit da2126f8 authored by Matthieu Cattin's avatar Matthieu Cattin

sw: Working altimeter driver. Put delay function in separate files. Add pressure…

sw: Working altimeter driver. Put delay function in separate files. Add pressure to altitude conversion function.
parent a763c050
......@@ -159,6 +159,7 @@ C_SRC += \
../common/gfx/font_xm4x5.c \
../common/gfx/font_xm4x6.c \
../common/udelay.c \
../common/delay.c \
../common/drivers/i2cdrv.c \
../common/drivers/altimeter.c \
main.c
......
......@@ -25,7 +25,8 @@
*/
#include <stdio.h>
#include <udelay.h>
#include <math.h>
#include <delay.h>
#include <i2cdrv.h>
#include <em_device.h>
#include <em_cmu.h>
......@@ -34,30 +35,21 @@
#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)
void print_err(uint8_t err)
{
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;
char str[20];
curTicks = msTicks;
while ((msTicks - curTicks) < dlyTicks);
Delay(1000);
lcd_clear();
sprintf(str, "err: 0x%02x", err);
text(&font_helv17, 5, 10, str);
lcd_update();
Delay(1000);
lcd_clear();
}
/**
* @brief Main function
*/
......@@ -65,11 +57,12 @@ int main(void)
{
I2C_Init_TypeDef i2cInit = I2C_INIT_DEFAULT;
int x, y, i;
//int x, y, i;
char str[20];
uint8_t cmd, ret;
uint8_t buf[16];
uint16_t calib_data[8];
uint8_t err;
double temp = 0;
double pressure = 0;
double altitude = 0;
/* Setup SysTick Timer for 1 msec interrupts */
if (SysTick_Config(CMU_ClockFreqGet(cmuClock_CORE) / 1000)) while (1);
......@@ -83,44 +76,36 @@ int main(void)
lcd_init();
UDELAY_Calibrate();
I2CDRV_Init(&i2cInit);
err = alti_init();
sprintf(str, "init: 0x%02x", err);
text(&font_helv11, 5, 10, str);
lcd_update();
while(1)
{
err = alti_get_temp_pressure(&temp, &pressure);
sprintf(str, "temp: %f C", temp);
text(&font_helv11, 5, 20, str);
sprintf(str, "pressure: %f mbar", pressure);
text(&font_helv11, 5, 30, str);
err = alti_mbar2altitude(pressure, &altitude);
sprintf(str, "altitude: %f m", altitude);
text(&font_helv11, 5, 40, str);
//sprintf(str, "err: 0x%02x", err);
//text(&font_helv11, 5, 50, str);
lcd_update();
//Delay(1000);
box(5, 10, 128, 50, 0);
//lcd_clear();
}
while (1) {
ms5806_write_cmd(MS5806_CMD_RESET);
Delay(1000);
ms5806_write_cmd(MS5806_CMD_READ_PROM);
Delay(2000);
//GPIO_PinOutSet(gpioPortE, 11);
for(i=0; i<MS5806_PROM_SIZE; i++)
{
cmd = MS5806_CMD_READ_PROM + (MS5806_PROM_ADR_MASK & (i << 1));
//ms5806_write_cmd(cmd);
//ms5806_read_reg(cmd, 2, &buf[2*i]);
ret = ms5806_read_reg(cmd, 2, (uint8_t*) calib_data);
sprintf(str, "C%d:0x%04x %x",i,calib_data[i], ret);
//sprintf(str, "C%d:0x%x%x",i,buf[2*i],buf[2*i+1]);
text(&font_helv17, 5, 15*i, str);
lcd_update();
Delay(1000);
}
//GPIO_PinOutSet(gpioPortE, 12);
//Delay(200);
}
/* Infinite blink loop */
while (1) {
Delay(200);
GPIO_PinOutClear(gpioPortE, 11);
GPIO_PinOutClear(gpioPortE, 12);
}
}
/*
* 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 Active delay utility
*/
#include <delay.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);
}
/*
* 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 Active delay utility
*/
#ifndef DELAY_H
#define DELAY_H
#include <stdint.h>
/*
* @brief Delays number of msTick Systicks (typically 1 ms)
* @param dlyTicks Number of ticks to delay
*/
void Delay(uint32_t dlyTicks);
#endif /* DELAY_H */
......@@ -26,11 +26,39 @@
#include "altimeter.h"
#include "i2cdrv.h"
#include <udelay.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)
......@@ -42,7 +70,7 @@ uint8_t ms5806_write_cmd(uint8_t cmd)
seq.flags = I2C_FLAG_WRITE; // sequence: write command (1 byte)
// Add command to buffer
seq.buf[0].data = cmd;
seq.buf[0].data = &cmd;
seq.buf[0].len = 1;
// Initiate transfer
......@@ -86,108 +114,174 @@ uint8_t ms5806_read_reg(uint8_t cmd, uint8_t length, uint8_t* buffer)
// Check PROM CRC
uint8_t ms5806_crc_chk(void)
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.
*/
void alti_init(void)
uint8_t alti_init(void)
{
uint8_t i, cmd, ret;
uint8_t i, err, cmd, crc;
uint8_t buf[2*MS5806_PROM_SIZE];
// calibrate udelay, TODO: move it out of altimeter driver
UDELAY_Calibrate();
// Reset the sensor
err = ms5806_write_cmd(MS5806_CMD_RESET);
if(err)
{
return err;
}
// Reset
ret = ms5806_write_cmd(MS5806_CMD_RESET); // TODO: do something with the return value
// Wait for the sensor to be ready
Delay(10); // 10ms
// Dummy command
ret = ms5806_write_cmd(MS5806_CMD_READ_PROM); // 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 + (MS5806_PROM_ADR_MASK & (i << 1));
ret = ms5806_read_reg(cmd, 2, (uint8_t*) calib_data); // TODO: do something with the return value
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 and compensate pressure value.
* @return Pressure in hundredth of millibars (e.g. 110002 = 1100.02mbar).
* @brief Reads temperature value.
* @param temp : Temperature in celsius degrees.
* @param pressure : Pressure in millibars.
* @return i2c error code, 0 if no errors.
*/
int32_t alti_get_pressure(void)
uint8_t alti_get_temp_pressure(double* temp, double* pressure)
{
uint8_t ret;
uint8_t cmd;
uint32_t adc_val;
int32_t temp;
int32_t pressure;
int64_t tmp;
uint8_t err, cmd;
uint8_t buf[3];
uint32_t d1, d2;
double dt, off, sens;
// Initiate temperature conversion
cmd = MS5806_CMD_CONV_TEMP + (MS5806_OSR_4096 & MS5806_OSR_MASK);
err = ms5806_write_cmd(cmd);
if(err)
{
return err;
}
// Reads temperature
temp = alti_get_temperature();
// 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);
ret = ms5806_write_cmd(cmd); // TODO: do something with the return value
err = ms5806_write_cmd(cmd);
if(err)
{
return err;
}
// 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
Delay(10); // 10ms
// 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;
// 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];
return pressure;
// 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;
*pressure = (((d1 * sens)/pow(2,21) - off)/pow(2,15))/100;
return 0;
}
/**
* @brief Reads temperature value.
* @return Temperature in hundredth of celsuis degrees (e.g. 2000 = 20.00 C).
* @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.
*/
int32_t alti_get_temperature(void)
uint8_t alti_mbar2altitude(double pressure, double* altitude)
{
uint8_t ret;
uint8_t cmd;
uint32_t adc_val;
int32_t temp;
int64_t tmp;
uint8_t i;
// 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
for(i=0; i<P2A_COEFF_SIZE; i++)
{
if((pressure*10) < p2a_coeff[i][1])
{
break;
}
}
// 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;
*altitude = p2a_coeff[i][3] - (pressure*10 - p2a_coeff[i][0]) * p2a_coeff[i][2]/pow(2,11);
return i;
}
......@@ -50,26 +50,41 @@
#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.
*/
void alti_init(void);
uint8_t alti_init(void);
/**
* @brief Reads and compensate pressure value.
* @return Pressure in hundredth of millibars (e.g. 110002 = 1100.02mbar).
* @brief Reads temperature value.
* @param temp : Temperature in celsius degrees.
* @param pressure : Pressure in millibars.
* @return i2c error code, 0 if no errors.
*/
int32_t alti_get_pressure(void);
uint8_t alti_get_temp_pressure(double* temp, double* pressure);
/**
* @brief Reads temperature value.
* @return Temperature in hundredth of celsuis degrees (e.g. 2000 = 20.00 C).
* @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.
*/
int32_t alti_get_temperature(void);
uint8_t alti_mbar2altitude(double pressure, double* altitude);
#endif /* ALTIMETER_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