refactor bmi055: use driver base class

This commit is contained in:
Beat Küng 2020-02-26 14:56:06 +01:00 committed by Daniel Agar
parent 969a77f889
commit 22a38453ab
8 changed files with 130 additions and 397 deletions

View File

@ -24,10 +24,10 @@ mpu6000 -R 8 -s -T 20602 start
mpu6000 -R 8 -s -T 20689 start
# Internal SPI bus BMI055 accel
bmi055 -A -R 10 start
bmi055 -A -R 10 -s start
# Internal SPI bus BMI055 gyro
bmi055 -G -R 10 start
bmi055 -G -R 10 -s start
# Possible external compasses
ist8310 -X start

View File

@ -18,10 +18,10 @@ mpu6000 -R 8 -s -T 20689 start
#icm20689 start
# Internal SPI bus BMI055 accel
bmi055 -A -R 10 start
bmi055 -A -R 10 -s start
# Internal SPI bus BMI055 gyro
bmi055 -G -R 10 start
bmi055 -G -R 10 -s start
# Possible external compasses
ist8310 -X start

View File

@ -37,6 +37,7 @@
#include <ecl/geo/geo.h>
#include <lib/perf/perf_counter.h>
#include <px4_platform_common/getopt.h>
#include <px4_platform_common/i2c_spi_buses.h>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#define DIR_READ 0x80
@ -49,12 +50,28 @@
#define BMI055_TIMER_REDUCTION 200
class BMI055 : public device::SPI
class BMI055 : public device::SPI, public I2CSPIDriver<BMI055>
{
public:
BMI055(const char *name, const char *devname, I2CSPIBusOption bus_option, int bus, int type, uint32_t device,
enum spi_mode_e mode, uint32_t frequency, enum Rotation rotation);
virtual ~BMI055() = default;
static I2CSPIDriverBase *instantiate(const BusCLIArguments &cli, const BusInstanceIterator &iterator,
int runtime_instance);
static void print_usage();
virtual void start() = 0;
virtual void RunImpl() = 0;
protected:
uint8_t _whoami; /** whoami result */
virtual void print_registers() = 0;
virtual void test_error() = 0;
void custom_method(const BusCLIArguments &cli) override;
uint8_t _whoami; ///< whoami result
uint8_t _register_wait;
uint64_t _reset_wait;
@ -80,16 +97,4 @@ protected:
*/
void write_reg(unsigned reg, uint8_t value);
/* do not allow to copy this class due to pointer data members */
BMI055(const BMI055 &);
BMI055 operator=(const BMI055 &);
public:
BMI055(const char *name, const char *devname, int bus, uint32_t device, enum spi_mode_e mode, uint32_t frequency,
enum Rotation rotation);
virtual ~BMI055() = default;
};

View File

@ -44,9 +44,10 @@ const uint8_t BMI055_accel::_checked_registers[BMI055_ACCEL_NUM_CHECKED_REGISTER
BMI055_ACC_INT_MAP_1,
};
BMI055_accel::BMI055_accel(int bus, const char *path_accel, uint32_t device, enum Rotation rotation) :
BMI055("BMI055_ACCEL", path_accel, bus, device, SPIDEV_MODE3, BMI055_BUS_SPEED, rotation),
ScheduledWorkItem(MODULE_NAME, px4::device_bus_to_wq(get_device_id())),
BMI055_accel::BMI055_accel(I2CSPIBusOption bus_option, int bus, const char *path_accel, uint32_t device,
enum Rotation rotation, int bus_frequency, spi_mode_e spi_mode) :
BMI055("bmi055_accel", path_accel, bus_option, bus, DRV_ACC_DEVTYPE_BMI055, device, spi_mode, bus_frequency,
rotation),
_px4_accel(get_device_id(), (external() ? ORB_PRIO_MAX - 1 : ORB_PRIO_HIGH - 1), rotation),
_sample_perf(perf_alloc(PC_ELAPSED, "bmi055_accel_read")),
_bad_transfers(perf_alloc(PC_COUNT, "bmi055_accel_bad_transfers")),
@ -59,10 +60,6 @@ BMI055_accel::BMI055_accel(int bus, const char *path_accel, uint32_t device, enu
BMI055_accel::~BMI055_accel()
{
/* make sure we are truly inactive */
stop();
/* delete the perf counter */
perf_free(_sample_perf);
perf_free(_bad_transfers);
perf_free(_bad_registers);
@ -218,26 +215,10 @@ BMI055_accel::set_accel_range(unsigned max_g)
void
BMI055_accel::start()
{
/* make sure we are stopped first */
stop();
/* start polling at the specified rate */
ScheduleOnInterval(BMI055_ACCEL_DEFAULT_RATE - BMI055_TIMER_REDUCTION, 1000);
}
void
BMI055_accel::stop()
{
ScheduleClear();
}
void
BMI055_accel::Run()
{
/* make another measurement */
measure();
}
void
BMI055_accel::check_registers(void)
{
@ -282,7 +263,7 @@ BMI055_accel::check_registers(void)
}
void
BMI055_accel::measure()
BMI055_accel::RunImpl()
{
if (hrt_absolute_time() < _reset_wait) {
// we're waiting for a reset to complete
@ -402,8 +383,10 @@ BMI055_accel::measure()
}
void
BMI055_accel::print_info()
BMI055_accel::print_status()
{
I2CSPIDriverBase::print_status();
PX4_INFO("Type: Accel");
perf_print_counter(_sample_perf);
perf_print_counter(_bad_transfers);
perf_print_counter(_bad_registers);

View File

@ -139,31 +139,29 @@
/* Mask definitions for ACCD_X_LSB, ACCD_Y_LSB and ACCD_Z_LSB Register */
#define BMI055_NEW_DATA_MASK 0x01
class BMI055_accel : public BMI055, public px4::ScheduledWorkItem
class BMI055_accel : public BMI055
{
public:
BMI055_accel(int bus, const char *path_accel, uint32_t device, enum Rotation rotation);
BMI055_accel(I2CSPIBusOption bus_option, int bus, const char *path_accel, uint32_t device, enum Rotation rotation,
int bus_frequency, spi_mode_e spi_mode);
virtual ~BMI055_accel();
virtual int init();
int init() override;
// Start automatic measurement.
void start();
/// Start automatic measurement.
void start() override;
/**
* Diagnostics - print some basic information about the driver.
*/
void print_info();
void print_status() override;
void print_registers();
void print_registers() override;
// deliberately cause a sensor error
void test_error();
/// deliberately cause a sensor error
void test_error() override;
void RunImpl() override;
protected:
virtual int probe();
int probe() override;
private:
PX4Accelerometer _px4_accel;
@ -183,11 +181,6 @@ private:
bool _got_duplicate;
/**
* Stop automatic measurement.
*/
void stop();
/**
* Reset chip.
*
@ -195,13 +188,6 @@ private:
*/
int reset();
void Run() override;
/**
* Fetch measurements from the sensor and update the report buffers.
*/
void measure();
/**
* Modify a register in the BMI055_accel
*

View File

@ -47,9 +47,10 @@ const uint8_t BMI055_gyro::_checked_registers[BMI055_GYRO_NUM_CHECKED_REGISTERS]
BMI055_GYR_INT_MAP_1
};
BMI055_gyro::BMI055_gyro(int bus, const char *path_gyro, uint32_t device, enum Rotation rotation) :
BMI055("BMI055_GYRO", path_gyro, bus, device, SPIDEV_MODE3, BMI055_BUS_SPEED, rotation),
ScheduledWorkItem(MODULE_NAME, px4::device_bus_to_wq(get_device_id())),
BMI055_gyro::BMI055_gyro(I2CSPIBusOption bus_option, int bus, const char *path_gyro, uint32_t device,
enum Rotation rotation, int bus_frequency, spi_mode_e spi_mode) :
BMI055("bmi055_gyro", path_gyro, bus_option, bus, DRV_GYR_DEVTYPE_BMI055, device, spi_mode, bus_frequency,
rotation),
_px4_gyro(get_device_id(), (external() ? ORB_PRIO_MAX - 1 : ORB_PRIO_HIGH - 1), rotation),
_sample_perf(perf_alloc(PC_ELAPSED, "bmi055_gyro_read")),
_bad_transfers(perf_alloc(PC_COUNT, "bmi055_gyro_bad_transfers")),
@ -60,10 +61,6 @@ BMI055_gyro::BMI055_gyro(int bus, const char *path_gyro, uint32_t device, enum R
BMI055_gyro::~BMI055_gyro()
{
/* make sure we are truly inactive */
stop();
/* delete the perf counter */
perf_free(_sample_perf);
perf_free(_bad_transfers);
perf_free(_bad_registers);
@ -254,26 +251,10 @@ BMI055_gyro::set_gyro_range(unsigned max_dps)
void
BMI055_gyro::start()
{
/* make sure we are stopped first */
stop();
/* start polling at the specified rate */
ScheduleOnInterval(BMI055_GYRO_DEFAULT_RATE - BMI055_TIMER_REDUCTION, 1000);
}
void
BMI055_gyro::stop()
{
ScheduleClear();
}
void
BMI055_gyro::Run()
{
/* make another measurement */
measure();
}
void
BMI055_gyro::check_registers(void)
{
@ -318,7 +299,7 @@ BMI055_gyro::check_registers(void)
}
void
BMI055_gyro::measure()
BMI055_gyro::RunImpl()
{
if (hrt_absolute_time() < _reset_wait) {
// we're waiting for a reset to complete
@ -412,9 +393,10 @@ BMI055_gyro::measure()
}
void
BMI055_gyro::print_info()
BMI055_gyro::print_status()
{
PX4_INFO("Gyro");
I2CSPIDriverBase::print_status();
PX4_INFO("Type: Gyro");
perf_print_counter(_sample_perf);
perf_print_counter(_bad_transfers);

View File

@ -131,30 +131,29 @@
#define BMI055_ACC_TEMP 0x08
class BMI055_gyro : public BMI055, public px4::ScheduledWorkItem
class BMI055_gyro : public BMI055
{
public:
BMI055_gyro(int bus, const char *path_gyro, uint32_t device, enum Rotation rotation);
BMI055_gyro(I2CSPIBusOption bus_option, int bus, const char *path_accel, uint32_t device, enum Rotation rotation,
int bus_frequency, spi_mode_e spi_mode);
virtual ~BMI055_gyro();
virtual int init();
int init() override;
// Start automatic measurement.
void start();
/// Start automatic measurement.
void start() override;
/**
* Diagnostics - print some basic information about the driver.
*/
void print_info();
void print_status() override;
void print_registers();
void print_registers() override;
// deliberately cause a sensor error
void test_error();
/// deliberately cause a sensor error
void test_error() override;
void RunImpl() override;
protected:
virtual int probe();
int probe() override;
private:
@ -172,11 +171,6 @@ private:
uint8_t _checked_values[BMI055_GYRO_NUM_CHECKED_REGISTERS];
uint8_t _checked_bad[BMI055_GYRO_NUM_CHECKED_REGISTERS];
/**
* Stop automatic measurement.
*/
void stop();
/**
* Reset chip.
*
@ -184,13 +178,6 @@ private:
*/
int reset();
void Run() override;
/**
* Fetch measurements from the sensor and update the report buffers.
*/
void measure();
/**
* Modify a register in the BMI055_gyro
*

View File

@ -33,267 +33,75 @@
#include "BMI055_accel.hpp"
#include "BMI055_gyro.hpp"
#include <px4_platform_common/i2c_spi_buses.h>
#include <px4_platform_common/module.h>
/** driver 'main' command */
extern "C" { __EXPORT int bmi055_main(int argc, char *argv[]); }
enum sensor_type {
BMI055_NONE = 0,
BMI055_ACCEL = 1,
BMI055_GYRO
};
namespace bmi055
{
BMI055_accel *g_acc_dev_int; // on internal bus (accel)
BMI055_accel *g_acc_dev_ext; // on external bus (accel)
BMI055_gyro *g_gyr_dev_int; // on internal bus (gyro)
BMI055_gyro *g_gyr_dev_ext; // on external bus (gyro)
void start(bool, enum Rotation, enum sensor_type);
void stop(bool, enum sensor_type);
void info(bool, enum sensor_type);
void regdump(bool, enum sensor_type);
void testerror(bool, enum sensor_type);
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, enum sensor_type sensor)
BMI055::print_usage()
{
BMI055_accel **g_dev_acc_ptr = external_bus ? &g_acc_dev_ext : &g_acc_dev_int;
const char *path_accel = external_bus ? BMI055_DEVICE_PATH_ACCEL_EXT : BMI055_DEVICE_PATH_ACCEL;
PRINT_MODULE_USAGE_NAME("bmi055", "driver");
PRINT_MODULE_USAGE_SUBCATEGORY("imu");
PRINT_MODULE_USAGE_COMMAND("start");
PRINT_MODULE_USAGE_PARAM_FLAG('A', "Accel", true);
PRINT_MODULE_USAGE_PARAM_FLAG('G', "Gyro", true);
PRINT_MODULE_USAGE_PARAMS_I2C_SPI_DRIVER(false, true);
PRINT_MODULE_USAGE_PARAM_INT('R', 0, 0, 35, "Rotation", true);
BMI055_gyro **g_dev_gyr_ptr = external_bus ? &g_gyr_dev_ext : &g_gyr_dev_int;
const char *path_gyro = external_bus ? BMI055_DEVICE_PATH_GYRO_EXT : BMI055_DEVICE_PATH_GYRO;
PRINT_MODULE_USAGE_COMMAND("regdump");
PRINT_MODULE_USAGE_COMMAND("testerror");
if (sensor == BMI055_ACCEL) {
if (*g_dev_acc_ptr != nullptr)
/* if already started, the still command succeeded */
{
errx(0, "bmi055 accel sensor already started");
}
PRINT_MODULE_USAGE_DEFAULT_COMMANDS();
}
/* create the driver */
if (external_bus) {
#if defined(PX4_SPI_BUS_EXT) && defined(PX4_SPIDEV_EXT_BMI)
*g_dev_acc_ptr = new BMI055_accel(PX4_SPI_BUS_EXT, path_accel, PX4_SPIDEV_EXT_BMI, rotation);
#else
errx(0, "External SPI not available");
#endif
I2CSPIDriverBase *BMI055::instantiate(const BusCLIArguments &cli, const BusInstanceIterator &iterator,
int runtime_instance)
{
BMI055 *instance = nullptr;
} else {
*g_dev_acc_ptr = new BMI055_accel(PX4_SPI_BUS_SENSORS, path_accel, PX4_SPIDEV_BMI055_ACC, rotation);
}
if (cli.type == DRV_ACC_DEVTYPE_BMI055) {
instance = new BMI055_accel(iterator.configuredBusOption(), iterator.bus(), BMI055_DEVICE_PATH_ACCEL, iterator.devid(),
cli.rotation, cli.bus_frequency, cli.spi_mode);
if (*g_dev_acc_ptr == nullptr) {
goto fail_accel;
}
if (OK != (*g_dev_acc_ptr)->init()) {
goto fail_accel;
}
// start automatic data collection
(*g_dev_acc_ptr)->start();
} else if (cli.type == DRV_GYR_DEVTYPE_BMI055) {
instance = new BMI055_gyro(iterator.configuredBusOption(), iterator.bus(), BMI055_DEVICE_PATH_GYRO, iterator.devid(),
cli.rotation, cli.bus_frequency, cli.spi_mode);
}
if (sensor == BMI055_GYRO) {
if (*g_dev_gyr_ptr != nullptr) {
errx(0, "bmi055 gyro sensor already started");
}
/* create the driver */
if (external_bus) {
#if defined(PX4_SPI_BUS_EXT) && defined(PX4_SPIDEV_EXT_BMI)
*g_dev_ptr = new BMI055_gyro(PX4_SPI_BUS_EXT, path_gyro, PX4_SPIDEV_EXT_BMI, rotation);
#else
errx(0, "External SPI not available");
#endif
} else {
*g_dev_gyr_ptr = new BMI055_gyro(PX4_SPI_BUS_SENSORS, path_gyro, PX4_SPIDEV_BMI055_GYR, rotation);
}
if (*g_dev_gyr_ptr == nullptr) {
goto fail_gyro;
}
if (OK != (*g_dev_gyr_ptr)->init()) {
goto fail_gyro;
}
// start automatic data collection
(*g_dev_gyr_ptr)->start();
if (instance == nullptr) {
return nullptr;
}
exit(PX4_OK);
fail_accel:
if (*g_dev_acc_ptr != nullptr) {
delete (*g_dev_acc_ptr);
*g_dev_acc_ptr = nullptr;
if (OK != instance->init()) {
PX4_DEBUG("no device on bus %i (devid 0x%x)", iterator.bus(), iterator.devid());
delete instance;
return nullptr;
}
PX4_WARN("No BMI055 accel found");
exit(PX4_ERROR);
instance->start();
fail_gyro:
if (*g_dev_gyr_ptr != nullptr) {
delete (*g_dev_gyr_ptr);
*g_dev_gyr_ptr = nullptr;
}
PX4_WARN("No BMI055 gyro found");
exit(PX4_ERROR);
return instance;
}
void
stop(bool external_bus, enum sensor_type sensor)
BMI055::custom_method(const BusCLIArguments &cli)
{
BMI055_accel **g_dev_acc_ptr = external_bus ? &g_acc_dev_ext : &g_acc_dev_int;
BMI055_gyro **g_dev_gyr_ptr = external_bus ? &g_gyr_dev_ext : &g_gyr_dev_int;
switch (cli.custom1) {
case 0: print_registers();
break;
if (sensor == BMI055_ACCEL) {
if (*g_dev_acc_ptr != nullptr) {
delete *g_dev_acc_ptr;
*g_dev_acc_ptr = nullptr;
} else {
/* warn, but not an error */
warnx("bmi055 accel sensor already stopped.");
}
case 1: test_error();
break;
}
if (sensor == BMI055_GYRO) {
if (*g_dev_gyr_ptr != nullptr) {
delete *g_dev_gyr_ptr;
*g_dev_gyr_ptr = nullptr;
} else {
/* warn, but not an error */
warnx("bmi055 gyro sensor already stopped.");
}
}
exit(0);
}
/**
* Print a little info about the driver.
*/
void
info(bool external_bus, enum sensor_type sensor)
{
BMI055_accel **g_dev_acc_ptr = external_bus ? &g_acc_dev_ext : &g_acc_dev_int;
BMI055_gyro **g_dev_gyr_ptr = external_bus ? &g_gyr_dev_ext : &g_gyr_dev_int;
if (sensor == BMI055_ACCEL) {
if (*g_dev_acc_ptr == nullptr) {
errx(1, "bmi055 accel driver not running");
}
printf("state @ %p\n", *g_dev_acc_ptr);
(*g_dev_acc_ptr)->print_info();
}
if (sensor == BMI055_GYRO) {
if (*g_dev_gyr_ptr == nullptr) {
errx(1, "bmi055 gyro driver not running");
}
printf("state @ %p\n", *g_dev_gyr_ptr);
(*g_dev_gyr_ptr)->print_info();
}
exit(0);
}
/**
* Dump the register information
*/
void
regdump(bool external_bus, enum sensor_type sensor)
{
BMI055_accel **g_dev_acc_ptr = external_bus ? &g_acc_dev_ext : &g_acc_dev_int;
BMI055_gyro **g_dev_gyr_ptr = external_bus ? &g_gyr_dev_ext : &g_gyr_dev_int;
if (sensor == BMI055_ACCEL) {
if (*g_dev_acc_ptr == nullptr) {
errx(1, "bmi055 accel driver not running");
}
printf("regdump @ %p\n", *g_dev_acc_ptr);
(*g_dev_acc_ptr)->print_registers();
}
if (sensor == BMI055_GYRO) {
if (*g_dev_gyr_ptr == nullptr) {
errx(1, "bmi055 gyro driver not running");
}
printf("regdump @ %p\n", *g_dev_gyr_ptr);
(*g_dev_gyr_ptr)->print_registers();
}
exit(0);
}
/**
* deliberately produce an error to test recovery
*/
void
testerror(bool external_bus, enum sensor_type sensor)
{
BMI055_accel **g_dev_acc_ptr = external_bus ? &g_acc_dev_ext : &g_acc_dev_int;
BMI055_gyro **g_dev_gyr_ptr = external_bus ? &g_gyr_dev_ext : &g_gyr_dev_int;
if (sensor == BMI055_ACCEL) {
if (*g_dev_acc_ptr == nullptr) {
errx(1, "bmi055 accel driver not running");
}
(*g_dev_acc_ptr)->test_error();
}
if (sensor == BMI055_GYRO) {
if (*g_dev_gyr_ptr == nullptr) {
errx(1, "bmi055 gyro driver not running");
}
(*g_dev_gyr_ptr)->test_error();
}
exit(0);
}
void
usage()
{
warnx("missing command: try 'start', 'info', 'stop', 'regdump', 'testerror'");
warnx("options:");
warnx(" -X (external bus)");
warnx(" -R rotation");
warnx(" -A (Enable Accelerometer)");
warnx(" -G (Enable Gyroscope)");
}
}//namespace ends
BMI055::BMI055(const char *name, const char *devname, int bus, uint32_t device, enum spi_mode_e mode,
BMI055::BMI055(const char *name, const char *devname, I2CSPIBusOption bus_option, int bus, int type, uint32_t device,
enum spi_mode_e mode,
uint32_t frequency, enum Rotation rotation):
SPI(name, devname, bus, device, mode, frequency),
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(get_device_id()), bus_option, bus, type),
_whoami(0),
_register_wait(0),
_reset_wait(0),
@ -336,77 +144,59 @@ BMI055::write_reg(unsigned reg, uint8_t value)
int
bmi055_main(int argc, char *argv[])
{
bool external_bus = false;
using ThisDriver = BMI055;
int ch;
enum Rotation rotation = ROTATION_NONE;
enum sensor_type sensor = BMI055_NONE;
int myoptind = 1;
const char *myoptarg = NULL;
BusCLIArguments cli{false, true};
cli.type = 0;
cli.default_spi_frequency = BMI055_BUS_SPEED;
/* jump over start/off/etc and look at options first */
while ((ch = px4_getopt(argc, argv, "XR:AG", &myoptind, &myoptarg)) != EOF) {
while ((ch = cli.getopt(argc, argv, "AGR:")) != EOF) {
switch (ch) {
case 'X':
external_bus = true;
break;
case 'R':
rotation = (enum Rotation)atoi(myoptarg);
break;
case 'A':
sensor = BMI055_ACCEL;
cli.type = DRV_ACC_DEVTYPE_BMI055;
break;
case 'G':
sensor = BMI055_GYRO;
cli.type = DRV_GYR_DEVTYPE_BMI055;
break;
default:
bmi055::usage();
exit(0);
case 'R':
cli.rotation = (enum Rotation)atoi(cli.optarg());
break;
}
}
const char *verb = argv[myoptind];
const char *verb = cli.optarg();
if (sensor == BMI055_NONE) {
bmi055::usage();
exit(0);
if (!verb) {
ThisDriver::print_usage();
return -1;
}
/*
* Start/load the driver.
*/
BusInstanceIterator iterator(MODULE_NAME, cli, cli.type);
if (!strcmp(verb, "start")) {
bmi055::start(external_bus, rotation, sensor);
return ThisDriver::module_start(cli, iterator);
}
/*
* Stop the driver.
*/
if (!strcmp(verb, "stop")) {
bmi055::stop(external_bus, sensor);
return ThisDriver::module_stop(iterator);
}
/*
* Print driver information.
*/
if (!strcmp(verb, "info")) {
bmi055::info(external_bus, sensor);
if (!strcmp(verb, "status")) {
return ThisDriver::module_status(iterator);
}
/*
* Print register information.
*/
if (!strcmp(verb, "regdump")) {
bmi055::regdump(external_bus, sensor);
cli.custom1 = 0;
return ThisDriver::module_custom_method(cli, iterator);
}
if (!strcmp(verb, "testerror")) {
bmi055::testerror(external_bus, sensor);
cli.custom1 = 1;
return ThisDriver::module_custom_method(cli, iterator);
}
bmi055::usage();
exit(1);
ThisDriver::print_usage();
return -1;
}