ms5611: move to PX4Barometer and cleanup

This commit is contained in:
Daniel Agar 2019-12-29 23:15:36 -05:00
parent 87e5da189b
commit ef12e63af2
8 changed files with 160 additions and 429 deletions

View File

@ -1,6 +1,6 @@
############################################################################
#
# Copyright (c) 2015 PX4 Development Team. All rights reserved.
# Copyright (c) 2015-2019 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
@ -32,7 +32,7 @@
############################################################################
px4_add_module(
MODULE drivers__ms5611
MODULE drivers__barometer__ms5611
MAIN ms5611
COMPILE_FLAGS
-Wno-cast-align # TODO: fix and enable
@ -43,5 +43,6 @@ px4_add_module(
ms5611_main.cpp
MS5611.hpp
DEPENDS
drivers_barometer
px4_work_queue
)

View File

@ -33,17 +33,11 @@
#pragma once
#include <drivers/device/i2c.h>
#include <drivers/device/device.h>
#include <drivers/device/ringbuffer.h>
#include <drivers/device/spi.h>
#include <drivers/drv_baro.h>
#include <lib/cdev/CDev.hpp>
#include <lib/drivers/barometer/PX4Barometer.hpp>
#include <lib/perf/perf_counter.h>
#include <px4_platform_common/getopt.h>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <systemlib/err.h>
#include <uORB/uORB.h>
#include "ms5611.h"
@ -89,19 +83,14 @@ enum MS56XX_DEVICE_TYPES {
*/
#define MS5611_CONVERSION_INTERVAL 10000 /* microseconds */
#define MS5611_MEASUREMENT_RATIO 3 /* pressure measurements per temperature measurement */
#define MS5611_BARO_DEVICE_PATH_EXT "/dev/ms5611_ext"
#define MS5611_BARO_DEVICE_PATH_INT "/dev/ms5611_int"
class MS5611 : public cdev::CDev, public px4::ScheduledWorkItem
class MS5611 : public px4::ScheduledWorkItem
{
public:
MS5611(device::Device *interface, ms5611::prom_u &prom_buf, const char *path, enum MS56XX_DEVICE_TYPES device_type);
MS5611(device::Device *interface, ms5611::prom_u &prom_buf, enum MS56XX_DEVICE_TYPES device_type);
~MS5611() override;
int init() override;
ssize_t read(cdev::file_t *filp, char *buffer, size_t buflen) override;
int ioctl(cdev::file_t *filp, int cmd, unsigned long arg) override;
int init();
/**
* Diagnostics - print some basic information about the driver.
@ -109,27 +98,22 @@ public:
void print_info();
protected:
PX4Barometer _px4_barometer;
device::Device *_interface;
ms5611::prom_s _prom;
unsigned _measure_interval{0};
ringbuffer::RingBuffer *_reports;
enum MS56XX_DEVICE_TYPES _device_type;
bool _collect_phase;
unsigned _measure_phase;
bool _collect_phase{false};
unsigned _measure_phase{false};
/* intermediate temperature values per MS5611/MS5607 datasheet */
int32_t _TEMP;
int64_t _OFF;
int64_t _SENS;
float _P;
float _T;
orb_advert_t _baro_topic;
int _orb_class_instance;
int _class_instance;
int64_t _OFF{0};
int64_t _SENS{0};
perf_counter_t _sample_perf;
perf_counter_t _measure_perf;

View File

@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2012-2015 PX4 Development Team. All rights reserved.
* Copyright (c) 2012-2019 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
@ -41,25 +41,15 @@
#include <cdev/CDev.hpp>
MS5611::MS5611(device::Device *interface, ms5611::prom_u &prom_buf, const char *path,
enum MS56XX_DEVICE_TYPES device_type) :
CDev(path),
MS5611::MS5611(device::Device *interface, ms5611::prom_u &prom_buf, enum MS56XX_DEVICE_TYPES device_type) :
ScheduledWorkItem(MODULE_NAME, px4::device_bus_to_wq(interface->get_device_id())),
_px4_barometer(interface->get_device_id()),
_interface(interface),
_prom(prom_buf.s),
_reports(nullptr),
_device_type(device_type),
_collect_phase(false),
_measure_phase(0),
_TEMP(0),
_OFF(0),
_SENS(0),
_baro_topic(nullptr),
_orb_class_instance(-1),
_class_instance(-1),
_sample_perf(perf_alloc(PC_ELAPSED, "ms5611_read")),
_measure_perf(perf_alloc(PC_ELAPSED, "ms5611_measure")),
_comms_errors(perf_alloc(PC_COUNT, "ms5611_com_err"))
_sample_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": read")),
_measure_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": measure")),
_comms_errors(perf_alloc(PC_COUNT, MODULE_NAME": com_err"))
{
}
@ -68,15 +58,6 @@ MS5611::~MS5611()
/* make sure we are truly inactive */
stop();
if (_class_instance != -1) {
unregister_class_devname(get_devname(), _class_instance);
}
/* free any existing reports */
if (_reports != nullptr) {
delete _reports;
}
// free perf counters
perf_free(_sample_perf);
perf_free(_measure_perf);
@ -91,29 +72,8 @@ MS5611::init()
int ret;
bool autodetect = false;
ret = CDev::init();
if (ret != OK) {
PX4_DEBUG("CDev init failed");
goto out;
}
/* allocate basic report buffers */
_reports = new ringbuffer::RingBuffer(2, sizeof(sensor_baro_s));
if (_reports == nullptr) {
PX4_DEBUG("can't get memory for reports");
ret = -ENOMEM;
goto out;
}
/* register alternate interfaces if we have to */
_class_instance = register_class_devname(BARO_BASE_DEVICE_PATH);
sensor_baro_s brp;
/* do a first measurement cycle to populate reports with valid data */
_measure_phase = 0;
_reports->flush();
if (_device_type == MS56XX_DEVICE) {
autodetect = true;
@ -149,7 +109,7 @@ MS5611::init()
}
/* state machine will have generated a report, copy it out */
_reports->get(&brp);
const sensor_baro_s &brp = _px4_barometer.get();
if (autodetect) {
if (_device_type == MS5611_DEVICE) {
@ -176,181 +136,31 @@ MS5611::init()
/* fall through */
case MS5611_DEVICE:
_interface->set_device_type(DRV_BARO_DEVTYPE_MS5611);
_px4_barometer.set_device_type(DRV_BARO_DEVTYPE_MS5611);
break;
case MS5607_DEVICE:
_interface->set_device_type(DRV_BARO_DEVTYPE_MS5607);
_px4_barometer.set_device_type(DRV_BARO_DEVTYPE_MS5607);
break;
}
/* ensure correct devid */
brp.device_id = _interface->get_device_id();
ret = OK;
_baro_topic = orb_advertise_multi(ORB_ID(sensor_baro), &brp,
&_orb_class_instance, _interface->external() ? ORB_PRIO_HIGH : ORB_PRIO_DEFAULT);
if (_baro_topic == nullptr) {
warnx("failed to create sensor_baro publication");
}
break;
}
out:
return ret;
}
ssize_t
MS5611::read(cdev::file_t *filp, char *buffer, size_t buflen)
{
unsigned count = buflen / sizeof(sensor_baro_s);
sensor_baro_s *brp = reinterpret_cast<sensor_baro_s *>(buffer);
int ret = 0;
/* buffer must be large enough */
if (count < 1) {
return -ENOSPC;
}
/* if automatic measurement is enabled */
if (_measure_interval > 0) {
/*
* While there is space in the caller's buffer, and reports, copy them.
* Note that we may be pre-empted by the workq thread while we are doing this;
* we are careful to avoid racing with them.
*/
while (count--) {
if (_reports->get(brp)) {
ret += sizeof(*brp);
brp++;
}
}
/* if there was no data, warn the caller */
return ret ? ret : -EAGAIN;
}
/* manual measurement - run one conversion */
do {
_measure_phase = 0;
_reports->flush();
/* do temperature first */
if (OK != measure()) {
ret = -EIO;
break;
}
px4_usleep(MS5611_CONVERSION_INTERVAL);
if (OK != collect()) {
ret = -EIO;
break;
}
/* now do a pressure measurement */
if (OK != measure()) {
ret = -EIO;
break;
}
px4_usleep(MS5611_CONVERSION_INTERVAL);
if (OK != collect()) {
ret = -EIO;
break;
}
/* state machine will have generated a report, copy it out */
if (_reports->get(brp)) {
ret = sizeof(*brp);
}
} while (0);
start();
return ret;
}
int
MS5611::ioctl(cdev::file_t *filp, int cmd, unsigned long arg)
{
switch (cmd) {
case SENSORIOCSPOLLRATE: {
switch (arg) {
/* zero would be bad */
case 0:
return -EINVAL;
/* set default polling rate */
case SENSOR_POLLRATE_DEFAULT: {
/* do we need to start internal polling? */
bool want_start = (_measure_interval == 0);
/* set interval for next measurement to minimum legal value */
_measure_interval = MS5611_CONVERSION_INTERVAL;
/* if we need to start the poll state machine, do it */
if (want_start) {
start();
}
return OK;
}
/* adjust to a legal polling interval in Hz */
default: {
/* do we need to start internal polling? */
bool want_start = (_measure_interval == 0);
/* convert hz to interval via microseconds */
unsigned interval = (1000000 / arg);
/* check against maximum rate */
if (_measure_interval < MS5611_CONVERSION_INTERVAL) {
return -EINVAL;
}
/* update interval for next measurement */
_measure_interval = interval;
/* if we need to start the poll state machine, do it */
if (want_start) {
start();
}
return OK;
}
}
}
case SENSORIOCRESET:
/*
* Since we are initialized, we do not need to do anything, since the
* PROM is correctly read and the part does not need to be configured.
*/
return OK;
default:
break;
}
/* give it to the bus-specific superclass */
// return bus_ioctl(filp, cmd, arg);
return CDev::ioctl(filp, cmd, arg);
}
void
MS5611::start()
{
/* reset the report ring and state machine */
_collect_phase = false;
_measure_phase = 0;
_reports->flush();
/* schedule a cycle to start things */
ScheduleNow();
@ -434,8 +244,6 @@ MS5611::Run()
int
MS5611::measure()
{
int ret;
perf_begin(_measure_perf);
/*
@ -446,12 +254,14 @@ MS5611::measure()
/*
* Send the command to begin measuring.
*/
ret = _interface->ioctl(IOCTL_MEASURE, addr);
int ret = _interface->ioctl(IOCTL_MEASURE, addr);
if (OK != ret) {
perf_count(_comms_errors);
}
_px4_barometer.set_error_count(perf_event_count(_comms_errors));
perf_end(_measure_perf);
return ret;
@ -460,18 +270,13 @@ MS5611::measure()
int
MS5611::collect()
{
int ret;
uint32_t raw;
perf_begin(_sample_perf);
sensor_baro_s report;
/* this should be fairly close to the end of the conversion, so the best approximation of the time */
report.timestamp = hrt_absolute_time();
report.error_count = perf_event_count(_comms_errors);
/* read the most recent measurement - read offset/size are hardcoded in the interface */
ret = _interface->read(0, (void *)&raw, 0);
const hrt_abstime timestamp_sample = hrt_absolute_time();
int ret = _interface->read(0, (void *)&raw, 0);
if (ret < 0) {
perf_count(_comms_errors);
@ -486,91 +291,71 @@ MS5611::collect()
int32_t dT = (int32_t)raw - ((int32_t)_prom.c5_reference_temp << 8);
/* absolute temperature in centidegrees - note intermediate value is outside 32-bit range */
_TEMP = 2000 + (int32_t)(((int64_t)dT * _prom.c6_temp_coeff_temp) >> 23);
int32_t TEMP = 2000 + (int32_t)(((int64_t)dT * _prom.c6_temp_coeff_temp) >> 23);
/* base sensor scale/offset values */
if (_device_type == MS5611_DEVICE) {
/* Perform MS5611 Caculation */
_OFF = ((int64_t)_prom.c2_pressure_offset << 16) + (((int64_t)_prom.c4_temp_coeff_pres_offset * dT) >> 7);
_SENS = ((int64_t)_prom.c1_pressure_sens << 15) + (((int64_t)_prom.c3_temp_coeff_pres_sens * dT) >> 8);
/* MS5611 temperature compensation */
if (_TEMP < 2000) {
if (TEMP < 2000) {
int32_t T2 = POW2(dT) >> 31;
int64_t f = POW2((int64_t)_TEMP - 2000);
int64_t f = POW2((int64_t)TEMP - 2000);
int64_t OFF2 = 5 * f >> 1;
int64_t SENS2 = 5 * f >> 2;
if (_TEMP < -1500) {
if (TEMP < -1500) {
int64_t f2 = POW2(_TEMP + 1500);
int64_t f2 = POW2(TEMP + 1500);
OFF2 += 7 * f2;
SENS2 += 11 * f2 >> 1;
}
_TEMP -= T2;
TEMP -= T2;
_OFF -= OFF2;
_SENS -= SENS2;
}
} else if (_device_type == MS5607_DEVICE) {
/* Perform MS5607 Caculation */
_OFF = ((int64_t)_prom.c2_pressure_offset << 17) + (((int64_t)_prom.c4_temp_coeff_pres_offset * dT) >> 6);
_SENS = ((int64_t)_prom.c1_pressure_sens << 16) + (((int64_t)_prom.c3_temp_coeff_pres_sens * dT) >> 7);
/* MS5607 temperature compensation */
if (_TEMP < 2000) {
if (TEMP < 2000) {
int32_t T2 = POW2(dT) >> 31;
int64_t f = POW2((int64_t)_TEMP - 2000);
int64_t f = POW2((int64_t)TEMP - 2000);
int64_t OFF2 = 61 * f >> 4;
int64_t SENS2 = 2 * f;
if (_TEMP < -1500) {
int64_t f2 = POW2(_TEMP + 1500);
if (TEMP < -1500) {
int64_t f2 = POW2(TEMP + 1500);
OFF2 += 15 * f2;
SENS2 += 8 * f2;
}
_TEMP -= T2;
TEMP -= T2;
_OFF -= OFF2;
_SENS -= SENS2;
}
}
} else {
float temperature = TEMP / 100.0f;
_px4_barometer.set_temperature(temperature);
} else {
/* pressure calculation, result in Pa */
int32_t P = (((raw * _SENS) >> 21) - _OFF) >> 15;
_P = P * 0.01f;
_T = _TEMP * 0.01f;
/* generate a new report */
report.temperature = _TEMP / 100.0f;
report.pressure = P / 100.0f; /* convert to millibar */
float pressure = P / 100.0f; /* convert to millibar */
/* return device ID */
report.device_id = _interface->get_device_id();
/* publish it */
if (_baro_topic != nullptr) {
/* publish it */
orb_publish(ORB_ID(sensor_baro), _baro_topic, &report);
}
_reports->force(&report);
/* notify anyone waiting for data */
poll_notify(POLLIN);
_px4_barometer.update(timestamp_sample, pressure);
}
/* update the measurement state machine */
@ -581,18 +366,14 @@ MS5611::collect()
return OK;
}
void
MS5611::print_info()
void MS5611::print_info()
{
perf_print_counter(_sample_perf);
perf_print_counter(_comms_errors);
printf("poll interval: %u\n", _measure_interval);
_reports->print_info("report queue");
printf("device: %s\n", _device_type == MS5611_DEVICE ? "ms5611" : "ms5607");
sensor_baro_s brp = {};
_reports->get(&brp);
print_message(brp);
_px4_barometer.print_status();
}
/**

View File

@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (C) 2012-2013 PX4 Development Team. All rights reserved.
* Copyright (C) 2012-2019 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
@ -43,12 +43,8 @@
#include <drivers/device/i2c.h>
#include <drivers/device/device.h>
#include <drivers/device/ringbuffer.h>
#include <drivers/device/spi.h>
#include <drivers/drv_baro.h>
#include <lib/cdev/CDev.hpp>
#include <lib/perf/perf_counter.h>
#include <px4_platform_common/getopt.h>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <systemlib/err.h>
#include <uORB/uORB.h>
@ -96,5 +92,5 @@ extern bool crc4(uint16_t *n_prom);
/* interface factories */
extern device::Device *MS5611_spi_interface(ms5611::prom_u &prom_buf, uint8_t busnum);
extern device::Device *MS5611_i2c_interface(ms5611::prom_u &prom_buf, uint8_t busnum);
extern device::Device *MS5611_sim_interface(ms5611::prom_u &prom_buf, uint8_t busnum);
typedef device::Device *(*MS5611_constructor)(ms5611::prom_u &prom_buf, uint8_t busnum);

View File

@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2013 PX4 Development Team. All rights reserved.
* Copyright (c) 2013-2019 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
@ -37,15 +37,13 @@
* I2C interface for MS5611
*/
#include <drivers/device/i2c.h>
#include "ms5611.h"
#define MS5611_ADDRESS_1 0x76 /* address select pins pulled high (PX4FMU series v1.6+) */
#define MS5611_ADDRESS_2 0x77 /* address select pins pulled low (PX4FMU prototypes) */
device::Device *MS5611_i2c_interface(ms5611::prom_u &prom_buf);
class MS5611_I2C : public device::I2C
{
public:

View File

@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2012-2015 PX4 Development Team. All rights reserved.
* Copyright (c) 2012-2019 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
@ -31,173 +31,152 @@
*
****************************************************************************/
/**
* @file ms5611.cpp
* Driver for the MS5611 and MS5607 barometric pressure sensor connected via I2C or SPI.
*/
#include <px4_platform_common/px4_config.h>
#include <px4_platform_common/getopt.h>
#include "MS5611.hpp"
#include "ms5611.h"
enum MS5611_BUS {
MS5611_BUS_ALL = 0,
MS5611_BUS_I2C_INTERNAL,
MS5611_BUS_I2C_EXTERNAL,
MS5611_BUS_SPI_INTERNAL,
MS5611_BUS_SPI_EXTERNAL
enum class MS5611_BUS {
ALL = 0,
I2C_INTERNAL,
I2C_EXTERNAL,
SPI_INTERNAL,
SPI_EXTERNAL
};
/*
* Driver 'main' command.
*/
extern "C" __EXPORT int ms5611_main(int argc, char *argv[]);
/**
* Local functions in support of the shell command.
*/
namespace ms5611
{
/*
list of supported bus configurations
*/
// list of supported bus configurations
struct ms5611_bus_option {
enum MS5611_BUS busid;
const char *devpath;
MS5611_BUS busid;
MS5611_constructor interface_constructor;
uint8_t busnum;
MS5611 *dev;
} bus_options[] = {
#if defined(PX4_SPIDEV_EXT_BARO) && defined(PX4_SPI_BUS_EXT)
{ MS5611_BUS_SPI_EXTERNAL, "/dev/ms5611_spi_ext", &MS5611_spi_interface, PX4_SPI_BUS_EXT, NULL },
#if defined(PX4_I2C_BUS_ONBOARD)
{ MS5611_BUS::I2C_INTERNAL, &MS5611_i2c_interface, PX4_I2C_BUS_ONBOARD, nullptr },
#endif
#ifdef PX4_SPIDEV_BARO
{ MS5611_BUS_SPI_INTERNAL, "/dev/ms5611_spi_int", &MS5611_spi_interface, PX4_SPI_BUS_BARO, NULL },
#if defined(PX4_I2C_BUS_EXPANSION)
{ MS5611_BUS::I2C_EXTERNAL, &MS5611_i2c_interface, PX4_I2C_BUS_EXPANSION, nullptr },
#endif
#ifdef PX4_I2C_BUS_ONBOARD
{ MS5611_BUS_I2C_INTERNAL, "/dev/ms5611_int", &MS5611_i2c_interface, PX4_I2C_BUS_ONBOARD, NULL },
#if defined(PX4_I2C_BUS_EXPANSION1)
{ MS5611_BUS::I2C_EXTERNAL, &MS5611_i2c_interface, PX4_I2C_BUS_EXPANSION1, nullptr },
#endif
#ifdef PX4_I2C_BUS_EXPANSION
{ MS5611_BUS_I2C_EXTERNAL, "/dev/ms5611_ext", &MS5611_i2c_interface, PX4_I2C_BUS_EXPANSION, NULL },
#if defined(PX4_I2C_BUS_EXPANSION2)
{ MS5611_BUS::I2C_EXTERNAL, &MS5611_i2c_interface, PX4_I2C_BUS_EXPANSION2, nullptr },
#endif
#ifdef PX4_I2C_BUS_EXPANSION1
{ MS5611_BUS_I2C_EXTERNAL, "/dev/ms5611_ext1", &MS5611_i2c_interface, PX4_I2C_BUS_EXPANSION1, NULL },
#if defined(PX4_SPI_BUS_BARO) && defined(PX4_SPIDEV_BARO)
{ MS5611_BUS::SPI_INTERNAL, &MS5611_spi_interface, PX4_SPI_BUS_BARO, nullptr },
#endif
#ifdef PX4_I2C_BUS_EXPANSION2
{ MS5611_BUS_I2C_EXTERNAL, "/dev/ms5611_ext2", &MS5611_i2c_interface, PX4_I2C_BUS_EXPANSION2, NULL },
#if defined(PX4_SPI_BUS_EXT) && defined(PX4_SPIDEV_EXT_BARO)
{ MS5611_BUS::SPI_EXTERNAL, &MS5611_spi_interface, PX4_SPI_BUS_EXT, nullptr },
#endif
};
#define NUM_BUS_OPTIONS (sizeof(bus_options)/sizeof(bus_options[0]))
/**
* Start the driver.
*/
static bool
start_bus(struct ms5611_bus_option &bus, enum MS56XX_DEVICE_TYPES device_type)
// find a bus structure for a busid
static struct ms5611_bus_option *find_bus(MS5611_BUS busid)
{
if (bus.dev != nullptr) {
PX4_ERR("bus option already started");
return false;
for (ms5611_bus_option &bus_option : bus_options) {
if ((busid == MS5611_BUS::ALL ||
busid == bus_option.busid) && bus_option.dev != nullptr) {
return &bus_option;
}
}
return nullptr;
}
static bool start_bus(ms5611_bus_option &bus, enum MS56XX_DEVICE_TYPES device_type)
{
prom_u prom_buf;
device::Device *interface = bus.interface_constructor(prom_buf, bus.busnum);
if (interface->init() != OK) {
delete interface;
if ((interface == nullptr) || (interface->init() != PX4_OK)) {
PX4_WARN("no device on bus %u", (unsigned)bus.busid);
delete interface;
return false;
}
bus.dev = new MS5611(interface, prom_buf, bus.devpath, device_type);
MS5611 *dev = new MS5611(interface, prom_buf, device_type);
if (bus.dev == nullptr) {
if (dev == nullptr) {
PX4_ERR("alloc failed");
return false;
}
if (bus.dev->init() != PX4_OK) {
delete bus.dev;
bus.dev = nullptr;
if (dev->init() != PX4_OK) {
PX4_ERR("driver start failed");
delete dev;
return false;
}
int fd = px4_open(bus.devpath, O_RDONLY);
bus.dev = dev;
/* set the poll rate to default, starts automatic data collection */
if (fd == -1) {
PX4_ERR("can't open baro device");
return false;
}
if (px4_ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) {
px4_close(fd);
PX4_ERR("failed setting default poll rate");
return false;
}
px4_close(fd);
return true;
}
/**
* Start the driver.
*
* This function call only returns once the driver
* is either successfully up and running or failed to start.
*/
static int
start(enum MS5611_BUS busid, enum MS56XX_DEVICE_TYPES device_type)
static int start(MS5611_BUS busid, enum MS56XX_DEVICE_TYPES device_type)
{
uint8_t i;
bool started = false;
for (i = 0; i < NUM_BUS_OPTIONS; i++) {
if (busid == MS5611_BUS_ALL && bus_options[i].dev != NULL) {
for (ms5611_bus_option &bus_option : bus_options) {
if (bus_option.dev != nullptr) {
// this device is already started
PX4_WARN("already started");
continue;
}
if (busid != MS5611_BUS_ALL && bus_options[i].busid != busid) {
if (busid != MS5611_BUS::ALL && bus_option.busid != busid) {
// not the one that is asked for
continue;
}
started = started | start_bus(bus_options[i], device_type);
}
if (!started) {
return PX4_ERROR;
}
// one or more drivers started OK
return PX4_OK;
}
static int
info()
{
for (uint8_t i = 0; i < NUM_BUS_OPTIONS; i++) {
struct ms5611_bus_option &bus = bus_options[i];
if (bus.dev != nullptr) {
PX4_INFO("%s", bus.devpath);
bus.dev->print_info();
if (start_bus(bus_option, device_type)) {
return PX4_OK;
}
}
return 0;
return PX4_ERROR;
}
static int
usage()
static int stop(MS5611_BUS busid)
{
PX4_INFO("missing command: try 'start', 'info',");
ms5611_bus_option *bus = find_bus(busid);
if (bus != nullptr && bus->dev != nullptr) {
delete bus->dev;
bus->dev = nullptr;
} else {
PX4_WARN("driver not running");
return PX4_ERROR;
}
return PX4_OK;
}
static int status(MS5611_BUS busid)
{
ms5611_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 (external I2C bus)");
PX4_INFO(" -I (intternal I2C bus)");
PX4_INFO(" -S (external SPI bus)");
PX4_INFO(" -s (internal SPI bus)");
PX4_INFO(" -X (i2c external bus)");
PX4_INFO(" -I (i2c internal bus)");
PX4_INFO(" -s (spi internal bus)");
PX4_INFO(" -S (spi external bus)");
PX4_INFO(" -T 5611|5607 (default 5611)");
PX4_INFO(" -T 0 (autodetect version)");
@ -206,32 +185,31 @@ usage()
} // namespace
int
ms5611_main(int argc, char *argv[])
extern "C" int ms5611_main(int argc, char *argv[])
{
enum MS5611_BUS busid = MS5611_BUS_ALL;
enum MS56XX_DEVICE_TYPES device_type = MS5611_DEVICE;
int ch;
int myoptind = 1;
const char *myoptarg = NULL;
int ch;
const char *myoptarg = nullptr;
/* jump over start/off/etc and look at options first */
while ((ch = px4_getopt(argc, argv, "T:XISs", &myoptind, &myoptarg)) != EOF) {
MS5611_BUS busid = MS5611_BUS::ALL;
enum MS56XX_DEVICE_TYPES device_type = MS5611_DEVICE;
while ((ch = px4_getopt(argc, argv, "XISsT:", &myoptind, &myoptarg)) != EOF) {
switch (ch) {
case 'X':
busid = MS5611_BUS_I2C_EXTERNAL;
busid = MS5611_BUS::I2C_EXTERNAL;
break;
case 'I':
busid = MS5611_BUS_I2C_INTERNAL;
busid = MS5611_BUS::I2C_INTERNAL;
break;
case 'S':
busid = MS5611_BUS_SPI_EXTERNAL;
busid = MS5611_BUS::SPI_EXTERNAL;
break;
case 's':
busid = MS5611_BUS_SPI_INTERNAL;
busid = MS5611_BUS::SPI_INTERNAL;
break;
case 'T': {
@ -239,19 +217,15 @@ ms5611_main(int argc, char *argv[])
if (val == 5611) {
device_type = MS5611_DEVICE;
break;
} else if (val == 5607) {
device_type = MS5607_DEVICE;
break;
} else if (val == 0) {
device_type = MS56XX_DEVICE;
break;
}
}
/* FALLTHROUGH */
break;
default:
return ms5611::usage();
@ -264,18 +238,14 @@ ms5611_main(int argc, char *argv[])
const char *verb = argv[myoptind];
/*
* Start/load the driver.
*/
if (!strcmp(verb, "start")) {
return ms5611::start(busid, device_type);
}
/*
* Print driver information.
*/
if (!strcmp(verb, "info")) {
return ms5611::info();
} else if (!strcmp(verb, "stop")) {
return ms5611::stop(busid);
} else if (!strcmp(verb, "status")) {
return ms5611::status(busid);
}
return ms5611::usage();

View File

@ -37,6 +37,7 @@
* SPI interface for MS5611
*/
#include <drivers/device/spi.h>
#include "ms5611.h"
/* SPI protocol address bits */
@ -46,8 +47,6 @@
#if defined(PX4_SPIDEV_BARO) || defined(PX4_SPIDEV_EXT_BARO)
device::Device *MS5611_spi_interface(ms5611::prom_u &prom_buf, bool external_bus);
class MS5611_SPI : public device::SPI
{
public:

View File

@ -48,6 +48,8 @@ public:
PX4Barometer(uint32_t device_id, uint8_t priority = ORB_PRIO_DEFAULT);
~PX4Barometer() override;
const sensor_baro_s &get() { return _sensor_baro_pub.get(); }
void set_device_type(uint8_t devtype);
void set_error_count(uint64_t error_count) { _sensor_baro_pub.get().error_count = error_count; }