Browse Source

Add a driver for the Analog Devices ADIS16448 IMU (#8301)

sbg
Amir Melzer 7 years ago committed by Daniel Agar
parent
commit
a8787e8fe3
  1. 1
      cmake/configs/nuttx_px4fmu-v2_default.cmake
  2. 3
      cmake/configs/nuttx_px4fmu-v3_default.cmake
  3. 43
      src/drivers/adis16448/CMakeLists.txt
  4. 2074
      src/drivers/adis16448/adis16448.cpp
  5. 52
      src/drivers/device/nuttx/SPI.cpp
  6. 23
      src/drivers/device/nuttx/SPI.hpp
  7. 2
      src/drivers/drv_accel.h
  8. 2
      src/drivers/drv_gyro.h
  9. 3
      src/drivers/drv_mag.h
  10. 3
      src/drivers/drv_sensor.h

1
cmake/configs/nuttx_px4fmu-v2_default.cmake

@ -7,6 +7,7 @@ set(config_module_list @@ -7,6 +7,7 @@ set(config_module_list
#
# Board support modules
#
#drivers/adis16448
drivers/airspeed
#drivers/blinkm
#drivers/bmi160

3
cmake/configs/nuttx_px4fmu-v3_default.cmake

@ -12,6 +12,7 @@ set(config_module_list @@ -12,6 +12,7 @@ set(config_module_list
#
# Board support modules
#
drivers/adis16448
drivers/airspeed
drivers/blinkm
drivers/bmi160
@ -27,8 +28,8 @@ set(config_module_list @@ -27,8 +28,8 @@ set(config_module_list
drivers/hott
drivers/hott/hott_sensors
drivers/hott/hott_telemetry
drivers/irlock
drivers/iridiumsbd
drivers/irlock
drivers/l3gd20
drivers/led
drivers/lis3mdl

43
src/drivers/adis16448/CMakeLists.txt

@ -0,0 +1,43 @@ @@ -0,0 +1,43 @@
############################################################################
#
# 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.
#
############################################################################
px4_add_module(
MODULE drivers__adis16448
MAIN adis16448
STACK_MAIN 1200
COMPILE_FLAGS
SRCS
adis16448.cpp
DEPENDS
platforms__common
)
# vim: set noet ft=cmake fenc=utf-8 ff=unix :

2074
src/drivers/adis16448/adis16448.cpp

File diff suppressed because it is too large Load Diff

52
src/drivers/device/nuttx/SPI.cpp

@ -181,4 +181,56 @@ SPI::_transfer(uint8_t *send, uint8_t *recv, unsigned len) @@ -181,4 +181,56 @@ SPI::_transfer(uint8_t *send, uint8_t *recv, unsigned len)
return OK;
}
int
SPI::transferhword(uint16_t *send, uint16_t *recv, unsigned len)
{
int result;
if ((send == nullptr) && (recv == nullptr)) {
return -EINVAL;
}
LockMode mode = up_interrupt_context() ? LOCK_NONE : locking_mode;
/* lock the bus as required */
switch (mode) {
default:
case LOCK_PREEMPTION: {
irqstate_t state = px4_enter_critical_section();
result = _transferhword(send, recv, len);
px4_leave_critical_section(state);
}
break;
case LOCK_THREADS:
SPI_LOCK(_dev, true);
result = _transferhword(send, recv, len);
SPI_LOCK(_dev, false);
break;
case LOCK_NONE:
result = _transferhword(send, recv, len);
break;
}
return result;
}
int
SPI::_transferhword(uint16_t *send, uint16_t *recv, unsigned len)
{
SPI_SETFREQUENCY(_dev, _frequency);
SPI_SETMODE(_dev, _mode);
SPI_SETBITS(_dev, 16); /* 16 bit transfer */
SPI_SELECT(_dev, _device, true);
/* do the transfer */
SPI_EXCHANGE(_dev, send, recv, len);
/* and clean up */
SPI_SELECT(_dev, _device, false);
return OK;
}
} // namespace device

23
src/drivers/device/nuttx/SPI.hpp

@ -108,6 +108,27 @@ protected: @@ -108,6 +108,27 @@ protected:
*/
int transfer(uint8_t *send, uint8_t *recv, unsigned len);
/**
* Perform a SPI 16 bit transfer.
*
* If called from interrupt context, this interface does not lock
* the bus and may interfere with non-interrupt-context callers.
*
* Clients in a mixed interrupt/non-interrupt configuration must
* ensure appropriate interlocking.
*
* At least one of send or recv must be non-null.
*
* @param send Words to send to the device, or nullptr if
* no data is to be sent.
* @param recv Words for receiving bytes from the device,
* or nullptr if no bytes are to be received.
* @param len Number of words to transfer.
* @return OK if the exchange was successful, -errno
* otherwise.
*/
int transferhword(uint16_t *send, uint16_t *recv, unsigned len);
/**
* Set the SPI bus frequency
* This is used to change frequency on the fly. Some sensors
@ -144,6 +165,8 @@ private: @@ -144,6 +165,8 @@ private:
protected:
int _transfer(uint8_t *send, uint8_t *recv, unsigned len);
int _transferhword(uint16_t *send, uint16_t *recv, unsigned len);
bool external() { return px4_spi_bus_external(get_device_bus()); }
};

2
src/drivers/drv_accel.h

@ -112,5 +112,7 @@ struct accel_calibration_s { @@ -112,5 +112,7 @@ struct accel_calibration_s {
/** determine if hardware is external or onboard */
#define ACCELIOCGEXTERNAL _ACCELIOC(12)
/** get the current accel type */
#define ACCELIOCTYPE _ACCELIOC(13)
#endif /* _DRV_ACCEL_H */

2
src/drivers/drv_gyro.h

@ -109,5 +109,7 @@ struct gyro_calibration_s { @@ -109,5 +109,7 @@ struct gyro_calibration_s {
/** determine if hardware is external or onboard */
#define GYROIOCGEXTERNAL _GYROIOC(12)
/** get the current gyro type */
#define GYROIOCTYPE _GYROIOC(13)
#endif /* _DRV_GYRO_H */

3
src/drivers/drv_mag.h

@ -108,4 +108,7 @@ struct mag_calibration_s { @@ -108,4 +108,7 @@ struct mag_calibration_s {
/** enable/disable temperature compensation */
#define MAGIOCSTEMPCOMP _MAGIOC(12)
/** get the current mag type */
#define MAGIOCTYPE _MAGIOC(13)
#endif /* _DRV_MAG_H */

3
src/drivers/drv_sensor.h

@ -100,6 +100,9 @@ @@ -100,6 +100,9 @@
#define DRV_ACC_DEVTYPE_FXOS8701C 0x52
#define DRV_MAG_DEVTYPE_FXOS8701C 0x53
#define DRV_GYR_DEVTYPE_FXAS2100C 0x54
#define DRV_ACC_DEVTYPE_ADIS16448 0x55
#define DRV_MAG_DEVTYPE_ADIS16448 0x56
#define DRV_GYR_DEVTYPE_ADIS16448 0x57
/*
* ioctl() definitions

Loading…
Cancel
Save