diff --git a/boards/av/x-v1/default.cmake b/boards/av/x-v1/default.cmake index 763d56dd2030924dfec85fef2f39d9daa3441452..8b48fbcc2f83673353a387930352d8887358f80d 100644 --- a/boards/av/x-v1/default.cmake +++ b/boards/av/x-v1/default.cmake @@ -26,6 +26,7 @@ px4_add_board( gps #heater imu/adis16477 + imu/adis16497 #imu # all available imu drivers irlock lights/blinkm diff --git a/boards/px4/fmu-v5/default.cmake b/boards/px4/fmu-v5/default.cmake index b0db71d0364a8fc3e3a9638002d4bc3a486dd910..e150f0c8b53dfcdcca0397888d126c28dfd38240 100644 --- a/boards/px4/fmu-v5/default.cmake +++ b/boards/px4/fmu-v5/default.cmake @@ -27,6 +27,7 @@ px4_add_board( gps #heater imu/adis16448 + imu/adis16497 #imu # all available imu drivers imu/bmi055 imu/icm20948 diff --git a/src/drivers/drv_sensor.h b/src/drivers/drv_sensor.h index d77a279dd6dc00fc7aad78a89b309f6d507c2ca1..759f8044d4762a24bd76ab68c4f391a809b275d7 100644 --- a/src/drivers/drv_sensor.h +++ b/src/drivers/drv_sensor.h @@ -109,6 +109,8 @@ #define DRV_GYR_DEVTYPE_ADIS16477 0x60 #define DRV_ACC_DEVTYPE_LSM303AGR 0x61 #define DRV_MAG_DEVTYPE_LSM303AGR 0x62 +#define DRV_ACC_DEVTYPE_ADIS16497 0x63 +#define DRV_GYR_DEVTYPE_ADIS16497 0x64 /* * ioctl() definitions diff --git a/src/drivers/imu/CMakeLists.txt b/src/drivers/imu/CMakeLists.txt index ef5b8b6c8ac8e6f9beac933625903bb89a4f2992..2b12572fd5602c0c5fd78940df90391b5bb99c82 100644 --- a/src/drivers/imu/CMakeLists.txt +++ b/src/drivers/imu/CMakeLists.txt @@ -33,6 +33,7 @@ add_subdirectory(adis16448) add_subdirectory(adis16477) +add_subdirectory(adis16497) add_subdirectory(bma180) add_subdirectory(bmi055) add_subdirectory(bmi160) diff --git a/src/drivers/imu/adis16497/ADIS16497.cpp b/src/drivers/imu/adis16497/ADIS16497.cpp new file mode 100644 index 0000000000000000000000000000000000000000..73d26eba53fcaecc0849be13feebc490c76a73cc --- /dev/null +++ b/src/drivers/imu/adis16497/ADIS16497.cpp @@ -0,0 +1,677 @@ +/**************************************************************************** + * + * Copyright (c) 2018 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. + * + ****************************************************************************/ + +#include "ADIS16497.hpp" +#include "ADIS16497_gyro.hpp" + +#include <px4_config.h> +#include <ecl/geo/geo.h> + +#define DIR_READ 0x00 +#define DIR_WRITE 0x80 + +// ADIS16497 registers +static constexpr uint8_t PAGE_ID = 0x0; // Page identifier + +// Page 0x00 +static constexpr uint8_t SYS_E_FLAG = 0x08; // Output, system error flags +static constexpr uint8_t DIAG_STS = 0x0A; // Output, self test error flags +static constexpr uint8_t BURST_CMD = 0x7C; // Burst-read command +static constexpr uint8_t PROD_ID = 0x7E; // Output, product identification + +// Page 0x03 +static constexpr uint8_t GLOB_CMD = 0x02; // Control, global commands +static constexpr uint8_t FNCTIO_CTRL = 0x06; // Control, I/O pins, functional definitions +static constexpr uint8_t GPIO_CTRL = 0x08; // Control, I/O pins, general-purpose +static constexpr uint8_t CONFIG = 0x0A; // Control, clock and miscellaneous corrections +static constexpr uint8_t DEC_RATE = 0x0C; // Control, output sample rate decimation +static constexpr uint8_t NULL_CNFG = 0x0E; // Control, automatic bias correction configuration +static constexpr uint8_t SYNC_SCALE = 0x10; // Control, automatic bias correction configuration +static constexpr uint8_t RANG_MDL = 0x12; // Measurement range (model-specific) Identifier TODO use this +static constexpr uint8_t FILTR_BNK_0 = 0x16; // Filter selection +static constexpr uint8_t FILTR_BNK_1 = 0x18; // Filter selection + +// Stall time between SPI transfers +static constexpr uint8_t T_STALL = 2; + +using namespace time_literals; + +ADIS16497::ADIS16497(int bus, const char *path_accel, const char *path_gyro, uint32_t device, enum Rotation rotation) : + SPI("ADIS16497", path_accel, bus, device, SPIDEV_MODE3, 5000000), + _gyro(new ADIS16497_gyro(this, path_gyro)), + _sample_perf(perf_alloc(PC_ELAPSED, "ADIS16497_read")), + _sample_interval_perf(perf_alloc(PC_INTERVAL, "ADIS16497_read_int")), + _bad_transfers(perf_alloc(PC_COUNT, "ADIS16497_bad_transfers")), + _rotation(rotation) +{ + +#ifdef GPIO_SPI1_RESET_ADIS16497 + // Configure hardware reset line + px4_arch_configgpio(GPIO_SPI1_RESET_ADIS16497); +#endif /* GPIO_SPI1_RESET_ADIS16497 */ + + _device_id.devid_s.devtype = DRV_ACC_DEVTYPE_ADIS16497; + + _gyro->_device_id.devid = _device_id.devid; + _gyro->_device_id.devid_s.devtype = DRV_GYR_DEVTYPE_ADIS16497; + + // Software low pass filter for controllers + const param_t accel_cut_ph = param_find("IMU_ACCEL_CUTOFF"); + float accel_cut = ADIS16497_ACCEL_DEFAULT_DRIVER_FILTER_FREQ; + + if (accel_cut_ph != PARAM_INVALID && param_get(accel_cut_ph, &accel_cut) == PX4_OK) { + _accel_filter.set_cutoff_frequency(_sample_rate, accel_cut); + + } else { + PX4_ERR("IMU_ACCEL_CUTOFF param invalid"); + } + + const param_t gyro_cut_ph = param_find("IMU_GYRO_CUTOFF"); + float gyro_cut = ADIS16497_GYRO_DEFAULT_DRIVER_FILTER_FREQ; + + if (gyro_cut_ph != PARAM_INVALID && param_get(gyro_cut_ph, &gyro_cut) == PX4_OK) { + _gyro_filter.set_cutoff_frequency(_sample_rate, gyro_cut); + + } else { + PX4_ERR("IMU_GYRO_CUTOFF param invalid"); + } +} + +ADIS16497::~ADIS16497() +{ + /* make sure we are truly inactive */ + stop(); + + /* delete the gyro subdriver */ + delete _gyro; + + if (_accel_class_instance != -1) { + unregister_class_devname(ACCEL_BASE_DEVICE_PATH, _accel_class_instance); + } + + /* delete the perf counter */ + perf_free(_sample_perf); + perf_free(_sample_interval_perf); + perf_free(_bad_transfers); +} + +int +ADIS16497::init() +{ + if (hrt_absolute_time() < 250_ms) { + // Power-on startup time (if needed) + up_mdelay(250); + } + + /* do SPI init (and probe) first */ + if (SPI::init() != OK) { + /* if probe/setup failed, bail now */ + DEVICE_DEBUG("SPI setup failed"); + return PX4_ERROR; + } + + /* Initialize offsets and scales */ + _gyro_scale.x_offset = 0.0f; + _gyro_scale.x_scale = 1.0f; + _gyro_scale.y_offset = 0.0f; + _gyro_scale.y_scale = 1.0f; + _gyro_scale.z_offset = 0.0f; + _gyro_scale.z_scale = 1.0f; + + _accel_scale.x_offset = 0.0f; + _accel_scale.x_scale = 1.0f; + _accel_scale.y_offset = 0.0f; + _accel_scale.y_scale = 1.0f; + _accel_scale.z_offset = 0.0f; + _accel_scale.z_scale = 1.0f; + + /* do CDev init for the gyro device node, keep it optional */ + int ret = _gyro->init(); + + /* if probe/setup failed, bail now */ + if (ret != OK) { + DEVICE_DEBUG("gyro init failed"); + return ret; + } + + _accel_class_instance = register_class_devname(ACCEL_BASE_DEVICE_PATH); + + /* fetch an initial set of measurements for advertisement */ + measure(); + + /* advertise sensor topic, measure manually to initialize valid report */ + sensor_accel_s arp = {}; + + /* measurement will have generated a report, publish */ + _accel_topic = orb_advertise_multi(ORB_ID(sensor_accel), &arp, &_accel_orb_class_instance, ORB_PRIO_MAX); + + if (_accel_topic == nullptr) { + PX4_ERR("ADVERT FAIL"); + } + + sensor_gyro_s grp = {}; + _gyro->_gyro_topic = orb_advertise_multi(ORB_ID(sensor_gyro), &grp, &_gyro->_gyro_orb_class_instance, ORB_PRIO_MAX); + + if (_gyro->_gyro_topic == nullptr) { + PX4_ERR("ADVERT FAIL"); + } + + if (ret == PX4_OK) { + start(); + } + + return ret; +} + +int ADIS16497::reset() +{ +#ifdef GPIO_SPI1_RESET_ADIS16497 + // Hardware reset + px4_arch_gpiowrite(GPIO_SPI1_RESET_ADIS16497, 0); + + // The RST line must be in a low state for at least 10 μs to ensure a proper reset initiation and recovery. + up_udelay(10); + + px4_arch_gpiowrite(GPIO_SPI1_RESET_ADIS16497, 1); + + // Reset recovery time + up_mdelay(250); +#else + // Software reset (global command bit 7) + uint8_t value[2] = {}; + value[0] = (1 << 7); + write_reg16(PAGE_ID, 0x03); + write_reg16(GLOB_CMD, (uint16_t)value[0]); + + // Reset recovery time + up_mdelay(210); +#endif /* GPIO_SPI1_RESET_ADIS16497 */ + + // Switch to configuration page + write_reg16(PAGE_ID, 0x03); + + // Functional IO control + static constexpr uint16_t FNCTIO_CTRL_DEFAULT = 0x000D; + + write_reg16(FNCTIO_CTRL, FNCTIO_CTRL_DEFAULT); + + up_udelay(340); + + const uint16_t fnctio_ctrl = read_reg16(FNCTIO_CTRL); + + if (fnctio_ctrl != FNCTIO_CTRL_DEFAULT) { + PX4_ERR("Invalid setup, FNCTIO_CTRL=%#X", fnctio_ctrl); + return PX4_ERROR; + } + + // Miscellaneous configuration + static constexpr uint16_t CONFIG_DEFAULT = 0x00C0; + + write_reg16(CONFIG, CONFIG_DEFAULT); + + up_udelay(45); + + const uint16_t config = read_reg16(CONFIG); + + if (config != CONFIG_DEFAULT) { + PX4_ERR("Invalid setup, CONFIG=%#X", config); + return PX4_ERROR; + } + + // Decimation Filter + static constexpr uint16_t DEC_RATE_DEFAULT = 0x0003; // 4250/4 = 1062 samples per second + + write_reg16(DEC_RATE, DEC_RATE_DEFAULT); + + up_udelay(340); + + const uint16_t dec_rate = read_reg16(DEC_RATE); + + if (dec_rate != DEC_RATE_DEFAULT) { + PX4_ERR("Invalid setup, DEC_RATE=%#X", dec_rate); + return PX4_ERROR; + } + + // Continious bias estimation + static constexpr uint16_t NULL_CNFG_DEFAULT = 0x0000; // Disable continious bias estimation + + write_reg16(NULL_CNFG, NULL_CNFG_DEFAULT); + + up_udelay(71); + + const uint16_t null_cnfg = read_reg16(NULL_CNFG); + + if (null_cnfg != NULL_CNFG_DEFAULT) { + PX4_ERR("Invalid setup, NULL_CNFG=%#X", null_cnfg); + return PX4_ERROR; + } + + // Bartlett Window FIR Filter + static constexpr uint16_t FILTR_BNK_0_SETUP = 0x0000; // Disable FIR filter + static constexpr uint16_t FILTR_BNK_1_SETUP = 0x0000; // Disable FIR filter + + write_reg16(FILTR_BNK_0, FILTR_BNK_0_SETUP); + write_reg16(FILTR_BNK_1, FILTR_BNK_1_SETUP); + + up_udelay(65); + + const uint16_t filtr_bnk_0 = read_reg16(FILTR_BNK_0); + + if (filtr_bnk_0 != FILTR_BNK_0_SETUP) { + PX4_ERR("Invalid setup, FILTR_BNK_0=%#X", filtr_bnk_0); + return PX4_ERROR; + } + + const uint16_t filtr_bnk_1 = read_reg16(FILTR_BNK_1); + + if (filtr_bnk_1 != FILTR_BNK_1_SETUP) { + PX4_ERR("Invalid setup, FILTR_BNK_1=%#X", filtr_bnk_1); + return PX4_ERROR; + } + + /* + // Save to flash memory (NOTE : Limited cycles!) + uint8_t value[2] = {}; + value[0] = (1 << 3); + write_reg16(PAGE_ID, 0x03); + write_reg16(GLOB_CMD, (uint16_t)value[0]); + + // save Recovery Time + up_mdelay(1125); + */ + + return OK; +} + +int +ADIS16497::probe() +{ + DEVICE_DEBUG("probe"); + + // read product id (5 attempts) + for (int i = 0; i < 5; i++) { + + if (reset() != PX4_OK) { + continue; + } + + // Switch to output page + write_reg16(PAGE_ID, 0x00); + + // Check if the device is an ADIS16497 + static constexpr uint16_t PROD_ID_ADIS16497 = 0x4071; + + uint16_t product_id = read_reg16(PROD_ID); + + if (product_id == PROD_ID_ADIS16497) { + + if (self_test_sensor()) { + // TODO check model here and set measurement ranges + return PX4_OK; + + } else { + PX4_ERR("probe attempt %d: self test failed, resetting", i); + } + + } else { + PX4_ERR("probe attempt %d: read product id failed, resetting", i); + } + } + + return -EIO; +} + +bool +ADIS16497::self_test_sensor() +{ + // Switch to configuration page + write_reg16(PAGE_ID, 0x03); + + // Self test (globa l command bit 1) + uint8_t value[2] = {}; + value[0] = (1 << 1); + write_reg16(GLOB_CMD, (uint16_t)value[0]); + + up_mdelay(20); // Self test time + + // Switch to output page + write_reg16(PAGE_ID, 0x0); + + // Read SYS_E_FLAG to check overall result + uint16_t sys_e_flag = read_reg16(SYS_E_FLAG); + + if (sys_e_flag != 0) { + PX4_ERR("SYS_E_FLAG: %#X", sys_e_flag); + + // Read DIAG_STS to check per-sensor results + uint16_t diag_sts_flag = read_reg16(DIAG_STS); + + if (diag_sts_flag != 0) { + PX4_ERR("DIAG_STS: %#X", diag_sts_flag); + } + + return false; + } + + return true; +} + +int +ADIS16497::ioctl(struct file *filp, int cmd, unsigned long arg) +{ + switch (cmd) { + case SENSORIOCRESET: + return reset(); + + case ACCELIOCSSCALE: { + /* copy scale, but only if off by a few percent */ + struct accel_calibration_s *s = (struct accel_calibration_s *) arg; + memcpy(&_accel_scale, s, sizeof(_accel_scale)); + return OK; + } + + default: + /* give it to the superclass */ + return SPI::ioctl(filp, cmd, arg); + } +} + +int +ADIS16497::gyro_ioctl(struct file *filp, int cmd, unsigned long arg) +{ + switch (cmd) { + + /* these are shared with the accel side */ + case SENSORIOCRESET: + return ioctl(filp, cmd, arg); + + case GYROIOCSSCALE: + /* copy scale in */ + memcpy(&_gyro_scale, (struct gyro_calibration_s *) arg, sizeof(_gyro_scale)); + return OK; + + default: + /* give it to the superclass */ + return SPI::ioctl(filp, cmd, arg); + } +} + +uint16_t +ADIS16497::read_reg16(uint8_t reg) +{ + uint16_t cmd[1]; + + cmd[0] = ((reg | DIR_READ) << 8) & 0xff00; + transferhword(cmd, nullptr, 1); + up_udelay(T_STALL); + transferhword(nullptr, cmd, 1); + up_udelay(T_STALL); + + return cmd[0]; +} + +void +ADIS16497::write_reg(uint8_t reg, uint8_t val) +{ + uint8_t cmd[2]; + cmd[0] = reg | 0x8; + cmd[1] = val; + transfer(cmd, cmd, sizeof(cmd)); +} + +void +ADIS16497::write_reg16(uint8_t reg, uint16_t value) +{ + uint16_t cmd[2]; + + cmd[0] = ((reg | DIR_WRITE) << 8) | (0x00ff & value); + cmd[1] = (((reg + 0x1) | DIR_WRITE) << 8) | ((0xff00 & value) >> 8); + + transferhword(cmd, nullptr, 1); + up_udelay(T_STALL); + transferhword(cmd + 1, nullptr, 1); + up_udelay(T_STALL); +} + +void +ADIS16497::start() +{ +#ifdef GPIO_SPI1_DRDY1_ADIS16497 + // Setup data ready on rising edge + px4_arch_gpiosetevent(GPIO_SPI1_DRDY1_ADIS16497, true, false, true, &ADIS16497::data_ready_interrupt, this); +#else + // Make sure we are stopped first + stop(); + + // Start polling at the specified rate + hrt_call_every(&_call, 1000, _call_interval, (hrt_callout)&ADIS16497::measure_trampoline, this); +#endif +} + +void +ADIS16497::stop() +{ +#ifdef GPIO_SPI1_DRDY1_ADIS16497 + // Disable data ready callback + px4_arch_gpiosetevent(GPIO_SPI1_DRDY1_ADIS16497, false, false, false, nullptr, nullptr); +#else + hrt_cancel(&_call); +#endif +} + +int +ADIS16497::data_ready_interrupt(int irq, void *context, void *arg) +{ + ADIS16497 *dev = reinterpret_cast<ADIS16497 *>(arg); + + /* make another measurement */ + dev->measure(); + + return PX4_OK; +} + +void +ADIS16497::measure_trampoline(void *arg) +{ + ADIS16497 *dev = reinterpret_cast<ADIS16497 *>(arg); + + /* make another measurement */ + dev->measure(); +} + +int +ADIS16497::measure() +{ + perf_begin(_sample_perf); + perf_count(_sample_interval_perf); + + // Fetch the full set of measurements from the ADIS16497 in one pass (burst read). + ADISReport adis_report {}; + adis_report.cmd = ((BURST_CMD | DIR_READ) << 8) & 0xff00; + + // ADIS16497 burst report should be 320 bits + static_assert(sizeof(adis_report) == (320 / 8), "ADIS16497 report not 320 bits"); + + const hrt_abstime t = hrt_absolute_time(); + + if (OK != transferhword((uint16_t *)&adis_report, ((uint16_t *)&adis_report), sizeof(adis_report) / sizeof(uint16_t))) { + perf_count(_bad_transfers); + perf_end(_sample_perf); + return -EIO; + } + + // Check burst ID to make sure the correct SPI speed is being used. + // The sensor uses a different burst report format at slower speeds + static constexpr uint16_t BURST_ID_DEFAULT = 0xA5A5; + + if (adis_report.BURST_ID != BURST_ID_DEFAULT) { + PX4_ERR("BURST_ID: %#X", adis_report.BURST_ID); + + perf_count(_bad_transfers); + perf_end(_sample_perf); + return -EIO; + } + + // Check all Status/Error Flag Indicators + if (adis_report.SYS_E_FLAG != 0) { + PX4_ERR("SYS_E_FLAG: %#X", adis_report.SYS_E_FLAG); + + perf_count(_bad_transfers); + perf_end(_sample_perf); + return -EIO; + } + + uint32_t checksum = uint32_t(adis_report.CRC_UPR) << 16 | adis_report.CRC_LWR; + uint32_t checksum_calc = crc32((uint16_t *)&adis_report.SYS_E_FLAG, 15); + + if (checksum != checksum_calc) { + PX4_ERR("CHECKSUM: %#X vs. calculated: %#X", checksum, checksum_calc); + perf_count(_bad_transfers); + perf_end(_sample_perf); + return -EIO; + } + + // TODO check data counter here to see if we're missing samples/getting repeated samples + + publish_accel(t, adis_report); + publish_gyro(t, adis_report); + + perf_end(_sample_perf); + return OK; +} + +void +ADIS16497::publish_accel(const hrt_abstime &t, const ADISReport &report) +{ + float xraw_f = (int32_t(report.X_ACCEL_OUT) << 16 | report.X_ACCEL_LOW) / 65536.0f * _accel_range_scale; + float yraw_f = (int32_t(report.Y_ACCEL_OUT) << 16 | report.Y_ACCEL_LOW) / 65536.0f * _accel_range_scale; + float zraw_f = (int32_t(report.Z_ACCEL_OUT) << 16 | report.Z_ACCEL_LOW) / 65536.0f * _accel_range_scale; + + // Apply user specified rotation + rotate_3f(_rotation, xraw_f, yraw_f, zraw_f); + + const float x_in_new = (xraw_f - _accel_scale.x_offset) * _accel_scale.x_scale; + const float y_in_new = (yraw_f - _accel_scale.y_offset) * _accel_scale.y_scale; + const float z_in_new = (zraw_f - _accel_scale.z_offset) * _accel_scale.z_scale; + + matrix::Vector3f aval(x_in_new, y_in_new, z_in_new); + + const matrix::Vector3f val_filt = _accel_filter.apply(aval); + + sensor_accel_s arb{}; + matrix::Vector3f aval_integrated; + + if (_accel_int.put(t, aval, aval_integrated, arb.integral_dt)) { + arb.timestamp = t; + + arb.device_id = _device_id.devid; + arb.error_count = perf_event_count(_bad_transfers); + + // Raw sensor readings + arb.x_raw = report.X_ACCEL_OUT; + arb.y_raw = report.Y_ACCEL_OUT; + arb.z_raw = report.Z_ACCEL_OUT; + arb.scaling = _accel_range_scale; + + // Filtered values for controls + arb.x = val_filt(0); + arb.y = val_filt(1); + arb.z = val_filt(2); + + // Intgrated values for estimation + arb.x_integral = aval_integrated(0); + arb.y_integral = aval_integrated(1); + arb.z_integral = aval_integrated(2); + + arb.temperature = report.TEMP_OUT * 0.1f - 25.0f; // 1 LSB = 0.1°C, 0x0000 at 25°C + + orb_publish(ORB_ID(sensor_accel), _accel_topic, &arb); + } +} + +void +ADIS16497::publish_gyro(const hrt_abstime &t, const ADISReport &report) +{ + float xraw_f = (int32_t(report.X_GYRO_OUT) << 16 | report.X_GYRO_LOW) / 65536.0f; + float yraw_f = (int32_t(report.Y_GYRO_OUT) << 16 | report.Y_GYRO_LOW) / 65536.0f; + float zraw_f = (int32_t(report.Z_GYRO_OUT) << 16 | report.Z_GYRO_LOW) / 65536.0f; + + // Apply user specified rotation + rotate_3f(_rotation, xraw_f, yraw_f, zraw_f); + + const float x_gyro_in_new = (math::radians(xraw_f * _gyro_range_scale) - _gyro_scale.x_offset) * _gyro_scale.x_scale; + const float y_gyro_in_new = (math::radians(yraw_f * _gyro_range_scale) - _gyro_scale.y_offset) * _gyro_scale.y_scale; + const float z_gyro_in_new = (math::radians(zraw_f * _gyro_range_scale) - _gyro_scale.z_offset) * _gyro_scale.z_scale; + + matrix::Vector3f gval(x_gyro_in_new, y_gyro_in_new, z_gyro_in_new); + + const matrix::Vector3f gval_filt = _gyro_filter.apply(gval); + + sensor_gyro_s grb{}; + matrix::Vector3f gval_integrated; + + if (_gyro_int.put(t, gval, gval_integrated, grb.integral_dt)) { + grb.timestamp = t; + + grb.device_id = _gyro->_device_id.devid; + grb.error_count = perf_event_count(_bad_transfers); + + // Raw sensor readings + grb.x_raw = report.X_GYRO_OUT; + grb.y_raw = report.Y_GYRO_OUT; + grb.z_raw = report.Z_GYRO_OUT; + grb.scaling = math::radians(_gyro_range_scale); + + // Filtered values for controls + grb.x = gval_filt(0); + grb.y = gval_filt(1); + grb.z = gval_filt(2); + + // Unfiltered integrated values for estimation + grb.x_integral = gval_integrated(0); + grb.y_integral = gval_integrated(1); + grb.z_integral = gval_integrated(2); + + grb.temperature = report.TEMP_OUT * 0.1f - 25.0f; // 1 LSB = 0.1°C, 0x0000 at 25°C + + orb_publish(ORB_ID(sensor_gyro), _gyro->_gyro_topic, &grb); + } +} + +void +ADIS16497::print_info() +{ + perf_print_counter(_sample_perf); + perf_print_counter(_sample_interval_perf); + perf_print_counter(_bad_transfers); +} diff --git a/src/drivers/imu/adis16497/ADIS16497.hpp b/src/drivers/imu/adis16497/ADIS16497.hpp new file mode 100644 index 0000000000000000000000000000000000000000..54c0d8302a6339b3be020083d71d4fe4defa1e8f --- /dev/null +++ b/src/drivers/imu/adis16497/ADIS16497.hpp @@ -0,0 +1,254 @@ +/**************************************************************************** + * + * Copyright (c) 2018 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. + * + ****************************************************************************/ + +/* + * ADIS16497.hpp + * + */ + +#ifndef DRIVERS_IMU_ADIS16497_ADIS16497_HPP_ +#define DRIVERS_IMU_ADIS16497_ADIS16497_HPP_ + +#include <drivers/device/ringbuffer.h> +#include <drivers/device/spi.h> +#include <drivers/drv_hrt.h> +#include <drivers/drv_accel.h> +#include <drivers/drv_gyro.h> +#include <mathlib/math/filter/LowPassFilter2pVector3f.hpp> +#include <drivers/device/integrator.h> +#include <lib/conversion/rotation.h> +#include <perf/perf_counter.h> +#include <ecl/geo/geo.h> + +#define ADIS16497_GYRO_DEFAULT_RATE 1000 +#define ADIS16497_GYRO_DEFAULT_DRIVER_FILTER_FREQ 80 + +#define ADIS16497_ACCEL_DEFAULT_RATE 1000 +#define ADIS16497_ACCEL_DEFAULT_DRIVER_FILTER_FREQ 30 + +// TODO : This is a copy of the NuttX CRC32 table +static const uint32_t crc32_tab[] = { + 0x00000000, 0x77073096, 0xee0e612c, 0x990951ba, 0x076dc419, 0x706af48f, 0xe963a535, 0x9e6495a3, + 0x0edb8832, 0x79dcb8a4, 0xe0d5e91e, 0x97d2d988, 0x09b64c2b, 0x7eb17cbd, 0xe7b82d07, 0x90bf1d91, + 0x1db71064, 0x6ab020f2, 0xf3b97148, 0x84be41de, 0x1adad47d, 0x6ddde4eb, 0xf4d4b551, 0x83d385c7, + 0x136c9856, 0x646ba8c0, 0xfd62f97a, 0x8a65c9ec, 0x14015c4f, 0x63066cd9, 0xfa0f3d63, 0x8d080df5, + 0x3b6e20c8, 0x4c69105e, 0xd56041e4, 0xa2677172, 0x3c03e4d1, 0x4b04d447, 0xd20d85fd, 0xa50ab56b, + 0x35b5a8fa, 0x42b2986c, 0xdbbbc9d6, 0xacbcf940, 0x32d86ce3, 0x45df5c75, 0xdcd60dcf, 0xabd13d59, + 0x26d930ac, 0x51de003a, 0xc8d75180, 0xbfd06116, 0x21b4f4b5, 0x56b3c423, 0xcfba9599, 0xb8bda50f, + 0x2802b89e, 0x5f058808, 0xc60cd9b2, 0xb10be924, 0x2f6f7c87, 0x58684c11, 0xc1611dab, 0xb6662d3d, + 0x76dc4190, 0x01db7106, 0x98d220bc, 0xefd5102a, 0x71b18589, 0x06b6b51f, 0x9fbfe4a5, 0xe8b8d433, + 0x7807c9a2, 0x0f00f934, 0x9609a88e, 0xe10e9818, 0x7f6a0dbb, 0x086d3d2d, 0x91646c97, 0xe6635c01, + 0x6b6b51f4, 0x1c6c6162, 0x856530d8, 0xf262004e, 0x6c0695ed, 0x1b01a57b, 0x8208f4c1, 0xf50fc457, + 0x65b0d9c6, 0x12b7e950, 0x8bbeb8ea, 0xfcb9887c, 0x62dd1ddf, 0x15da2d49, 0x8cd37cf3, 0xfbd44c65, + 0x4db26158, 0x3ab551ce, 0xa3bc0074, 0xd4bb30e2, 0x4adfa541, 0x3dd895d7, 0xa4d1c46d, 0xd3d6f4fb, + 0x4369e96a, 0x346ed9fc, 0xad678846, 0xda60b8d0, 0x44042d73, 0x33031de5, 0xaa0a4c5f, 0xdd0d7cc9, + 0x5005713c, 0x270241aa, 0xbe0b1010, 0xc90c2086, 0x5768b525, 0x206f85b3, 0xb966d409, 0xce61e49f, + 0x5edef90e, 0x29d9c998, 0xb0d09822, 0xc7d7a8b4, 0x59b33d17, 0x2eb40d81, 0xb7bd5c3b, 0xc0ba6cad, + 0xedb88320, 0x9abfb3b6, 0x03b6e20c, 0x74b1d29a, 0xead54739, 0x9dd277af, 0x04db2615, 0x73dc1683, + 0xe3630b12, 0x94643b84, 0x0d6d6a3e, 0x7a6a5aa8, 0xe40ecf0b, 0x9309ff9d, 0x0a00ae27, 0x7d079eb1, + 0xf00f9344, 0x8708a3d2, 0x1e01f268, 0x6906c2fe, 0xf762575d, 0x806567cb, 0x196c3671, 0x6e6b06e7, + 0xfed41b76, 0x89d32be0, 0x10da7a5a, 0x67dd4acc, 0xf9b9df6f, 0x8ebeeff9, 0x17b7be43, 0x60b08ed5, + 0xd6d6a3e8, 0xa1d1937e, 0x38d8c2c4, 0x4fdff252, 0xd1bb67f1, 0xa6bc5767, 0x3fb506dd, 0x48b2364b, + 0xd80d2bda, 0xaf0a1b4c, 0x36034af6, 0x41047a60, 0xdf60efc3, 0xa867df55, 0x316e8eef, 0x4669be79, + 0xcb61b38c, 0xbc66831a, 0x256fd2a0, 0x5268e236, 0xcc0c7795, 0xbb0b4703, 0x220216b9, 0x5505262f, + 0xc5ba3bbe, 0xb2bd0b28, 0x2bb45a92, 0x5cb36a04, 0xc2d7ffa7, 0xb5d0cf31, 0x2cd99e8b, 0x5bdeae1d, + 0x9b64c2b0, 0xec63f226, 0x756aa39c, 0x026d930a, 0x9c0906a9, 0xeb0e363f, 0x72076785, 0x05005713, + 0x95bf4a82, 0xe2b87a14, 0x7bb12bae, 0x0cb61b38, 0x92d28e9b, 0xe5d5be0d, 0x7cdcefb7, 0x0bdbdf21, + 0x86d3d2d4, 0xf1d4e242, 0x68ddb3f8, 0x1fda836e, 0x81be16cd, 0xf6b9265b, 0x6fb077e1, 0x18b74777, + 0x88085ae6, 0xff0f6a70, 0x66063bca, 0x11010b5c, 0x8f659eff, 0xf862ae69, 0x616bffd3, 0x166ccf45, + 0xa00ae278, 0xd70dd2ee, 0x4e048354, 0x3903b3c2, 0xa7672661, 0xd06016f7, 0x4969474d, 0x3e6e77db, + 0xaed16a4a, 0xd9d65adc, 0x40df0b66, 0x37d83bf0, 0xa9bcae53, 0xdebb9ec5, 0x47b2cf7f, 0x30b5ffe9, + 0xbdbdf21c, 0xcabac28a, 0x53b39330, 0x24b4a3a6, 0xbad03605, 0xcdd70693, 0x54de5729, 0x23d967bf, + 0xb3667a2e, 0xc4614ab8, 0x5d681b02, 0x2a6f2b94, 0xb40bbe37, 0xc30c8ea1, 0x5a05df1b, 0x2d02ef8d +}; + +class ADIS16497_gyro; + +class ADIS16497 : public device::SPI +{ +public: + ADIS16497(int bus, const char *path_accel, const char *path_gyro, uint32_t device, enum Rotation rotation); + virtual ~ADIS16497(); + + virtual int init(); + + virtual int ioctl(struct file *filp, int cmd, unsigned long arg); + + void print_info(); + +protected: + virtual int probe(); + + friend class ADIS16497_gyro; + + virtual int gyro_ioctl(struct file *filp, int cmd, unsigned long arg); + +private: + ADIS16497_gyro *_gyro{nullptr}; + + struct hrt_call _call {}; + unsigned _call_interval{1000}; + + struct gyro_calibration_s _gyro_scale {}; + + // gyro 0.025 °/sec/LSB + float _gyro_range_scale{0.025f}; + float _gyro_range_rad_s{math::radians(500.0f)}; + + struct accel_calibration_s _accel_scale {}; + + // accel 1.25 mg/LSB + float _accel_range_scale{1.25f * CONSTANTS_ONE_G / 1000.0f}; + float _accel_range_m_s2{40.0f * CONSTANTS_ONE_G}; + + orb_advert_t _accel_topic{nullptr}; + + int _accel_orb_class_instance{-1}; + int _accel_class_instance{-1}; + + unsigned _sample_rate{1000}; + + perf_counter_t _sample_perf; + perf_counter_t _sample_interval_perf; + + perf_counter_t _bad_transfers; + + math::LowPassFilter2pVector3f _gyro_filter{ADIS16497_GYRO_DEFAULT_RATE, ADIS16497_GYRO_DEFAULT_DRIVER_FILTER_FREQ}; + math::LowPassFilter2pVector3f _accel_filter{ADIS16497_ACCEL_DEFAULT_RATE, ADIS16497_ACCEL_DEFAULT_DRIVER_FILTER_FREQ}; + + Integrator _accel_int{4000, false}; + Integrator _gyro_int{4000, true}; + + enum Rotation _rotation; + +#pragma pack(push, 1) + /** + * Report conversation with the ADIS16497, including command byte. + */ + struct ADISReport { + uint16_t cmd; + uint16_t ZEROES; + uint16_t BURST_ID; + uint16_t SYS_E_FLAG; + uint16_t TEMP_OUT; + uint16_t X_GYRO_LOW; + uint16_t X_GYRO_OUT; + uint16_t Y_GYRO_LOW; + uint16_t Y_GYRO_OUT; + uint16_t Z_GYRO_LOW; + uint16_t Z_GYRO_OUT; + uint16_t X_ACCEL_LOW; + uint16_t X_ACCEL_OUT; + uint16_t Y_ACCEL_LOW; + uint16_t Y_ACCEL_OUT; + uint16_t Z_ACCEL_LOW; + uint16_t Z_ACCEL_OUT; + uint16_t DATA_CNT; + uint16_t CRC_LWR; + uint16_t CRC_UPR; + }; +#pragma pack(pop) + + /** + * Start automatic measurement. + */ + void start(); + + /** + * Stop automatic measurement. + */ + void stop(); + + /** + * Reset chip. + * + * Resets the chip and measurements ranges, but not scale and offset. + */ + int reset(); + + /** + * Static trampoline from the hrt_call context; because we don't have a + * generic hrt wrapper yet. + * + * Called by the HRT in interrupt context at the specified rate if + * automatic polling is enabled. + * + * @param arg Instance pointer for the driver that is polling. + */ + static void measure_trampoline(void *arg); + + static int data_ready_interrupt(int irq, void *context, void *arg); + + /** + * Fetch measurements from the sensor and update the report buffers. + */ + int measure(); + + void publish_accel(const hrt_abstime &t, const ADISReport &report); + void publish_gyro(const hrt_abstime &t, const ADISReport &report); + + uint16_t read_reg16(uint8_t reg); + + void write_reg(uint8_t reg, uint8_t value); + void write_reg16(uint8_t reg, uint16_t value); + + // ADIS16497 onboard self test + bool self_test_sensor(); + + ADIS16497(const ADIS16497 &); + ADIS16497 operator=(const ADIS16497 &); + + uint32_t crc32(const uint16_t *data, size_t len) + { + uint32_t crc = 0xffffffff; + uint8_t tbl_idx; + uint8_t b; + + while (len--) { + b = *data; + tbl_idx = crc ^ b; + crc = (crc32_tab[tbl_idx] ^ (crc >> 8)); + + b = *data >> 8; + tbl_idx = crc ^ b; + crc = (crc32_tab[tbl_idx] ^ (crc >> 8)); + + data++; + } + + return crc ^ 0xffffffff; + } + +}; + +#endif /* DRIVERS_IMU_ADIS16497_ADIS16497_HPP_ */ diff --git a/src/drivers/imu/adis16497/ADIS16497_gyro.cpp b/src/drivers/imu/adis16497/ADIS16497_gyro.cpp new file mode 100644 index 0000000000000000000000000000000000000000..49e17d8d7d17823e23e767d1efb964902e021a50 --- /dev/null +++ b/src/drivers/imu/adis16497/ADIS16497_gyro.cpp @@ -0,0 +1,79 @@ +/**************************************************************************** + * + * Copyright (c) 2018 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. + * + ****************************************************************************/ + +#include "ADIS16497_gyro.hpp" + +ADIS16497_gyro::ADIS16497_gyro(ADIS16497 *parent, const char *path) : + CDev("ADIS16497_gyro", path), + _parent(parent), + _gyro_topic(nullptr), + _gyro_orb_class_instance(-1), + _gyro_class_instance(-1) +{ +} + +ADIS16497_gyro::~ADIS16497_gyro() +{ + if (_gyro_class_instance != -1) { + unregister_class_devname(GYRO_BASE_DEVICE_PATH, _gyro_class_instance); + } +} + +int +ADIS16497_gyro::init() +{ + int ret = CDev::init(); + + /* if probe/setup failed, bail now */ + if (ret != OK) { + DEVICE_DEBUG("gyro init failed"); + return ret; + } + + _gyro_class_instance = register_class_devname(GYRO_BASE_DEVICE_PATH); + + return ret; +} + +int +ADIS16497_gyro::ioctl(struct file *filp, int cmd, unsigned long arg) +{ + switch (cmd) { + case DEVIOCGDEVICEID: + return (int)CDev::ioctl(filp, cmd, arg); + break; + + default: + return _parent->gyro_ioctl(filp, cmd, arg); + } +} diff --git a/src/drivers/imu/adis16497/ADIS16497_gyro.hpp b/src/drivers/imu/adis16497/ADIS16497_gyro.hpp new file mode 100644 index 0000000000000000000000000000000000000000..bea3890b12b7b979e1ee52c1d8f9d8597a63d855 --- /dev/null +++ b/src/drivers/imu/adis16497/ADIS16497_gyro.hpp @@ -0,0 +1,71 @@ +/**************************************************************************** + * + * Copyright (c) 2018 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. + * + ****************************************************************************/ + +#ifndef DRIVERS_IMU_ADIS16497_ADIS16497_GYRO_HPP_ +#define DRIVERS_IMU_ADIS16497_ADIS16497_GYRO_HPP_ + +#include "ADIS16497.hpp" + +#include <drivers/device/CDev.hpp> +#include <drivers/drv_gyro.h> + +/** + * Helper class implementing the gyro driver node. + */ +class ADIS16497_gyro : public device::CDev +{ +public: + ADIS16497_gyro(ADIS16497 *parent, const char *path); + virtual ~ADIS16497_gyro(); + + virtual int ioctl(struct file *filp, int cmd, unsigned long arg); + + virtual int init(); + +protected: + friend class ADIS16497; + +private: + ADIS16497 *_parent{nullptr}; + orb_advert_t _gyro_topic{nullptr}; + + int _gyro_orb_class_instance{-1}; + int _gyro_class_instance{-1}; + + /* do not allow to copy this class due to pointer data members */ + ADIS16497_gyro(const ADIS16497_gyro &); + ADIS16497_gyro operator=(const ADIS16497_gyro &); + +}; + +#endif /* DRIVERS_IMU_ADIS16497_ADIS16497_GYRO_HPP_ */ diff --git a/src/drivers/imu/adis16497/ADIS16497_main.cpp b/src/drivers/imu/adis16497/ADIS16497_main.cpp new file mode 100644 index 0000000000000000000000000000000000000000..d14884413a40cb3e02fc019ccdb0f611adfcb1cc --- /dev/null +++ b/src/drivers/imu/adis16497/ADIS16497_main.cpp @@ -0,0 +1,249 @@ +/**************************************************************************** + * + * Copyright (c) 2018 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. + * + ****************************************************************************/ + +#include "ADIS16497.hpp" +#include <systemlib/err.h> + +#define ADIS16497_DEVICE_PATH_ACCEL "/dev/ADIS16497_accel" +#define ADIS16497_DEVICE_PATH_GYRO "/dev/ADIS16497_gyro" + +extern "C" { __EXPORT int adis16497_main(int argc, char *argv[]); } + +/** + * Local functions in support of the shell command. + */ +namespace adis16497 +{ + +ADIS16497 *g_dev; + +void start(enum Rotation rotation); +void test(); +void reset(); +void info(); +void usage(); +/** + * Start the driver. + */ +void +start(enum Rotation rotation) +{ + if (g_dev != nullptr) + /* if already started, the still command succeeded */ + { + errx(0, "already started"); + } + + /* create the driver */ +#if defined(PX4_SPIDEV_EXTERNAL1_1) + g_dev = new ADIS16497(PX4_SPI_BUS_EXTERNAL1, ADIS16497_DEVICE_PATH_ACCEL, ADIS16497_DEVICE_PATH_GYRO, + PX4_SPIDEV_EXTERNAL1_1, rotation); +#else + PX4_ERR("External SPI not available"); + exit(0); +#endif + + if (g_dev == nullptr) { + goto fail; + } + + if (OK != g_dev->init()) { + goto fail; + } + + exit(0); +fail: + + if (g_dev != nullptr) { + delete g_dev; + g_dev = nullptr; + } + + errx(1, "driver start failed"); +} + +/** + * Perform some basic functional tests on the driver; + * make sure we can collect data from the sensor in polled + * and automatic modes. + */ +void +test() +{ + sensor_accel_s a_report{}; + sensor_gyro_s g_report{}; + + ssize_t sz; + + /* get the driver */ + int fd = px4_open(ADIS16497_DEVICE_PATH_ACCEL, O_RDONLY); + + if (fd < 0) { + err(1, "%s open failed", ADIS16497_DEVICE_PATH_ACCEL); + } + + /* get the gyro driver */ + int fd_gyro = px4_open(ADIS16497_DEVICE_PATH_GYRO, O_RDONLY); + + if (fd_gyro < 0) { + err(1, "%s open failed", ADIS16497_DEVICE_PATH_GYRO); + } + + /* do a simple demand read */ + sz = read(fd, &a_report, sizeof(a_report)); + + if (sz != sizeof(a_report)) { + PX4_ERR("ret: %d, expected: %d", sz, sizeof(a_report)); + err(1, "immediate acc read failed"); + } + + print_message(a_report); + + /* do a simple demand read */ + sz = px4_read(fd_gyro, &g_report, sizeof(g_report)); + + if (sz != sizeof(g_report)) { + warnx("ret: %d, expected: %d", sz, sizeof(g_report)); + err(1, "immediate gyro read failed"); + } + + print_message(g_report); + + px4_close(fd_gyro); + px4_close(fd); + + reset(); + errx(0, "PASS"); +} + +/** + * Reset the driver. + */ +void +reset() +{ + int fd = px4_open(ADIS16497_DEVICE_PATH_ACCEL, O_RDONLY); + + if (fd < 0) { + err(1, "open failed"); + } + + if (px4_ioctl(fd, SENSORIOCRESET, 0) < 0) { + err(1, "driver reset failed"); + } + + px4_close(fd); + + exit(0); +} + +/** + * Print a little info about the driver. + */ +void +info() +{ + if (g_dev == nullptr) { + errx(1, "driver not running"); + } + + printf("state @ %p\n", g_dev); + g_dev->print_info(); + + exit(0); +} + +void +usage() +{ + PX4_INFO("missing command: try 'start', 'test', 'info', 'reset'"); + PX4_INFO("options:"); + PX4_INFO(" -R rotation"); +} + +} +// namespace + +int +adis16497_main(int argc, char *argv[]) +{ + enum Rotation rotation = ROTATION_NONE; + int ch; + + /* start options */ + while ((ch = getopt(argc, argv, "R:")) != EOF) { + switch (ch) { + case 'R': + rotation = (enum Rotation)atoi(optarg); + break; + + default: + adis16497::usage(); + exit(0); + } + } + + const char *verb = argv[optind]; + + /* + * Start/load the driver. + + */ + if (!strcmp(verb, "start")) { + adis16497::start(rotation); + } + + /* + * Test the driver/device. + */ + if (!strcmp(verb, "test")) { + adis16497::test(); + } + + /* + * Reset the driver. + */ + if (!strcmp(verb, "reset")) { + adis16497::reset(); + } + + /* + * Print driver information. + */ + if (!strcmp(verb, "info")) { + adis16497::info(); + } + + adis16497::usage(); + exit(1); +} diff --git a/src/drivers/imu/adis16497/CMakeLists.txt b/src/drivers/imu/adis16497/CMakeLists.txt new file mode 100644 index 0000000000000000000000000000000000000000..3ea48d9d1a3a0094524c6092cfba2f4aa3652e74 --- /dev/null +++ b/src/drivers/imu/adis16497/CMakeLists.txt @@ -0,0 +1,42 @@ +############################################################################ +# +# Copyright (c) 2018 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__imu__adis16497 + MAIN adis16497 + STACK_MAIN 1200 + COMPILE_FLAGS + SRCS + ADIS16497.cpp + ADIS16497_gyro.cpp + ADIS16497_main.cpp + )