Skip to content
Snippets Groups Projects
Commit 7b0078a2 authored by Daniel Agar's avatar Daniel Agar Committed by Lorenz Meier
Browse files

bosch bmi160 driver (#4469)

parent 755176b2
No related branches found
No related tags found
No related merge requests found
......@@ -48,6 +48,7 @@ set(config_module_list
drivers/bst
drivers/snapdragon_rc_pwm
drivers/lis3mdl
drivers/bmi160
#
# System commands
......
############################################################################
#
# 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__bmi160
MAIN bmi160
STACK_MAIN 1200
COMPILE_FLAGS
-Weffc++
-Os
SRCS
bmi160.cpp
bmi160_gyro.cpp
bmi160_main.cpp
DEPENDS
platforms__common
)
# vim: set noet ft=cmake fenc=utf-8 ff=unix :
This diff is collapsed.
#ifndef BMI160_HPP_
#define BMI160_HPP_
#include <px4_config.h>
#include <sys/types.h>
#include <stdint.h>
#include <stdbool.h>
#include <stddef.h>
#include <stdlib.h>
#include <semaphore.h>
#include <string.h>
#include <fcntl.h>
#include <poll.h>
#include <errno.h>
#include <stdio.h>
#include <math.h>
#include <unistd.h>
#include <getopt.h>
#include <systemlib/perf_counter.h>
#include <systemlib/err.h>
#include <systemlib/conversions.h>
#include <nuttx/arch.h>
#include <nuttx/clock.h>
#include <board_config.h>
#include <drivers/drv_hrt.h>
#include <drivers/device/spi.h>
#include <drivers/device/ringbuffer.h>
#include <drivers/device/integrator.h>
#include <drivers/drv_accel.h>
#include <drivers/drv_gyro.h>
#include <drivers/drv_mag.h>
#include <mathlib/math/filter/LowPassFilter2p.hpp>
#include <lib/conversion/rotation.h>
#define DIR_READ 0x80
#define DIR_WRITE 0x00
#define BMI160_DEVICE_PATH_ACCEL "/dev/bmi160_accel"
#define BMI160_DEVICE_PATH_GYRO "/dev/bmi160_gyro"
#define BMI160_DEVICE_PATH_MAG "/dev/bmi160_mag"
#define BMI160_DEVICE_PATH_ACCEL_EXT "/dev/bmi160_accel_ext"
#define BMI160_DEVICE_PATH_GYRO_EXT "/dev/bmi160_gyro_ext"
#define BMI160_DEVICE_PATH_MAG_EXT "/dev/bmi160_mag_ext"
// BMI 160 registers
#define BMIREG_CHIP_ID 0x00
#define BMIREG_ERR_REG 0x02
#define BMIREG_PMU_STATUS 0x03
#define BMIREG_DATA_0 0x04
#define BMIREG_DATA_1 0x05
#define BMIREG_DATA_2 0x06
#define BMIREG_DATA_3 0x07
#define BMIREG_DATA_4 0x08
#define BMIREG_DATA_5 0x09
#define BMIREG_DATA_6 0x0A
#define BMIREG_DATA_7 0x0B
#define BMIREG_GYR_X_L 0x0C
#define BMIREG_GYR_X_H 0x0D
#define BMIREG_GYR_Y_L 0x0E
#define BMIREG_GYR_Y_H 0x0F
#define BMIREG_GYR_Z_L 0x10
#define BMIREG_GYR_Z_H 0x11
#define BMIREG_ACC_X_L 0x12
#define BMIREG_ACC_X_H 0x13
#define BMIREG_ACC_Y_L 0x14
#define BMIREG_ACC_Y_H 0x15
#define BMIREG_ACC_Z_L 0x16
#define BMIREG_ACC_Z_H 0x17
#define BMIREG_SENSORTIME0 0x18
#define BMIREG_SENSORTIME1 0x19
#define BMIREG_SENSORTIME2 0x1A
#define BMIREG_STATUS 0x1B
#define BMIREG_INT_STATUS_0 0x1C
#define BMIREG_INT_STATUS_1 0x1D
#define BMIREG_INT_STATUS_2 0x1E
#define BMIREG_INT_STATUS_3 0x1F
#define BMIREG_TEMP_0 0x20
#define BMIREG_TEMP_1 0x21
#define BMIREG_FIFO_LEN_0 0x22
#define BMIREG_FIFO_LEN_1 0x23
#define BMIREG_FIFO_DATA 0x24
#define BMIREG_ACC_CONF 0x40
#define BMIREG_ACC_RANGE 0x41
#define BMIREG_GYR_CONF 0x42
#define BMIREG_GYR_RANGE 0x43
#define BMIREG_MAG_CONF 0x44
#define BMIREG_FIFO_DOWNS 0x45
#define BMIREG_FIFO_CONFIG_0 0x46
#define BMIREG_FIFO_CONFIG_1 0x47
#define BMIREG_MAG_IF_0 0x4B
#define BMIREG_MAG_IF_1 0x4C
#define BMIREG_MAG_IF_2 0x4D
#define BMIREG_MAG_IF_3 0x4E
#define BMIREG_MAG_IF_4 0x4F
#define BMIREG_INT_EN_0 0x50
#define BMIREG_INT_EN_1 0x51
#define BMIREG_INT_EN_2 0x52
#define BMIREG_INT_OUT_CTRL 0x53
#define BMIREG_INT_LANTCH 0x54
#define BMIREG_INT_MAP_0 0x55
#define BMIREG_INT_MAP_1 0x56
#define BMIREG_INT_MAP_2 0x57
#define BMIREG_INT_DATA_0 0x58
#define BMIREG_INT_DATA_1 0x59
#define BMIREG_INT_LH_0 0x5A
#define BMIREG_INT_LH_1 0x5B
#define BMIREG_INT_LH_2 0x5C
#define BMIREG_INT_LH_3 0x5D
#define BMIREG_INT_LH_4 0x5E
#define BMIREG_INT_MOT_0 0x5F
#define BMIREG_INT_MOT_1 0x60
#define BMIREG_INT_MOT_2 0x61
#define BMIREG_INT_MOT_3 0x62
#define BMIREG_INT_TAP_0 0x63
#define BMIREG_INT_TAP_1 0x64
#define BMIREG_INT_ORIE_0 0x65
#define BMIREG_INT_ORIE_1 0x66
#define BMIREG_INT_FLAT_0 0x67
#define BMIREG_INT_FLAT_1 0x68
#define BMIREG_FOC_CONF 0x69
#define BMIREG_CONF 0x6A
#define BMIREG_IF_CONF 0x6B
#define BMIREG_PMU_TRIGGER 0x6C
#define BMIREG_SELF_TEST 0x6D
#define BMIREG_NV_CONF 0x70
#define BMIREG_OFFSET_ACC_X 0x71
#define BMIREG_OFFSET_ACC_Y 0x72
#define BMIREG_OFFSET_ACC_Z 0x73
#define BMIREG_OFFSET_GYR_X 0x74
#define BMIREG_OFFSET_GYR_Y 0x75
#define BMIREG_OFFSET_GYR_Z 0x76
#define BMIREG_OFFSET_EN 0x77
#define BMIREG_STEP_CONT_0 0x78
#define BMIREG_STEP_CONT_1 0x79
#define BMIREG_STEP_CONF_0 0x7A
#define BMIREG_STEP_CONF_1 0x7B
#define BMIREG_CMD 0x7E
// Configuration bits BMI 160
#define BMI160_WHO_AM_I 0xD1
//BMIREG_STATUS 0x1B
#define BMI_DRDY_ACCEL (1<<7)
#define BMI_DRDY_GYRO (1<<6)
#define BMI_DRDY_MAG (1<<5)
#define BMI_GYRO_SELF_TEST_OK (1<<1)
//BMIREG_INT_STATUS_1 0x1D
#define BMI_DRDY_INT (1<<4)
//BMIREG_ACC_CONF 0x40
#define BMI_ACCEL_RATE_25_32 (0<<3) | (0<<2) | (0<<1) | (1<<0)
#define BMI_ACCEL_RATE_25_16 (0<<3) | (0<<2) | (1<<1) | (0<<0)
#define BMI_ACCEL_RATE_25_8 (0<<3) | (0<<2) | (1<<1) | (1<<0)
#define BMI_ACCEL_RATE_25_4 (0<<3) | (1<<2) | (0<<1) | (0<<0)
#define BMI_ACCEL_RATE_25_2 (0<<3) | (1<<2) | (0<<1) | (1<<0)
#define BMI_ACCEL_RATE_25 (0<<3) | (1<<2) | (1<<1) | (0<<0)
#define BMI_ACCEL_RATE_50 (0<<3) | (1<<2) | (1<<1) | (1<<0)
#define BMI_ACCEL_RATE_100 (1<<3) | (0<<2) | (0<<1) | (0<<0)
#define BMI_ACCEL_RATE_200 (1<<3) | (0<<2) | (0<<1) | (1<<0)
#define BMI_ACCEL_RATE_400 (1<<3) | (0<<2) | (1<<1) | (0<<0)
#define BMI_ACCEL_RATE_800 (1<<3) | (0<<2) | (1<<1) | (1<<0)
#define BMI_ACCEL_RATE_1600 (1<<3) | (1<<2) | (0<<1) | (0<<0)
#define BMI_ACCEL_US (0<<7)
#define BMI_ACCEL_BWP_NORMAL (0<<6) | (1<<5) | (0<<4)
#define BMI_ACCEL_BWP_OSR2 (0<<6) | (0<<5) | (1<<4)
#define BMI_ACCEL_BWP_OSR4 (0<<6) | (0<<5) | (0<<4)
//BMIREG_ACC_RANGE 0x41
#define BMI_ACCEL_RANGE_2_G (0<<3) | (0<<2) | (1<<1) | (1<<0)
#define BMI_ACCEL_RANGE_4_G (0<<3) | (1<<2) | (0<<1) | (1<<0)
#define BMI_ACCEL_RANGE_8_G (1<<3) | (0<<2) | (0<<1) | (0<<0)
#define BMI_ACCEL_RANGE_16_G (1<<3) | (1<<2) | (0<<1) | (0<<0)
//BMIREG_GYR_CONF 0x42
#define BMI_GYRO_RATE_25 (0<<3) | (1<<2) | (1<<1) | (0<<0)
#define BMI_GYRO_RATE_50 (0<<3) | (1<<2) | (1<<1) | (1<<0)
#define BMI_GYRO_RATE_100 (1<<3) | (0<<2) | (0<<1) | (0<<0)
#define BMI_GYRO_RATE_200 (1<<3) | (0<<2) | (0<<1) | (1<<0)
#define BMI_GYRO_RATE_400 (1<<3) | (0<<2) | (1<<1) | (0<<0)
#define BMI_GYRO_RATE_800 (1<<3) | (0<<2) | (1<<1) | (1<<0)
#define BMI_GYRO_RATE_1600 (1<<3) | (1<<2) | (0<<1) | (0<<0)
#define BMI_GYRO_RATE_3200 (1<<3) | (1<<2) | (0<<1) | (1<<0)
#define BMI_GYRO_BWP_NORMAL (1<<5) | (0<<4)
#define BMI_GYRO_BWP_OSR2 (0<<5) | (1<<4)
#define BMI_GYRO_BWP_OSR4 (0<<5) | (0<<4)
//BMIREG_GYR_RANGE 0x43
#define BMI_GYRO_RANGE_2000_DPS (0<<2) | (0<<1) | (0<<0)
#define BMI_GYRO_RANGE_1000_DPS (0<<2) | (0<<1) | (1<<0)
#define BMI_GYRO_RANGE_500_DPS (0<<2) | (1<<1) | (0<<0)
#define BMI_GYRO_RANGE_250_DPS (0<<2) | (1<<1) | (1<<0)
#define BMI_GYRO_RANGE_125_DPS (1<<2) | (0<<1) | (0<<0)
//BMIREG_INT_EN_1 0x51
#define BMI_DRDY_INT_EN (1<<4)
//BMIREG_INT_OUT_CTRL 0x53
#define BMI_INT1_EN (1<<3) | (0<<2) | (1<<1) //Data Ready on INT1 High
//BMIREG_INT_MAP_1 0x56
#define BMI_DRDY_INT1 (1<<7)
//BMIREG_IF_CONF 0x6B
#define BMI_SPI_3_WIRE (1<<0)
#define BMI_SPI_4_WIRE (0<<0)
#define BMI_AUTO_DIS_SEC (0<<5) | (0<<4)
#define BMI_I2C_OIS_SEC (0<<5) | (1<<4)
#define BMI_AUTO_MAG_SEC (1<<5) | (0<<4)
//BMIREG_NV_CONF 0x70
#define BMI_SPI (1<<0)
//BMIREG_CMD 0x7E
#define BMI_ACCEL_NORMAL_MODE 0x11 //Wait at least 3.8 ms before another CMD
#define BMI_GYRO_NORMAL_MODE 0x15 //Wait at least 80 ms before another CMD
#define BMI160_SOFT_RESET 0xB6
#define BMI160_ACCEL_DEFAULT_RANGE_G 4
#define BMI160_GYRO_DEFAULT_RANGE_DPS 2000
#define BMI160_ACCEL_DEFAULT_RATE 800
#define BMI160_ACCEL_MAX_RATE 1600
#define BMI160_GYRO_DEFAULT_RATE 800
#define BMI160_GYRO_MAX_RATE 3200
#define BMI160_ACCEL_DEFAULT_ONCHIP_FILTER_FREQ 324
#define BMI160_ACCEL_DEFAULT_DRIVER_FILTER_FREQ 50
#define BMI160_GYRO_DEFAULT_ONCHIP_FILTER_FREQ 254.6f
#define BMI160_GYRO_DEFAULT_DRIVER_FILTER_FREQ 50
#define BMI160_ONE_G 9.80665f
#define BMI160_LOW_BUS_SPEED 1000*1000
#define BMI160_HIGH_BUS_SPEED 11*1000*1000
#define BMI160_TIMER_REDUCTION 200
#ifdef PX4_SPI_BUS_EXT
#define EXTERNAL_BUS PX4_SPI_BUS_EXT
#else
#define EXTERNAL_BUS 0
#endif
class BMI160_gyro;
class BMI160 : public device::SPI
{
public:
BMI160(int bus, const char *path_accel, const char *path_gyro, spi_dev_e device, enum Rotation rotation);
virtual ~BMI160();
virtual int init();
virtual ssize_t read(struct file *filp, char *buffer, size_t buflen);
virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
/**
* Diagnostics - print some basic information about the driver.
*/
void print_info();
void print_registers();
// deliberately cause a sensor error
void test_error();
protected:
virtual int probe();
friend class BMI160_gyro;
virtual ssize_t gyro_read(struct file *filp, char *buffer, size_t buflen);
virtual int gyro_ioctl(struct file *filp, int cmd, unsigned long arg);
private:
BMI160_gyro *_gyro;
uint8_t _whoami; /** whoami result */
struct hrt_call _call;
unsigned _call_interval;
ringbuffer::RingBuffer *_accel_reports;
struct accel_calibration_s _accel_scale;
float _accel_range_scale;
float _accel_range_m_s2;
orb_advert_t _accel_topic;
int _accel_orb_class_instance;
int _accel_class_instance;
ringbuffer::RingBuffer *_gyro_reports;
struct gyro_calibration_s _gyro_scale;
float _gyro_range_scale;
float _gyro_range_rad_s;
unsigned _dlpf_freq;
float _accel_sample_rate;
float _gyro_sample_rate;
perf_counter_t _accel_reads;
perf_counter_t _gyro_reads;
perf_counter_t _sample_perf;
perf_counter_t _bad_transfers;
perf_counter_t _bad_registers;
perf_counter_t _good_transfers;
perf_counter_t _reset_retries;
perf_counter_t _duplicates;
perf_counter_t _controller_latency_perf;
uint8_t _register_wait;
uint64_t _reset_wait;
math::LowPassFilter2p _accel_filter_x;
math::LowPassFilter2p _accel_filter_y;
math::LowPassFilter2p _accel_filter_z;
math::LowPassFilter2p _gyro_filter_x;
math::LowPassFilter2p _gyro_filter_y;
math::LowPassFilter2p _gyro_filter_z;
Integrator _accel_int;
Integrator _gyro_int;
enum Rotation _rotation;
// this is used to support runtime checking of key
// configuration registers to detect SPI bus errors and sensor
// reset
#define BMI160_NUM_CHECKED_REGISTERS 10
static const uint8_t _checked_registers[BMI160_NUM_CHECKED_REGISTERS];
uint8_t _checked_values[BMI160_NUM_CHECKED_REGISTERS];
uint8_t _checked_bad[BMI160_NUM_CHECKED_REGISTERS];
uint8_t _checked_next;
// last temperature reading for print_info()
float _last_temperature;
// keep last accel reading for duplicate detection
uint16_t _last_accel[3];
bool _got_duplicate;
/**
* 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);
/**
* Fetch measurements from the sensor and update the report buffers.
*/
void measure();
/**
* Read a register from the BMI160
*
* @param The register to read.
* @return The value that was read.
*/
uint8_t read_reg(unsigned reg, uint32_t speed = BMI160_LOW_BUS_SPEED);
uint16_t read_reg16(unsigned reg);
/**
* Write a register in the BMI160
*
* @param reg The register to write.
* @param value The new value to write.
*/
void write_reg(unsigned reg, uint8_t value);
/**
* Modify a register in the BMI160
*
* Bits are cleared before bits are set.
*
* @param reg The register to modify.
* @param clearbits Bits in the register to clear.
* @param setbits Bits in the register to set.
*/
void modify_reg(unsigned reg, uint8_t clearbits, uint8_t setbits);
/**
* Write a register in the BMI160, updating _checked_values
*
* @param reg The register to write.
* @param value The new value to write.
*/
void write_checked_reg(unsigned reg, uint8_t value);
/**
* Set the BMI160 measurement range.
*
* @param max_g The maximum G value the range must support.
* @param max_dps The maximum DPS value the range must support.
* @return OK if the value can be supported, -ERANGE otherwise.
*/
int set_accel_range(unsigned max_g);
int set_gyro_range(unsigned max_dps);
/**
* Swap a 16-bit value read from the BMI160 to native byte order.
*/
uint16_t swap16(uint16_t val) { return (val >> 8) | (val << 8); }
/**
* Get the internal / external state
*
* @return true if the sensor is not on the main MCU board
*/
bool is_external() { return (_bus == EXTERNAL_BUS); }
/**
* Measurement self test
*
* @return 0 on success, 1 on failure
*/
int self_test();
/**
* Accel self test
*
* @return 0 on success, 1 on failure
*/
int accel_self_test();
/**
* Gyro self test
*
* @return 0 on success, 1 on failure
*/
int gyro_self_test();
/*
set low pass filter frequency
*/
void _set_dlpf_filter(uint16_t frequency_hz);
/*
set sample rate (approximate) - 10 - 952 Hz
*/
int accel_set_sample_rate(float desired_sample_rate_hz);
int gyro_set_sample_rate(float desired_sample_rate_hz);
/*
check that key registers still have the right value
*/
void check_registers(void);
/* do not allow to copy this class due to pointer data members */
BMI160(const BMI160 &);
BMI160 operator=(const BMI160 &);
#pragma pack(push, 1)
/**
* Report conversation within the BMI160, including command byte and
* interrupt status.
*/
struct BMIReport {
uint8_t cmd;
int16_t gyro_x;
int16_t gyro_y;
int16_t gyro_z;
int16_t accel_x;
int16_t accel_y;
int16_t accel_z;
};
#pragma pack(pop)
};
#endif /* BMI160_HPP_ */
#include "bmi160_gyro.hpp"
#include "bmi160.hpp"
BMI160_gyro::BMI160_gyro(BMI160 *parent, const char *path) : CDev("BMI160_gyro", path),
_parent(parent),
_gyro_topic(nullptr),
_gyro_orb_class_instance(-1),
_gyro_class_instance(-1)
{
}
BMI160_gyro::~BMI160_gyro()
{
if (_gyro_class_instance != -1) {
unregister_class_devname(GYRO_BASE_DEVICE_PATH, _gyro_class_instance);
}
}
int
BMI160_gyro::init()
{
int ret;
// do base class init
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;
}
void
BMI160_gyro::parent_poll_notify()
{
poll_notify(POLLIN);
}
ssize_t
BMI160_gyro::read(struct file *filp, char *buffer, size_t buflen)
{
return _parent->gyro_read(filp, buffer, buflen);
}
int
BMI160_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);
}
}
#ifndef BMI160_GYRO_HPP_
#define BMI160_GYRO_HPP_
#include <px4_config.h>
#include "bmi160.hpp"
/**
* Helper class implementing the gyro driver node.
*/
class BMI160_gyro : public device::CDev
{
public:
BMI160_gyro(BMI160 *parent, const char *path);
~BMI160_gyro();
virtual ssize_t read(struct file *filp, char *buffer, size_t buflen);
virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
virtual int init();
protected:
friend class BMI160;
void parent_poll_notify();
private:
BMI160 *_parent;
orb_advert_t _gyro_topic;
int _gyro_orb_class_instance;
int _gyro_class_instance;
/* do not allow to copy this class due to pointer data members */
BMI160_gyro(const BMI160_gyro &);
BMI160_gyro operator=(const BMI160_gyro &);
};
#endif /* BMI160_GYRO_HPP_ */
#include "bmi160.hpp"
#include <board_config.h>
/** driver 'main' command */
extern "C" { __EXPORT int bmi160_main(int argc, char *argv[]); }
/**
* Local functions in support of the shell command.
*/
namespace bmi160
{
BMI160 *g_dev_int; // on internal bus
BMI160 *g_dev_ext; // on external bus
void start(bool, enum Rotation);
void stop(bool);
void test(bool);
void reset(bool);
void info(bool);
void regdump(bool);
void testerror(bool);
void usage();
/**
* Start the driver.
*
* This function only returns if the driver is up and running
* or failed to detect the sensor.
*/
void
start(bool external_bus, enum Rotation rotation)
{
int fd;
BMI160 **g_dev_ptr = external_bus ? &g_dev_ext : &g_dev_int;
const char *path_accel = external_bus ? BMI160_DEVICE_PATH_ACCEL_EXT : BMI160_DEVICE_PATH_ACCEL;
const char *path_gyro = external_bus ? BMI160_DEVICE_PATH_GYRO_EXT : BMI160_DEVICE_PATH_GYRO;
if (*g_dev_ptr != nullptr)
/* if already started, the still command succeeded */
{
errx(0, "already started");
}
/* create the driver */
if (external_bus) {
#if defined(PX4_SPI_BUS_EXT) && defined(PX4_SPIDEV_EXT_BMI)
*g_dev_ptr = new BMI160(PX4_SPI_BUS_EXT, path_accel, path_gyro, (spi_dev_e)PX4_SPIDEV_EXT_BMI, rotation);
#else
errx(0, "External SPI not available");
#endif
} else {
*g_dev_ptr = new BMI160(PX4_SPI_BUS_SENSORS, path_accel, path_gyro, (spi_dev_e)PX4_SPIDEV_BMI, rotation);
}
if (*g_dev_ptr == nullptr) {
goto fail;
}
if (OK != (*g_dev_ptr)->init()) {
goto fail;
}
/* set the poll rate to default, starts automatic data collection */
fd = open(path_accel, O_RDONLY);
if (fd < 0) {
goto fail;
}
if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) {
goto fail;
}
close(fd);
exit(0);
fail:
if (*g_dev_ptr != nullptr) {
delete(*g_dev_ptr);
*g_dev_ptr = nullptr;
}
errx(1, "driver start failed");
}
void
stop(bool external_bus)
{
BMI160 **g_dev_ptr = external_bus ? &g_dev_ext : &g_dev_int;
if (*g_dev_ptr != nullptr) {
delete *g_dev_ptr;
*g_dev_ptr = nullptr;
} else {
/* warn, but not an error */
warnx("already stopped.");
}
exit(0);
}
/**
* Perform some basic functional tests on the driver;
* make sure we can collect data from the sensor in polled
* and automatic modes.
*/
void
test(bool external_bus)
{
const char *path_accel = external_bus ? BMI160_DEVICE_PATH_ACCEL_EXT : BMI160_DEVICE_PATH_ACCEL;
const char *path_gyro = external_bus ? BMI160_DEVICE_PATH_GYRO_EXT : BMI160_DEVICE_PATH_GYRO;
accel_report a_report;
gyro_report g_report;
ssize_t sz;
/* get the driver */
int fd = open(path_accel, O_RDONLY);
if (fd < 0)
err(1, "%s open failed (try 'bmi160 start')",
path_accel);
/* get the driver */
int fd_gyro = open(path_gyro, O_RDONLY);
if (fd_gyro < 0) {
err(1, "%s open failed", path_gyro);
}
/* reset to manual polling */
if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_MANUAL) < 0) {
err(1, "reset to manual polling");
}
/* do a simple demand read */
sz = read(fd, &a_report, sizeof(a_report));
if (sz != sizeof(a_report)) {
warnx("ret: %d, expected: %d", sz, sizeof(a_report));
err(1, "immediate acc read failed");
}
warnx("single read");
warnx("time: %lld", a_report.timestamp);
warnx("acc x: \t%8.4f\tm/s^2", (double)a_report.x);
warnx("acc y: \t%8.4f\tm/s^2", (double)a_report.y);
warnx("acc z: \t%8.4f\tm/s^2", (double)a_report.z);
warnx("acc x: \t%d\traw 0x%0x", (short)a_report.x_raw, (unsigned short)a_report.x_raw);
warnx("acc y: \t%d\traw 0x%0x", (short)a_report.y_raw, (unsigned short)a_report.y_raw);
warnx("acc z: \t%d\traw 0x%0x", (short)a_report.z_raw, (unsigned short)a_report.z_raw);
warnx("acc range: %8.4f m/s^2 (%8.4f g)", (double)a_report.range_m_s2,
(double)(a_report.range_m_s2 / BMI160_ONE_G));
/* do a simple demand read */
sz = 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");
}
warnx("gyro x: \t% 9.5f\trad/s", (double)g_report.x);
warnx("gyro y: \t% 9.5f\trad/s", (double)g_report.y);
warnx("gyro z: \t% 9.5f\trad/s", (double)g_report.z);
warnx("gyro x: \t%d\traw", (int)g_report.x_raw);
warnx("gyro y: \t%d\traw", (int)g_report.y_raw);
warnx("gyro z: \t%d\traw", (int)g_report.z_raw);
warnx("gyro range: %8.4f rad/s (%d deg/s)", (double)g_report.range_rad_s,
(int)((g_report.range_rad_s / M_PI_F) * 180.0f + 0.5f));
warnx("temp: \t%8.4f\tdeg celsius", (double)a_report.temperature);
warnx("temp: \t%d\traw 0x%0x", (short)a_report.temperature_raw, (unsigned short)a_report.temperature_raw);
/* reset to default polling */
if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) {
err(1, "reset to default polling");
}
close(fd);
close(fd_gyro);
/* XXX add poll-rate tests here too */
reset(external_bus);
errx(0, "PASS");
}
/**
* Reset the driver.
*/
void
reset(bool external_bus)
{
const char *path_accel = external_bus ? BMI160_DEVICE_PATH_ACCEL_EXT : BMI160_DEVICE_PATH_ACCEL;
int fd = open(path_accel, O_RDONLY);
if (fd < 0) {
err(1, "failed ");
}
if (ioctl(fd, SENSORIOCRESET, 0) < 0) {
err(1, "driver reset failed");
}
if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) {
err(1, "driver poll restart failed");
}
close(fd);
exit(0);
}
/**
* Print a little info about the driver.
*/
void
info(bool external_bus)
{
BMI160 **g_dev_ptr = external_bus ? &g_dev_ext : &g_dev_int;
if (*g_dev_ptr == nullptr) {
errx(1, "driver not running");
}
printf("state @ %p\n", *g_dev_ptr);
(*g_dev_ptr)->print_info();
exit(0);
}
/**
* Dump the register information
*/
void
regdump(bool external_bus)
{
BMI160 **g_dev_ptr = external_bus ? &g_dev_ext : &g_dev_int;
if (*g_dev_ptr == nullptr) {
errx(1, "driver not running");
}
printf("regdump @ %p\n", *g_dev_ptr);
(*g_dev_ptr)->print_registers();
exit(0);
}
/**
* deliberately produce an error to test recovery
*/
void
testerror(bool external_bus)
{
BMI160 **g_dev_ptr = external_bus ? &g_dev_ext : &g_dev_int;
if (*g_dev_ptr == nullptr) {
errx(1, "driver not running");
}
(*g_dev_ptr)->test_error();
exit(0);
}
void
usage()
{
warnx("missing command: try 'start', 'info', 'test', 'stop',\n'reset', 'regdump', 'testerror'");
warnx("options:");
warnx(" -X (external bus)");
warnx(" -R rotation");
}
} // namespace
int
bmi160_main(int argc, char *argv[])
{
bool external_bus = false;
int ch;
enum Rotation rotation = ROTATION_NONE;
/* jump over start/off/etc and look at options first */
while ((ch = getopt(argc, argv, "XR:")) != EOF) {
switch (ch) {
case 'X':
external_bus = true;
break;
case 'R':
rotation = (enum Rotation)atoi(optarg);
break;
default:
bmi160::usage();
exit(0);
}
}
const char *verb = argv[optind];
/*
* Start/load the driver.
*/
if (!strcmp(verb, "start")) {
bmi160::start(external_bus, rotation);
}
if (!strcmp(verb, "stop")) {
bmi160::stop(external_bus);
}
/*
* Test the driver/device.
*/
if (!strcmp(verb, "test")) {
bmi160::test(external_bus);
}
/*
* Reset the driver.
*/
if (!strcmp(verb, "reset")) {
bmi160::reset(external_bus);
}
/*
* Print driver information.
*/
if (!strcmp(verb, "info")) {
bmi160::info(external_bus);
}
/*
* Print register information.
*/
if (!strcmp(verb, "regdump")) {
bmi160::regdump(external_bus);
}
if (!strcmp(verb, "testerror")) {
bmi160::testerror(external_bus);
}
bmi160::usage();
exit(1);
}
......@@ -125,6 +125,7 @@ __BEGIN_DECLS
#define PX4_SPIDEV_MPU 4
#define PX4_SPIDEV_HMC 5
#define PX4_SPIDEV_LIS 7
#define PX4_SPIDEV_BMI 8
/* External bus */
#define PX4_SPIDEV_EXT0 1
......@@ -138,6 +139,8 @@ __BEGIN_DECLS
#define PX4_SPIDEV_EXT_ACCEL_MAG PX4_SPIDEV_EXT2
#define PX4_SPIDEV_EXT_GYRO PX4_SPIDEV_EXT3
#define PX4_SPIDEV_EXT_BMI PX4_SPIDEV_EXT_GYRO
/* I2C busses */
#define PX4_I2C_BUS_EXPANSION 1
#define PX4_I2C_BUS_ONBOARD 2
......
......@@ -63,10 +63,12 @@
#define DRV_ACC_DEVTYPE_ACCELSIM 0x14
#define DRV_ACC_DEVTYPE_GYROSIM 0x15
#define DRV_ACC_DEVTYPE_MPU9250 0x16
#define DRV_ACC_DEVTYPE_BMI160 0x17
#define DRV_GYR_DEVTYPE_MPU6000 0x21
#define DRV_GYR_DEVTYPE_L3GD20 0x22
#define DRV_GYR_DEVTYPE_GYROSIM 0x23
#define DRV_GYR_DEVTYPE_MPU9250 0x24
#define DRV_GYR_DEVTYPE_BMI160 0x25
#define DRV_RNG_DEVTYPE_MB12XX 0x31
#define DRV_RNG_DEVTYPE_LL40LS 0x32
......@@ -78,6 +80,7 @@
#define DRV_GYR_DEVTYPE_MPU6500 0x21
#endif
/*
* ioctl() definitions
*
......
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