diff --git a/boards/atlflight/eagle/src/board_config.h b/boards/atlflight/eagle/src/board_config.h index a1e2ae5a91..50869060f0 100644 --- a/boards/atlflight/eagle/src/board_config.h +++ b/boards/atlflight/eagle/src/board_config.h @@ -54,8 +54,6 @@ #define PX4_NUMBER_I2C_BUSES 3 -#define PX4_I2C_OBDEV_BMP280 0x76 - // SPI #define PX4_SPI_BUS_SENSORS 1 #define PX4_SPIDEV_MPU PX4_MK_SPI_SEL(0, DRV_IMU_DEVTYPE_MPU9250) // spi-1 - mpu9250 diff --git a/boards/atlflight/excelsior/src/board_config.h b/boards/atlflight/excelsior/src/board_config.h index d279ed1afa..bebfbe1afd 100644 --- a/boards/atlflight/excelsior/src/board_config.h +++ b/boards/atlflight/excelsior/src/board_config.h @@ -54,8 +54,6 @@ #define PX4_NUMBER_I2C_BUSES 3 -#define PX4_I2C_OBDEV_BMP280 0x76 - // SPI #define PX4_SPI_BUS_SENSORS 1 #define PX4_SPIDEV_MPU PX4_MK_SPI_SEL(0, DRV_IMU_DEVTYPE_MPU9250) diff --git a/boards/beaglebone/blue/src/board_config.h b/boards/beaglebone/blue/src/board_config.h index 216b9e6169..e3361a1f80 100644 --- a/boards/beaglebone/blue/src/board_config.h +++ b/boards/beaglebone/blue/src/board_config.h @@ -56,7 +56,6 @@ #define PX4_NUMBER_I2C_BUSES 2 #define PX4_I2C_OBDEV_MPU9250 0x68 -#define PX4_I2C_OBDEV_BMP280 0x76 // ADC channels: diff --git a/boards/holybro/kakutef7/init/rc.board_sensors b/boards/holybro/kakutef7/init/rc.board_sensors index a719957806..a1328d90db 100644 --- a/boards/holybro/kakutef7/init/rc.board_sensors +++ b/boards/holybro/kakutef7/init/rc.board_sensors @@ -11,8 +11,8 @@ then mpu6000 -R 12 -s -T 20689 start fi -# Internal Baro -bmp280 start +# Onboard Baro +bmp280 -X start # Possible external compasses ist8310 -X start diff --git a/boards/holybro/kakutef7/src/board_config.h b/boards/holybro/kakutef7/src/board_config.h index 744f4bf0d9..2fa2d6a0f7 100644 --- a/boards/holybro/kakutef7/src/board_config.h +++ b/boards/holybro/kakutef7/src/board_config.h @@ -105,8 +105,6 @@ #define BOARD_NUMBER_I2C_BUSES 1 #define BOARD_I2C_BUS_CLOCK_INIT {100000} -#define PX4_I2C_OBDEV_BMP280 0x76 - /* * ADC channels * diff --git a/boards/nxp/fmuk66-v3/src/board_config.h b/boards/nxp/fmuk66-v3/src/board_config.h index 7888359589..5df4fd37be 100644 --- a/boards/nxp/fmuk66-v3/src/board_config.h +++ b/boards/nxp/fmuk66-v3/src/board_config.h @@ -268,8 +268,6 @@ __END_DECLS #define PX4_I2C_BUS_LED PX4_I2C_BUS_EXPANSION -#define PX4_I2C_OBDEV_BMP280 0x76 - /* * ADC channels * diff --git a/boards/uvify/core/src/board_config.h b/boards/uvify/core/src/board_config.h index 202cb02e10..16064993c0 100644 --- a/boards/uvify/core/src/board_config.h +++ b/boards/uvify/core/src/board_config.h @@ -170,12 +170,6 @@ #define PX4_I2C_BUS_EXPANSION 1 #define PX4_I2C_BUS_LED PX4_I2C_BUS_EXPANSION -/** - * Devices on the external bus. - * Note that these are unshifted addresses. - */ -#define PX4_I2C_OBDEV_BMP280 0x76 - /** * ADC channels: * These are the channel numbers of the ADCs of the microcontroller that can be used by the Px4 Firmware in the adc driver. diff --git a/posix-configs/eagle/200qx/px4.config b/posix-configs/eagle/200qx/px4.config index 3578a9d286..8ea74aab74 100644 --- a/posix-configs/eagle/200qx/px4.config +++ b/posix-configs/eagle/200qx/px4.config @@ -19,7 +19,7 @@ param set SENS_BOARD_ROT 0 sleep 1 mpu9250 start -bmp280 start +bmp280 -I start gps start -d /dev/tty-4 rc_update start sensors start diff --git a/posix-configs/eagle/210qc/px4.config b/posix-configs/eagle/210qc/px4.config index 91a77144c0..2adeb36f8f 100644 --- a/posix-configs/eagle/210qc/px4.config +++ b/posix-configs/eagle/210qc/px4.config @@ -19,7 +19,7 @@ param set SENS_BOARD_ROT 0 sleep 1 mpu9250 start -bmp280 start +bmp280 -I start gps start -d /dev/tty-4 rc_update start sensors start diff --git a/posix-configs/excelsior/px4.config b/posix-configs/excelsior/px4.config index eaaf5d0314..f7de529cf5 100644 --- a/posix-configs/excelsior/px4.config +++ b/posix-configs/excelsior/px4.config @@ -18,7 +18,7 @@ param set SENS_BOARD_ROT 4 sleep 1 mpu9250 start -bmp280 start +bmp280 -I start rc_update start sensors start commander start diff --git a/src/drivers/barometer/bmp280/BMP280.cpp b/src/drivers/barometer/bmp280/BMP280.cpp index 8472fad7ea..99547a3c9e 100644 --- a/src/drivers/barometer/bmp280/BMP280.cpp +++ b/src/drivers/barometer/bmp280/BMP280.cpp @@ -33,8 +33,9 @@ #include "BMP280.hpp" -BMP280::BMP280(bmp280::IBMP280 *interface) : - ScheduledWorkItem(MODULE_NAME, px4::device_bus_to_wq(interface->get_device_id())), +BMP280::BMP280(I2CSPIBusOption bus_option, int bus, bmp280::IBMP280 *interface) : + I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(interface->get_device_id()), bus_option, bus, + interface->get_device_address()), _px4_baro(interface->get_device_id()), _interface(interface), _sample_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": sample")), @@ -46,9 +47,6 @@ BMP280::BMP280(bmp280::IBMP280 *interface) : BMP280::~BMP280() { - // make sure we are truly inactive - Stop(); - // free perf counters perf_free(_sample_perf); perf_free(_measure_perf); @@ -109,13 +107,7 @@ BMP280::Start() } void -BMP280::Stop() -{ - ScheduleClear(); -} - -void -BMP280::Run() +BMP280::RunImpl() { if (_collect_phase) { collect(); @@ -194,8 +186,9 @@ BMP280::collect() } void -BMP280::print_info() +BMP280::print_status() { + I2CSPIDriverBase::print_status(); perf_print_counter(_sample_perf); perf_print_counter(_measure_perf); perf_print_counter(_comms_errors); diff --git a/src/drivers/barometer/bmp280/BMP280.hpp b/src/drivers/barometer/bmp280/BMP280.hpp index 1461e981cc..3759062801 100644 --- a/src/drivers/barometer/bmp280/BMP280.hpp +++ b/src/drivers/barometer/bmp280/BMP280.hpp @@ -37,23 +37,27 @@ #include #include +#include #include #include #include -class BMP280 : public px4::ScheduledWorkItem +class BMP280 : public I2CSPIDriver { public: - BMP280(bmp280::IBMP280 *interface); + BMP280(I2CSPIBusOption bus_option, int bus, bmp280::IBMP280 *interface); virtual ~BMP280(); + static I2CSPIDriverBase *instantiate(const BusCLIArguments &cli, const BusInstanceIterator &iterator, + int runtime_instance); + static void print_usage(); + int init(); - void print_info(); + void print_status(); + void RunImpl(); private: - void Run() override; void Start(); - void Stop(); int measure(); //start measure int collect(); //get results and publish diff --git a/src/drivers/barometer/bmp280/BMP280_I2C.cpp b/src/drivers/barometer/bmp280/BMP280_I2C.cpp index 0e2a8a6315..136fe2f2a1 100644 --- a/src/drivers/barometer/bmp280/BMP280_I2C.cpp +++ b/src/drivers/barometer/bmp280/BMP280_I2C.cpp @@ -42,12 +42,11 @@ #include #include -#if defined(PX4_I2C_OBDEV_BMP280) || defined(PX4_I2C_EXT_OBDEV_BMP280) class BMP280_I2C: public device::I2C, public bmp280::IBMP280 { public: - BMP280_I2C(uint8_t bus, uint32_t device); + BMP280_I2C(uint8_t bus, uint32_t device, int bus_frequency); virtual ~BMP280_I2C() override = default; int init() override { return I2C::init(); } @@ -60,18 +59,19 @@ public: uint32_t get_device_id() const override { return device::I2C::get_device_id(); } + uint8_t get_device_address() const override { return device::I2C::get_device_address(); } private: bmp280::calibration_s _cal{}; bmp280::data_s _data{}; }; -bmp280::IBMP280 *bmp280_i2c_interface(uint8_t busnum, uint32_t device) +bmp280::IBMP280 *bmp280_i2c_interface(uint8_t busnum, uint32_t device, int bus_frequency) { - return new BMP280_I2C(busnum, device); + return new BMP280_I2C(busnum, device, bus_frequency); } -BMP280_I2C::BMP280_I2C(uint8_t bus, uint32_t device) : - I2C("BMP280_I2C", nullptr, bus, device, 100 * 1000) +BMP280_I2C::BMP280_I2C(uint8_t bus, uint32_t device, int bus_frequency) : + I2C("BMP280_I2C", nullptr, bus, device, bus_frequency) { } @@ -117,4 +117,3 @@ BMP280_I2C::get_calibration(uint8_t addr) } } -#endif /* PX4_I2C_OBDEV_BMP280 || PX4_I2C_EXT_OBDEV_BMP280 */ diff --git a/src/drivers/barometer/bmp280/BMP280_SPI.cpp b/src/drivers/barometer/bmp280/BMP280_SPI.cpp index fcd6484147..68461b180c 100644 --- a/src/drivers/barometer/bmp280/BMP280_SPI.cpp +++ b/src/drivers/barometer/bmp280/BMP280_SPI.cpp @@ -42,8 +42,6 @@ #include #include -#if defined(PX4_SPIDEV_BARO) || defined(PX4_SPIDEV_EXT_BARO) - /* SPI protocol address bits */ #define DIR_READ (1<<7) //for set #define DIR_WRITE ~(1<<7) //for clear @@ -63,7 +61,7 @@ struct spi_calibration_s { class BMP280_SPI: public device::SPI, public bmp280::IBMP280 { public: - BMP280_SPI(uint8_t bus, uint32_t device); + BMP280_SPI(uint8_t bus, uint32_t device, int bus_frequency, spi_mode_e spi_mode); virtual ~BMP280_SPI() override = default; int init() override { return SPI::init(); } @@ -76,19 +74,20 @@ public: uint32_t get_device_id() const override { return device::SPI::get_device_id(); } + uint8_t get_device_address() const override { return device::SPI::get_device_address(); } private: spi_calibration_s _cal{}; spi_data_s _data{}; }; bmp280::IBMP280 * -bmp280_spi_interface(uint8_t busnum, uint32_t device) +bmp280_spi_interface(uint8_t busnum, uint32_t device, int bus_frequency, spi_mode_e spi_mode) { - return new BMP280_SPI(busnum, device); + return new BMP280_SPI(busnum, device, bus_frequency, spi_mode); } -BMP280_SPI::BMP280_SPI(uint8_t bus, uint32_t device) : - SPI("BMP280_SPI", nullptr, bus, device, SPIDEV_MODE3, 10 * 1000 * 1000) +BMP280_SPI::BMP280_SPI(uint8_t bus, uint32_t device, int bus_frequency, spi_mode_e spi_mode) : + SPI("BMP280_SPI", nullptr, bus, device, spi_mode, bus_frequency) { } @@ -133,5 +132,3 @@ BMP280_SPI::get_calibration(uint8_t addr) return nullptr; } } - -#endif /* PX4_SPIDEV_BARO || PX4_SPIDEV_EXT_BARO */ diff --git a/src/drivers/barometer/bmp280/bmp280.h b/src/drivers/barometer/bmp280/bmp280.h index c08a596d62..9103c97973 100644 --- a/src/drivers/barometer/bmp280/bmp280.h +++ b/src/drivers/barometer/bmp280/bmp280.h @@ -38,6 +38,7 @@ */ #pragma once +#include #include #define BMP280_ADDR_CAL 0x88 /* address of 12x 2 bytes calibration data */ @@ -151,12 +152,12 @@ public: virtual uint32_t get_device_id() const = 0; + virtual uint8_t get_device_address() const = 0; }; } /* namespace */ /* interface factories */ -extern bmp280::IBMP280 *bmp280_spi_interface(uint8_t busnum, uint32_t device); -extern bmp280::IBMP280 *bmp280_i2c_interface(uint8_t busnum, uint32_t device); -typedef bmp280::IBMP280 *(*BMP280_constructor)(uint8_t, uint32_t); +extern bmp280::IBMP280 *bmp280_spi_interface(uint8_t busnum, uint32_t device, int bus_frequency, spi_mode_e spi_mode); +extern bmp280::IBMP280 *bmp280_i2c_interface(uint8_t busnum, uint32_t device, int bus_frequency); diff --git a/src/drivers/barometer/bmp280/bmp280_main.cpp b/src/drivers/barometer/bmp280/bmp280_main.cpp index 071633c11a..a77da14357 100644 --- a/src/drivers/barometer/bmp280/bmp280_main.cpp +++ b/src/drivers/barometer/bmp280/bmp280_main.cpp @@ -33,198 +33,91 @@ #include #include +#include #include "BMP280.hpp" -enum class BMP280_BUS { - ALL = 0, - I2C_INTERNAL, - I2C_EXTERNAL, - SPI_INTERNAL, - SPI_EXTERNAL -}; +extern "C" { __EXPORT int bmp280_main(int argc, char *argv[]); } -namespace bmp280 +void +BMP280::print_usage() { + PRINT_MODULE_USAGE_NAME("bmp280", "driver"); + PRINT_MODULE_USAGE_SUBCATEGORY("baro"); + PRINT_MODULE_USAGE_COMMAND("start"); + PRINT_MODULE_USAGE_PARAMS_I2C_SPI_DRIVER(true, true); + PRINT_MODULE_USAGE_PARAMS_I2C_ADDRESS(0x76); + PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); +} -// list of supported bus configurations -struct bmp280_bus_option { - BMP280_BUS busid; - BMP280_constructor interface_constructor; - uint8_t busnum; - uint32_t address; - BMP280 *dev; -} bus_options[] = { -#if defined(PX4_SPI_BUS_EXT) && defined(PX4_SPIDEV_EXT_BARO) - { BMP280_BUS::SPI_EXTERNAL, &bmp280_spi_interface, PX4_SPI_BUS_EXT, PX4_SPIDEV_EXT_BARO, nullptr }, -#endif -#if defined(PX4_SPIDEV_BARO_BUS) && defined(PX4_SPIDEV_BARO) - { BMP280_BUS::SPI_INTERNAL, &bmp280_spi_interface, PX4_SPIDEV_BARO_BUS, PX4_SPIDEV_BARO, nullptr }, -#elif defined(PX4_SPI_BUS_SENSORS) && defined(PX4_SPIDEV_BARO) - { BMP280_BUS::SPI_INTERNAL, &bmp280_spi_interface, PX4_SPI_BUS_SENSORS, PX4_SPIDEV_BARO, nullptr }, -#endif -#if defined(PX4_I2C_BUS_ONBOARD) && defined(PX4_I2C_OBDEV_BMP280) - { BMP280_BUS::I2C_INTERNAL, &bmp280_i2c_interface, PX4_I2C_BUS_ONBOARD, PX4_I2C_OBDEV_BMP280, nullptr }, -#endif -#if defined(PX4_I2C_BUS_EXPANSION) && defined(PX4_I2C_OBDEV_BMP280) - { BMP280_BUS::I2C_EXTERNAL, &bmp280_i2c_interface, PX4_I2C_BUS_EXPANSION, PX4_I2C_OBDEV_BMP280, nullptr }, -#endif -}; - -// find a bus structure for a busid -static struct bmp280_bus_option *find_bus(BMP280_BUS busid) +I2CSPIDriverBase *BMP280::instantiate(const BusCLIArguments &cli, const BusInstanceIterator &iterator, + int runtime_instance) { - for (bmp280_bus_option &bus_option : bus_options) { - if ((busid == BMP280_BUS::ALL || - busid == bus_option.busid) && bus_option.dev != nullptr) { + bmp280::IBMP280 *interface = nullptr; - return &bus_option; - } - } + if (iterator.busType() == BOARD_I2C_BUS) { + interface = bmp280_i2c_interface(iterator.bus(), cli.i2c_address, cli.bus_frequency); - return nullptr; -} + } else if (iterator.busType() == BOARD_SPI_BUS) { + interface = bmp280_spi_interface(iterator.bus(), iterator.devid(), cli.bus_frequency, cli.spi_mode); + } -static bool start_bus(bmp280_bus_option &bus) -{ - bmp280::IBMP280 *interface = bus.interface_constructor(bus.busnum, bus.address); + if (interface == nullptr) { + PX4_ERR("failed creating interface for bus %i (devid 0x%x)", iterator.bus(), iterator.devid()); + return nullptr; + } - if ((interface == nullptr) || (interface->init() != PX4_OK)) { - PX4_WARN("no device on bus %u", (unsigned)bus.busid); + if (interface->init() != OK) { delete interface; - return false; + PX4_DEBUG("no device on bus %i (devid 0x%x)", iterator.bus(), iterator.devid()); + return nullptr; } - BMP280 *dev = new BMP280(interface); + BMP280 *dev = new BMP280(iterator.configuredBusOption(), iterator.bus(), interface); if (dev == nullptr) { - PX4_ERR("driver allocate failed"); delete interface; - return false; - } - - if (dev->init() != PX4_OK) { - PX4_ERR("driver start failed"); - delete dev; // BMP280 deletes the interface - return false; + return nullptr; } - bus.dev = dev; - - return true; -} - -static int start(BMP280_BUS busid) -{ - for (bmp280_bus_option &bus_option : bus_options) { - if (bus_option.dev != nullptr) { - // this device is already started - PX4_WARN("already started"); - continue; - } - - if (busid != BMP280_BUS::ALL && bus_option.busid != busid) { - // not the one that is asked for - continue; - } - - if (start_bus(bus_option)) { - return PX4_OK; - } + if (OK != dev->init()) { + delete dev; + return nullptr; } - return PX4_ERROR; + return dev; } -static int stop(BMP280_BUS busid) +int +bmp280_main(int argc, char *argv[]) { - bmp280_bus_option *bus = find_bus(busid); + using ThisDriver = BMP280; + BusCLIArguments cli{true, true}; + cli.i2c_address = 0x76; + cli.default_i2c_frequency = 100 * 1000; + cli.default_spi_frequency = 10 * 1000 * 1000; - if (bus != nullptr && bus->dev != nullptr) { - delete bus->dev; - bus->dev = nullptr; + const char *verb = cli.parseDefaultArguments(argc, argv); - } else { - PX4_WARN("driver not running"); - return PX4_ERROR; + if (!verb) { + ThisDriver::print_usage(); + return -1; } - return PX4_OK; -} + BusInstanceIterator iterator(MODULE_NAME, cli, DRV_BARO_DEVTYPE_BMP280); -static int status(BMP280_BUS busid) -{ - bmp280_bus_option *bus = find_bus(busid); - - if (bus != nullptr && bus->dev != nullptr) { - bus->dev->print_info(); - return PX4_OK; - } - - PX4_WARN("driver not running"); - return PX4_ERROR; -} - -static int usage() -{ - PX4_INFO("missing command: try 'start', 'stop', 'status'"); - PX4_INFO("options:"); - PX4_INFO(" -X (i2c external bus)"); - PX4_INFO(" -I (i2c internal bus)"); - PX4_INFO(" -s (spi internal bus)"); - PX4_INFO(" -S (spi external bus)"); - - return 0; -} - -} // namespace - -extern "C" int bmp280_main(int argc, char *argv[]) -{ - int myoptind = 1; - int ch; - const char *myoptarg = nullptr; - - BMP280_BUS busid = BMP280_BUS::ALL; - - while ((ch = px4_getopt(argc, argv, "XISs:", &myoptind, &myoptarg)) != EOF) { - switch (ch) { - case 'X': - busid = BMP280_BUS::I2C_EXTERNAL; - break; - - case 'I': - busid = BMP280_BUS::I2C_INTERNAL; - break; - - case 'S': - busid = BMP280_BUS::SPI_EXTERNAL; - break; - - case 's': - busid = BMP280_BUS::SPI_INTERNAL; - break; - - default: - return bmp280::usage(); - } + if (!strcmp(verb, "start")) { + return ThisDriver::module_start(cli, iterator); } - if (myoptind >= argc) { - return bmp280::usage(); + if (!strcmp(verb, "stop")) { + return ThisDriver::module_stop(iterator); } - const char *verb = argv[myoptind]; - - if (!strcmp(verb, "start")) { - return bmp280::start(busid); - - } else if (!strcmp(verb, "stop")) { - return bmp280::stop(busid); - - } else if (!strcmp(verb, "status")) { - return bmp280::status(busid); + if (!strcmp(verb, "status")) { + return ThisDriver::module_status(iterator); } - return bmp280::usage(); + ThisDriver::print_usage(); + return -1; }