Refactor MS5611 driver to use interface nubs for the I2C and SPI versions of the chip. This reduces the amount of duplicated code.

This commit is contained in:
px4dev 2013-07-14 11:45:21 -07:00
parent 6c7f1e883e
commit 5350c2be09
4 changed files with 782 additions and 1231 deletions

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,86 @@
/****************************************************************************
*
* Copyright (C) 2012-2013 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file ms5611.h
*
* Shared defines for the ms5611 driver.
*/
#define ADDR_RESET_CMD 0x1E /* write to this address to reset chip */
#define ADDR_CMD_CONVERT_D1 0x48 /* write to this address to start temperature conversion */
#define ADDR_CMD_CONVERT_D2 0x58 /* write to this address to start pressure conversion */
#define ADDR_DATA 0x00 /* address of 3 bytes / 32bit pressure data */
#define ADDR_PROM_SETUP 0xA0 /* address of 8x 2 bytes factory and calibration data */
#define ADDR_PROM_C1 0xA2 /* address of 6x 2 bytes calibration data */
/* interface ioctls */
#define IOCTL_SET_PROMBUFFER 1
#define IOCTL_RESET 2
#define IOCTL_MEASURE 3
/* interface factories */
extern device::Device *MS5611_spi_interface() weak_function;
extern device::Device *MS5611_i2c_interface() weak_function;
namespace ms5611
{
/**
* Calibration PROM as reported by the device.
*/
#pragma pack(push,1)
struct prom_s {
uint16_t factory_setup;
uint16_t c1_pressure_sens;
uint16_t c2_pressure_offset;
uint16_t c3_temp_coeff_pres_sens;
uint16_t c4_temp_coeff_pres_offset;
uint16_t c5_reference_temp;
uint16_t c6_temp_coeff_temp;
uint16_t serial_and_crc;
};
/**
* Grody hack for crc4()
*/
union prom_u {
uint16_t c[8];
prom_s s;
};
#pragma pack(pop)
extern bool crc4(uint16_t *n_prom);
} /* namespace */

View File

@ -0,0 +1,264 @@
/****************************************************************************
*
* Copyright (c) 2013 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file ms5611_i2c.cpp
*
* I2C interface for MS5611
*/
#ifndef PX4_I2C_BUS_ONBOARD
#define MS5611_BUS 1
#else
#define MS5611_BUS PX4_I2C_BUS_ONBOARD
#endif
#define MS5611_ADDRESS_1 0x76 /* address select pins pulled high (PX4FMU series v1.6+) */
#define MS5611_ADDRESS_2 0x77 /* address select pins pulled low (PX4FMU prototypes) */
device::Device *MS5611_i2c_interface();
class MS5611_I2C : device::I2C
{
public:
MS5611_I2C(int bus);
virtual ~MS5611_I2C();
virtual int init();
virtual int read(unsigned offset, void *data, unsigned count);
virtual int ioctl(unsigned operation, unsigned &arg);
protected:
virtual int probe();
private:
ms5611::prom_u *_prom
int _probe_address(uint8_t address);
/**
* Send a reset command to the MS5611.
*
* This is required after any bus reset.
*/
int _reset();
/**
* Send a measure command to the MS5611.
*
* @param addr Which address to use for the measure operation.
*/
int _measure(unsigned addr);
/**
* Read the MS5611 PROM
*
* @return OK if the PROM reads successfully.
*/
int _read_prom();
};
device::Device *
MS5611_i2c_interface()
{
#ifdef PX4_I2C_OBDEV_MS5611
return new MS5611_I2C(MS5611_BUS);
#endif
return nullptr;
}
MS5611_I2C::MS5611_I2C(int bus, ms5611_prom_u &prom) :
I2C("MS5611_I2C", nullptr, bus, 0, 400000),
_prom(prom)
{
}
MS5611_I2C::~MS5611_I2C()
{
}
int
MS5611_I2C::init()
{
/* this will call probe(), and thereby _probe_address */
return I2C::init();
}
int
MS5611_I2C::read(unsigned offset, void *data, unsigned count)
{
union _cvt {
uint8_t b[4];
uint32_t w;
} *cvt = (_cvt *)data;
uint8_t buf[3];
/* read the most recent measurement */
uint8_t cmd = 0;
int ret = transfer(&cmd, 1, &buf[0], 3);
if (ret == OK) {
/* fetch the raw value */
cvt->b[0] = buf[2];
cvt->b[1] = buf[1];
cvt->b[2] = buf[0];
cvt->b[3] = 0;
}
return ret;
}
int
MS5611_I2C::ioctl(unsigned operation, unsigned &arg)
{
int ret;
switch (operation) {
case IOCTL_SET_PROMBUFFER:
_prom = reinterpret_cast<ms5611_prom_u *>(arg);
ret = OK;
break;
case IOCTL_RESET:
ret = _reset();
break;
case IOCTL_MEASURE:
ret = _measure(arg);
break;
default:
ret = EINVAL;
}
return ret;
}
int
MS5611_I2C::probe()
{
_retries = 10;
if ((OK == _probe_address(MS5611_ADDRESS_1)) ||
(OK == _probe_address(MS5611_ADDRESS_2))) {
/*
* Disable retries; we may enable them selectively in some cases,
* but the device gets confused if we retry some of the commands.
*/
_retries = 0;
return OK;
}
return -EIO;
}
int
MS5611_I2C::_probe_address(uint8_t address)
{
/* select the address we are going to try */
set_address(address);
/* send reset command */
if (OK != _reset())
return -EIO;
/* read PROM */
if (OK != _read_prom())
return -EIO;
return OK;
}
int
MS5611_I2C::_reset()
{
unsigned old_retrycount = _retries;
uint8_t cmd = ADDR_RESET_CMD;
int result;
/* bump the retry count */
_retries = 10;
result = transfer(&cmd, 1, nullptr, 0);
_retries = old_retrycount;
return result;
}
int
MS5611_I2C::_measure(unsigned addr)
{
/*
* Disable retries on this command; we can't know whether failure
* means the device did or did not see the command.
*/
_retries = 0;
uint8_t cmd = addr;
return transfer(&cmd, 1, nullptr, 0);
}
int
MS5611_I2C::_read_prom()
{
uint8_t prom_buf[2];
union {
uint8_t b[2];
uint16_t w;
} cvt;
/*
* Wait for PROM contents to be in the device (2.8 ms) in the case we are
* called immediately after reset.
*/
usleep(3000);
/* read and convert PROM words */
for (int i = 0; i < 8; i++) {
uint8_t cmd = ADDR_PROM_SETUP + (i * 2);
if (OK != transfer(&cmd, 1, &prom_buf[0], 2))
break;
/* assemble 16 bit value and convert from big endian (sensor) to little endian (MCU) */
cvt.b[0] = prom_buf[1];
cvt.b[1] = prom_buf[0];
_prom->c[i] = cvt.w;
}
/* calculate CRC and return success/failure accordingly */
return ms5611::crc4(&_prom->c[0]) ? OK : -EIO;
}

View File

@ -0,0 +1,228 @@
/****************************************************************************
*
* Copyright (c) 2013 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file ms5611_spi.cpp
*
* SPI interface for MS5611
*/
/* SPI protocol address bits */
#define DIR_READ (1<<7)
#define DIR_WRITE (0<<7)
#define ADDR_INCREMENT (1<<6)
device::Device *MS5611_spi_interface();
class MS5611_SPI : device::SPI
{
public:
MS5611_SPI(int bus, spi_dev_e device);
virtual ~MS5611_SPI();
virtual int init();
virtual int read(unsigned offset, void *data, unsigned count);
virtual int ioctl(unsigned operation, unsigned &arg);
protected:
virtual int probe();
private:
ms5611::prom_u *_prom
int _probe_address(uint8_t address);
/**
* Send a reset command to the MS5611.
*
* This is required after any bus reset.
*/
int _reset();
/**
* Send a measure command to the MS5611.
*
* @param addr Which address to use for the measure operation.
*/
int _measure(unsigned addr);
/**
* Read the MS5611 PROM
*
* @return OK if the PROM reads successfully.
*/
int _read_prom();
/**
* Read a 16-bit register value.
*
* @param reg The register to read.
*/
uint16_t _reg16(unsigned reg);
};
device::Device *
MS5611_spi_interface()
{
#ifdef PX4_SPIDEV_BARO
return new MS5611_SPI(1 /* XXX MAGIC NUMBER */, (spi_dev_e)PX4_SPIDEV_BARO);
#endif
return nullptr;
}
int
MS5611_SPI::init()
{
int ret;
ret = SPI::init();
if (ret != OK)
goto out;
/* send reset command */
ret = _reset();
if (ret != OK)
goto out;
/* read PROM */
ret = _read_prom();
if (ret != OK)
goto out;
out:
return ret;
}
int
MS5611_SPI::read(unsigned offset, void *data, unsigned count)
{
union _cvt {
uint8_t b[4];
uint32_t w;
} *cvt = (_cvt *)data;
uint8_t buf[4];
/* read the most recent measurement */
buf[0] = 0 | DIR_WRITE;
int ret = transfer(&buf[0], &buf[0], sizeof(buf));
if (ret == OK) {
/* fetch the raw value */
cvt->b[0] = data[3];
cvt->b[1] = data[2];
cvt->b[2] = data[1];
cvt->b[3] = 0;
ret = count;
}
return ret;
}
int
MS5611_SPI::ioctl(unsigned operation, unsigned &arg)
{
int ret;
switch (operation) {
case IOCTL_SET_PROMBUFFER:
_prom = reinterpret_cast<ms5611_prom_u *>(arg);
return OK;
case IOCTL_RESET:
ret = _reset();
break;
case IOCTL_MEASURE:
ret = _measure(arg);
break;
default:
ret = EINVAL;
}
if (ret != OK) {
errno = ret;
return -1;
}
return 0;
}
int
MS5611_SPI::_reset()
{
uint8_t cmd = ADDR_RESET_CMD | DIR_WRITE;
return transfer(&cmd, nullptr, 1);
}
int
MS5611_SPI::_measure(unsigned addr)
{
uint8_t cmd = addr | DIR_WRITE;
return transfer(&cmd, nullptr, 1);
}
int
MS5611_SPI::_read_prom()
{
/*
* Wait for PROM contents to be in the device (2.8 ms) in the case we are
* called immediately after reset.
*/
usleep(3000);
/* read and convert PROM words */
for (int i = 0; i < 8; i++) {
uint8_t cmd = (ADDR_PROM_SETUP + (i * 2));
_prom.c[i] = _reg16(cmd);
}
/* calculate CRC and return success/failure accordingly */
return ms5611::crc4(&_prom.c[0]) ? OK : -EIO;
}
uint16_t
MS5611_SPI::_reg16(unsigned reg)
{
uint8_t cmd[3];
cmd[0] = reg | DIR_READ;
transfer(cmd, cmd, sizeof(cmd));
return (uint16_t)(cmd[1] << 8) | cmd[2];
}