Skip to content
Snippets Groups Projects
Commit 45a601b9 authored by Robert Dickenson's avatar Robert Dickenson Committed by Lorenz Meier
Browse files

New driver for the LIS3MDL magnetometer.

parent ff800a4c
No related branches found
No related tags found
No related merge requests found
#!nsh
#
# Standard startup script for PX4FMU v1, v2, v3 onboard sensor drivers.
# Standard startup script for PX4FMU v1, v2, v3, v4 onboard sensor drivers.
#
if ver hwcmp PX4FMU_V1
......@@ -35,6 +35,11 @@ then
then
fi
# External I2C bus
if lis3mdl -X start
then
fi
# Internal I2C bus
if hmc5883 -C -T -I -R 4 start
then
......@@ -96,6 +101,10 @@ then
then
fi
if lis3mdl -R 2 start
then
fi
# Internal SPI bus is rotated 90 deg yaw
if hmc5883 -C -T -S -R 2 start
then
......@@ -163,6 +172,10 @@ then
if hmc5883 -C -T -X start
then
fi
if lis3mdl -R 2 start
then
fi
fi
if meas_airspeed start
......
......@@ -47,6 +47,7 @@ set(config_module_list
drivers/camera_trigger
drivers/bst
drivers/snapdragon_rc_pwm
drivers/lis3mdl
#
# System commands
......
......@@ -44,6 +44,7 @@ set(config_module_list
drivers/camera_trigger
drivers/bst
drivers/snapdragon_rc_pwm
drivers/lis3mdl
#
# System commands
......
......@@ -111,6 +111,7 @@ __BEGIN_DECLS
#define GPIO_SPI_CS_EXT1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN14)
#define GPIO_SPI_CS_EXT2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN15)
#define GPIO_SPI_CS_EXT3 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN13)
#define GPIO_SPI_CS_LIS (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN4)
#define PX4_SPI_BUS_SENSORS 1
#define PX4_SPI_BUS_RAMTRON 2
......@@ -123,6 +124,7 @@ __BEGIN_DECLS
#define PX4_SPIDEV_BARO 3
#define PX4_SPIDEV_MPU 4
#define PX4_SPIDEV_HMC 5
#define PX4_SPIDEV_LIS 7
/* External bus */
#define PX4_SPIDEV_EXT0 1
......@@ -147,6 +149,7 @@ __BEGIN_DECLS
*/
#define PX4_I2C_OBDEV_LED 0x55
#define PX4_I2C_OBDEV_HMC5883 0x1e
#define PX4_I2C_OBDEV_LIS3MDL 0x1e
/*
* ADC channels
......
......@@ -150,6 +150,15 @@ __EXPORT void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid,
stm32_gpiowrite(GPIO_SPI_CS_MPU, 1);
break;
case PX4_SPIDEV_LIS:
/* Making sure the other peripherals are not selected */
stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
stm32_gpiowrite(GPIO_SPI_CS_BARO, 1);
stm32_gpiowrite(GPIO_SPI_CS_LIS, !selected);
stm32_gpiowrite(GPIO_SPI_CS_MPU, 1);
break;
case PX4_SPIDEV_MPU:
/* Making sure the other peripherals are not selected */
stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
......
......@@ -84,6 +84,7 @@ __BEGIN_DECLS
#define GPIO_SPI_CS_MPU9250 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN2)
#define GPIO_SPI_CS_HMC5983 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN15)
#define GPIO_SPI_CS_LIS3MDL (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN15)
#define GPIO_SPI_CS_MS5611 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN7)
#define GPIO_SPI_CS_ICM_20608_G (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN15)
......@@ -105,6 +106,7 @@ __BEGIN_DECLS
#define GPIO_SPI_CS_OFF_MPU9250 _PIN_OFF(GPIO_SPI_CS_MPU9250)
#define GPIO_SPI_CS_OFF_HMC5983 _PIN_OFF(GPIO_SPI_CS_HMC5983)
#define GPIO_SPI_CS_OFF_LIS3MDL _PIN_OFF(GPIO_SPI_CS_LIS3MDL)
#define GPIO_SPI_CS_OFF_MS5611 _PIN_OFF(GPIO_SPI_CS_MS5611)
#define GPIO_SPI_CS_OFF_ICM_20608_G _PIN_OFF(GPIO_SPI_CS_ICM_20608_G)
......@@ -128,6 +130,7 @@ __BEGIN_DECLS
#define PX4_SPIDEV_MPU 4
#define PX4_SPIDEV_HMC 5
#define PX4_SPIDEV_ICM 6
#define PX4_SPIDEV_LIS 7
/* onboard MS5611 and FRAM are both on bus SPI2
* spi_dev_e:SPIDEV_FLASH has the value 2 and is used in the NuttX ramtron driver
......@@ -148,6 +151,7 @@ __BEGIN_DECLS
*/
#define PX4_I2C_OBDEV_LED 0x55
#define PX4_I2C_OBDEV_HMC5883 0x1e
#define PX4_I2C_OBDEV_LIS3MDL 0x1e
/*
* ADC channels
......
......@@ -56,6 +56,7 @@
#define DRV_MAG_DEVTYPE_LSM303D 0x02
#define DRV_MAG_DEVTYPE_ACCELSIM 0x03
#define DRV_MAG_DEVTYPE_MPU9250 0x04
#define DRV_MAG_DEVTYPE_LIS3MDL 0x05
#define DRV_ACC_DEVTYPE_LSM303D 0x11
#define DRV_ACC_DEVTYPE_BMA180 0x12
#define DRV_ACC_DEVTYPE_MPU6000 0x13
......
############################################################################
#
# Copyright (c) 2016 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.
#
############################################################################
px4_add_module(
MODULE drivers__lis3mdl
MAIN lis3mdl
STACK 1200
COMPILE_FLAGS
-Weffc++
-Os
SRCS
lis3mdl_i2c.cpp
lis3mdl_spi.cpp
lis3mdl.cpp
DEPENDS
platforms__common
)
# vim: set noet ft=cmake fenc=utf-8 ff=unix :
This diff is collapsed.
/****************************************************************************
*
* Copyright (c) 2015 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 lis3mdl.h
*
* Shared defines for the LIS3MDL driver.
*/
#pragma once
#define ADDR_WHO_AM_I 0x0f
#define ID_WHO_AM_I 0x3d
/* interface factories */
extern device::Device *LIS3MDL_SPI_interface(int bus);
extern device::Device *LIS3MDL_I2C_interface(int bus);
typedef device::Device *(*LIS3MDL_constructor)(int);
/****************************************************************************
*
* Copyright (c) 2013-2015 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 lis3mdl_i2c.cpp
*
* I2C interface for LIS3MDL
*/
/* XXX trim includes */
#include <px4_config.h>
#include <sys/types.h>
#include <stdint.h>
#include <stdbool.h>
#include <string.h>
#include <assert.h>
#include <debug.h>
#include <errno.h>
#include <unistd.h>
#include <arch/board/board.h>
#include <drivers/device/i2c.h>
#include <drivers/drv_mag.h>
#include <drivers/drv_device.h>
#include "lis3mdl.h"
#include "board_config.h"
#undef DEVICE_DEBUG
#define DEVICE_DEBUG printf
#ifdef PX4_I2C_OBDEV_LIS3MDL
#define LIS3MDLL_ADDRESS PX4_I2C_OBDEV_LIS3MDL
device::Device *LIS3MDL_I2C_interface(int bus);
class LIS3MDL_I2C : public device::I2C
{
public:
LIS3MDL_I2C(int bus);
virtual ~LIS3MDL_I2C();
virtual int init();
virtual int read(unsigned address, void *data, unsigned count);
virtual int write(unsigned address, void *data, unsigned count);
virtual int ioctl(unsigned operation, unsigned &arg);
protected:
virtual int probe();
};
device::Device *
LIS3MDL_I2C_interface(int bus)
{
return new LIS3MDL_I2C(bus);
}
LIS3MDL_I2C::LIS3MDL_I2C(int bus) :
I2C("LIS3MDL_I2C", nullptr, bus, LIS3MDLL_ADDRESS, 400000)
{
_device_id.devid_s.devtype = DRV_MAG_DEVTYPE_LIS3MDL;
}
LIS3MDL_I2C::~LIS3MDL_I2C()
{
}
int
LIS3MDL_I2C::init()
{
/* this will call probe() */
return I2C::init();
}
int
LIS3MDL_I2C::ioctl(unsigned operation, unsigned &arg)
{
int ret;
switch (operation) {
case MAGIOCGEXTERNAL:
// On PX4v1 the MAG can be on an internal I2C
// On everything else its always external
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
if (_bus == PX4_I2C_BUS_EXPANSION) {
return 1;
} else {
return 0;
}
#else
return 1;
#endif
case DEVIOCGDEVICEID:
return CDev::ioctl(nullptr, operation, arg);
default:
ret = -EINVAL;
}
return ret;
}
int
LIS3MDL_I2C::probe()
{
uint8_t data = 0;
_retries = 10;
if (read(ADDR_WHO_AM_I, &data, 1)) {
DEVICE_DEBUG("read_reg fail");
return -EIO;
}
_retries = 2;
if (data != ID_WHO_AM_I) {
DEVICE_DEBUG("LIS3MDL bad ID: %02x", data);
return -EIO;
}
return OK;
}
int
LIS3MDL_I2C::write(unsigned address, void *data, unsigned count)
{
uint8_t buf[32];
if (sizeof(buf) < (count + 1)) {
return -EIO;
}
buf[0] = address;
memcpy(&buf[1], data, count);
return transfer(&buf[0], count + 1, nullptr, 0);
}
int
LIS3MDL_I2C::read(unsigned address, void *data, unsigned count)
{
uint8_t cmd = address;
return transfer(&cmd, 1, (uint8_t *)data, count);
}
#endif /* PX4_I2C_OBDEV_LIS3MDL */
/****************************************************************************
*
* Copyright (c) 2013-2015 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 lis3mdl_spi.cpp
*
* SPI interface for LIS3MDL
*/
/* XXX trim includes */
#include <px4_config.h>
#include <sys/types.h>
#include <stdint.h>
#include <stdbool.h>
#include <string.h>
#include <assert.h>
#include <debug.h>
#include <errno.h>
#include <unistd.h>
#include <arch/board/board.h>
#include <drivers/device/spi.h>
#include <drivers/drv_mag.h>
#include <drivers/drv_device.h>
#include "lis3mdl.h"
#include "board_config.h"
#undef DEVICE_DEBUG
#define DEVICE_DEBUG printf
#ifdef PX4_SPIDEV_LIS
/* SPI protocol address bits */
#define DIR_READ (1<<7)
#define DIR_WRITE (0<<7)
#define ADDR_INCREMENT (1<<6)
device::Device *LIS3MDL_SPI_interface(int bus);
class LIS3MDL_SPI : public device::SPI
{
public:
LIS3MDL_SPI(int bus, spi_dev_e device);
virtual ~LIS3MDL_SPI();
virtual int init();
virtual int read(unsigned address, void *data, unsigned count);
virtual int write(unsigned address, void *data, unsigned count);
virtual int ioctl(unsigned operation, unsigned &arg);
};
device::Device *
LIS3MDL_SPI_interface(int bus)
{
return new LIS3MDL_SPI(bus, (spi_dev_e)PX4_SPIDEV_LIS);
}
LIS3MDL_SPI::LIS3MDL_SPI(int bus, spi_dev_e device) :
SPI("LIS3MDL_SPI", nullptr, bus, device, SPIDEV_MODE3, 11 * 1000 * 1000 /* will be rounded to 10.4 MHz */)
{
_device_id.devid_s.devtype = DRV_MAG_DEVTYPE_LIS3MDL;
}
LIS3MDL_SPI::~LIS3MDL_SPI()
{
}
int
LIS3MDL_SPI::init()
{
int ret;
ret = SPI::init();
if (ret != OK) {
DEVICE_DEBUG("SPI init failed");
return -EIO;
}
// read WHO_AM_I value
uint8_t data = 0;
if (read(ADDR_WHO_AM_I, &data, 1)) {
DEVICE_DEBUG("LIS3MDL read_reg fail");
}
if (data != ID_WHO_AM_I) {
DEVICE_DEBUG("LIS3MDL bad ID: %02x", data);
return -EIO;
}
return OK;
}
int
LIS3MDL_SPI::ioctl(unsigned operation, unsigned &arg)
{
int ret;
switch (operation) {
case MAGIOCGEXTERNAL:
/*
* Even if this sensor is on the external SPI
* bus it is still internal to the autopilot
* assembly, so always return 0 for internal.
*/
return 0;
case DEVIOCGDEVICEID:
return CDev::ioctl(nullptr, operation, arg);
default: {
ret = -EINVAL;
}
}
return ret;
}
int
LIS3MDL_SPI::write(unsigned address, void *data, unsigned count)
{
uint8_t buf[32];
if (sizeof(buf) < (count + 1)) {
return -EIO;
}
buf[0] = address | DIR_WRITE;
memcpy(&buf[1], data, count);
return transfer(&buf[0], &buf[0], count + 1);
}
int
LIS3MDL_SPI::read(unsigned address, void *data, unsigned count)
{
uint8_t buf[32];
if (sizeof(buf) < (count + 1)) {
return -EIO;
}
buf[0] = address | DIR_READ | ADDR_INCREMENT;
int ret = transfer(&buf[0], &buf[0], count + 1);
memcpy(data, &buf[1], count);
return ret;
}
#endif /* PX4_SPIDEV_LIS */
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment