mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-23 14:47:44 +08:00
drivers/differential_pressure: split ms4515 and ms4525
This commit is contained in:
@@ -24,7 +24,7 @@ if ms5525 start -X
|
||||
then
|
||||
fi
|
||||
|
||||
if ms4525_airspeed start -X
|
||||
if ms4525 start -X
|
||||
then
|
||||
fi
|
||||
|
||||
|
||||
@@ -11,7 +11,7 @@ lps22hb -s start
|
||||
|
||||
lsm303agr -s -R 4 start
|
||||
|
||||
ms4525_airspeed -T 4515 -I -b 3 start
|
||||
ms4515 -I -b 3 start
|
||||
|
||||
if ! param greater SENS_EN_PMW3901 0
|
||||
then
|
||||
|
||||
@@ -36,7 +36,7 @@ board_adc start
|
||||
battery_status start
|
||||
|
||||
gps start -d /dev/spidev0.0 -i spi -p ubx
|
||||
ms4525_airspeed start -X
|
||||
ms4525 start -X
|
||||
rc_update start
|
||||
sensors start
|
||||
commander start
|
||||
|
||||
@@ -32,6 +32,7 @@
|
||||
############################################################################
|
||||
|
||||
add_subdirectory(ets)
|
||||
add_subdirectory(ms4515)
|
||||
add_subdirectory(ms4525)
|
||||
add_subdirectory(ms5525)
|
||||
add_subdirectory(sdp3x)
|
||||
add_subdirectory(sdp3x)
|
||||
|
||||
@@ -0,0 +1,43 @@
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2015-2021 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__differential_pressure__ms4515
|
||||
MAIN ms4515
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
MS4515.cpp
|
||||
MS4515.hpp
|
||||
DEPENDS
|
||||
mathlib
|
||||
px4_work_queue
|
||||
)
|
||||
@@ -0,0 +1,275 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2013-2021 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 "MS4515.hpp"
|
||||
|
||||
/* Register address */
|
||||
#define ADDR_READ_MR 0x00 /* write to this address to start conversion */
|
||||
|
||||
/* Measurement rate is 100Hz */
|
||||
#define MEAS_RATE 100
|
||||
#define CONVERSION_INTERVAL (1000000 / MEAS_RATE) /* microseconds */
|
||||
|
||||
MS4515::MS4515(I2CSPIBusOption bus_option, const int bus, int bus_frequency, int address) :
|
||||
I2C(DRV_DIFF_PRESS_DEVTYPE_MS4515, MODULE_NAME, bus, address, bus_frequency),
|
||||
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(get_device_id()), bus_option, bus, address)
|
||||
{
|
||||
}
|
||||
|
||||
MS4515::~MS4515()
|
||||
{
|
||||
perf_free(_sample_perf);
|
||||
perf_free(_comms_errors);
|
||||
}
|
||||
|
||||
int MS4515::probe()
|
||||
{
|
||||
uint8_t cmd = 0;
|
||||
int ret = transfer(&cmd, 1, nullptr, 0);
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
int MS4515::measure()
|
||||
{
|
||||
// Send the command to begin a measurement.
|
||||
uint8_t cmd = 0;
|
||||
int ret = transfer(&cmd, 1, nullptr, 0);
|
||||
|
||||
if (OK != ret) {
|
||||
perf_count(_comms_errors);
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
int MS4515::collect()
|
||||
{
|
||||
/* read from the sensor */
|
||||
perf_begin(_sample_perf);
|
||||
|
||||
const hrt_abstime timestamp_sample = hrt_absolute_time();
|
||||
|
||||
uint8_t val[4] {};
|
||||
int ret = transfer(nullptr, 0, &val[0], 4);
|
||||
|
||||
if (ret < 0) {
|
||||
perf_count(_comms_errors);
|
||||
perf_end(_sample_perf);
|
||||
return ret;
|
||||
}
|
||||
|
||||
uint8_t status = (val[0] & 0xC0) >> 6;
|
||||
|
||||
switch (status) {
|
||||
case 0:
|
||||
// Normal Operation. Good Data Packet
|
||||
break;
|
||||
|
||||
case 1:
|
||||
// Reserved
|
||||
return -EAGAIN;
|
||||
|
||||
case 2:
|
||||
// Stale Data. Data has been fetched since last measurement cycle.
|
||||
return -EAGAIN;
|
||||
|
||||
case 3:
|
||||
// Fault Detected
|
||||
perf_count(_comms_errors);
|
||||
perf_end(_sample_perf);
|
||||
return -EAGAIN;
|
||||
}
|
||||
|
||||
/* mask the used bits */
|
||||
int16_t dp_raw = (0x3FFF & ((val[0] << 8) + val[1]));
|
||||
int16_t dT_raw = (0xFFE0 & ((val[2] << 8) + val[3])) >> 5;
|
||||
|
||||
// dT max is almost certainly an invalid reading
|
||||
if (dT_raw == 2047) {
|
||||
perf_count(_comms_errors);
|
||||
return -EAGAIN;
|
||||
}
|
||||
|
||||
// only publish changes
|
||||
if ((dp_raw != _dp_raw_prev) || (dT_raw != _dT_raw_prev)) {
|
||||
|
||||
_dp_raw_prev = dp_raw;
|
||||
_dT_raw_prev = dT_raw;
|
||||
|
||||
float temperature = ((200.0f * dT_raw) / 2047) - 50;
|
||||
|
||||
// Calculate differential pressure. As its centered around 8000
|
||||
// and can go positive or negative
|
||||
const float P_min = -1.0f;
|
||||
const float P_max = 1.0f;
|
||||
const float IN_H20_to_Pa = 248.84f;
|
||||
/*
|
||||
this equation is an inversion of the equation in the
|
||||
pressure transfer function figure on page 4 of the datasheet
|
||||
|
||||
We negate the result so that positive differential pressures
|
||||
are generated when the bottom port is used as the static
|
||||
port on the pitot and top port is used as the dynamic port
|
||||
*/
|
||||
float diff_press_PSI = -((dp_raw - 0.1f * 16383) * (P_max - P_min) / (0.8f * 16383) + P_min);
|
||||
float diff_press_pa_raw = diff_press_PSI * IN_H20_to_Pa;
|
||||
|
||||
/*
|
||||
With the above calculation the MS4525 sensor will produce a
|
||||
positive number when the top port is used as a dynamic port
|
||||
and bottom port is used as the static port
|
||||
*/
|
||||
sensor_differential_pressure_s report{};
|
||||
report.timestamp_sample = timestamp_sample;
|
||||
report.device_id = get_device_id();
|
||||
report.differential_pressure_pa = diff_press_pa_raw;
|
||||
report.temperature = temperature;
|
||||
report.error_count = perf_event_count(_comms_errors);
|
||||
report.timestamp = hrt_absolute_time();
|
||||
_differential_pressure_pub.publish(report);
|
||||
}
|
||||
|
||||
perf_end(_sample_perf);
|
||||
|
||||
return PX4_OK;
|
||||
}
|
||||
|
||||
void MS4515::RunImpl()
|
||||
{
|
||||
int ret;
|
||||
|
||||
/* collection phase? */
|
||||
if (_collect_phase) {
|
||||
|
||||
/* perform collection */
|
||||
ret = collect();
|
||||
|
||||
if (OK != ret) {
|
||||
/* restart the measurement state machine */
|
||||
_collect_phase = false;
|
||||
_sensor_ok = false;
|
||||
ScheduleNow();
|
||||
return;
|
||||
}
|
||||
|
||||
/* next phase is measurement */
|
||||
_collect_phase = false;
|
||||
|
||||
/*
|
||||
* Is there a collect->measure gap?
|
||||
*/
|
||||
if (_measure_interval > CONVERSION_INTERVAL) {
|
||||
|
||||
/* schedule a fresh cycle call when we are ready to measure again */
|
||||
ScheduleDelayed(_measure_interval - CONVERSION_INTERVAL);
|
||||
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
/* measurement phase */
|
||||
ret = measure();
|
||||
|
||||
if (PX4_OK != ret) {
|
||||
DEVICE_DEBUG("measure error");
|
||||
}
|
||||
|
||||
_sensor_ok = (ret == OK);
|
||||
|
||||
/* next phase is collection */
|
||||
_collect_phase = true;
|
||||
|
||||
/* schedule a fresh cycle call when the measurement is done */
|
||||
ScheduleDelayed(CONVERSION_INTERVAL);
|
||||
}
|
||||
|
||||
I2CSPIDriverBase *MS4515::instantiate(const BusCLIArguments &cli, const BusInstanceIterator &iterator,
|
||||
int runtime_instance)
|
||||
{
|
||||
MS4515 *instance = new MS4515(iterator.configuredBusOption(), iterator.bus(), cli.bus_frequency, cli.i2c_address);
|
||||
|
||||
if (instance == nullptr) {
|
||||
PX4_ERR("alloc failed");
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
if (instance->init() != PX4_OK) {
|
||||
delete instance;
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
instance->ScheduleNow();
|
||||
return instance;
|
||||
}
|
||||
|
||||
void MS4515::print_usage()
|
||||
{
|
||||
PRINT_MODULE_USAGE_NAME("ms4515", "driver");
|
||||
PRINT_MODULE_USAGE_SUBCATEGORY("airspeed_sensor");
|
||||
PRINT_MODULE_USAGE_COMMAND("start");
|
||||
PRINT_MODULE_USAGE_PARAMS_I2C_SPI_DRIVER(true, false);
|
||||
PRINT_MODULE_USAGE_DEFAULT_COMMANDS();
|
||||
}
|
||||
|
||||
extern "C" __EXPORT int ms4515_main(int argc, char *argv[])
|
||||
{
|
||||
using ThisDriver = MS4515;
|
||||
BusCLIArguments cli{true, false};
|
||||
cli.default_i2c_frequency = 100000;
|
||||
cli.i2c_address = I2C_ADDRESS_MS4515DO;
|
||||
|
||||
const char *verb = cli.optarg();
|
||||
|
||||
if (!verb) {
|
||||
ThisDriver::print_usage();
|
||||
return -1;
|
||||
}
|
||||
|
||||
BusInstanceIterator iterator(MODULE_NAME, cli, DRV_DIFF_PRESS_DEVTYPE_MS4515);
|
||||
|
||||
if (!strcmp(verb, "start")) {
|
||||
return ThisDriver::module_start(cli, iterator);
|
||||
}
|
||||
|
||||
if (!strcmp(verb, "stop")) {
|
||||
return ThisDriver::module_stop(iterator);
|
||||
}
|
||||
|
||||
if (!strcmp(verb, "status")) {
|
||||
return ThisDriver::module_status(iterator);
|
||||
}
|
||||
|
||||
ThisDriver::print_usage();
|
||||
return -1;
|
||||
}
|
||||
@@ -0,0 +1,89 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2013, 2014 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
*
|
||||
* Driver for the MEAS Spec series connected via I2C.
|
||||
*
|
||||
* Supported sensors:
|
||||
*
|
||||
* - MS4515DO
|
||||
*
|
||||
* Interface application notes:
|
||||
*
|
||||
* - Interfacing to MEAS Digital Pressure Modules (http://www.meas-spec.com/downloads/Interfacing_to_MEAS_Digital_Pressure_Modules.pdf)
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <px4_platform_common/getopt.h>
|
||||
#include <px4_platform_common/module.h>
|
||||
#include <px4_platform_common/i2c_spi_buses.h>
|
||||
#include <drivers/device/i2c.h>
|
||||
#include <uORB/topics/sensor_differential_pressure.h>
|
||||
#include <uORB/PublicationMulti.hpp>
|
||||
|
||||
#define I2C_ADDRESS_MS4515DO 0x46 /* I2C bus address is 1010001x */
|
||||
|
||||
class MS4515 : public device::I2C, public I2CSPIDriver<MS4515>
|
||||
{
|
||||
public:
|
||||
MS4515(I2CSPIBusOption bus_option, const int bus, int bus_frequency, int address = I2C_ADDRESS_MS4515DO);
|
||||
|
||||
virtual ~MS4515();
|
||||
|
||||
static I2CSPIDriverBase *instantiate(const BusCLIArguments &cli, const BusInstanceIterator &iterator,
|
||||
int runtime_instance);
|
||||
static void print_usage();
|
||||
|
||||
void RunImpl();
|
||||
|
||||
private:
|
||||
int probe() override;
|
||||
|
||||
int measure();
|
||||
int collect();
|
||||
|
||||
bool _sensor_ok{false};
|
||||
int _measure_interval{0};
|
||||
bool _collect_phase{false};
|
||||
unsigned _conversion_interval{0};
|
||||
|
||||
int16_t _dp_raw_prev{0};
|
||||
int16_t _dT_raw_prev{0};
|
||||
|
||||
uORB::PublicationMulti<sensor_differential_pressure_s> _differential_pressure_pub{ORB_ID(sensor_differential_pressure)};
|
||||
|
||||
perf_counter_t _sample_perf{perf_alloc(PC_ELAPSED, MODULE_NAME": read")};
|
||||
perf_counter_t _comms_errors{perf_alloc(PC_COUNT, MODULE_NAME": com err")};
|
||||
};
|
||||
@@ -31,11 +31,12 @@
|
||||
#
|
||||
############################################################################
|
||||
px4_add_module(
|
||||
MODULE drivers__ms4525_airspeed
|
||||
MAIN ms4525_airspeed
|
||||
MODULE drivers__differential_pressure__ms4525
|
||||
MAIN ms4525
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
ms4525_airspeed.cpp
|
||||
MS4525.cpp
|
||||
MS4525.hpp
|
||||
DEPENDS
|
||||
mathlib
|
||||
px4_work_queue
|
||||
|
||||
+31
-100
@@ -31,39 +31,7 @@
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file meas_airspeed.cpp
|
||||
* @author Lorenz Meier
|
||||
* @author Sarthak Kaingade
|
||||
* @author Simon Wilks
|
||||
* @author Thomas Gubler
|
||||
*
|
||||
* Driver for the MEAS Spec series connected via I2C.
|
||||
*
|
||||
* Supported sensors:
|
||||
*
|
||||
* - MS4525DO (http://www.meas-spec.com/downloads/MS4525DO.pdf)
|
||||
*
|
||||
* Interface application notes:
|
||||
*
|
||||
* - Interfacing to MEAS Digital Pressure Modules (http://www.meas-spec.com/downloads/Interfacing_to_MEAS_Digital_Pressure_Modules.pdf)
|
||||
*/
|
||||
|
||||
#include <px4_platform_common/getopt.h>
|
||||
#include <px4_platform_common/module.h>
|
||||
#include <px4_platform_common/i2c_spi_buses.h>
|
||||
#include <drivers/device/i2c.h>
|
||||
#include <uORB/topics/sensor_differential_pressure.h>
|
||||
#include <uORB/PublicationMulti.hpp>
|
||||
|
||||
enum MS_DEVICE_TYPE {
|
||||
DEVICE_TYPE_MS4515 = 4515,
|
||||
DEVICE_TYPE_MS4525 = 4525
|
||||
};
|
||||
|
||||
/* I2C bus address is 1010001x */
|
||||
#define I2C_ADDRESS_MS4515DO 0x46
|
||||
#define I2C_ADDRESS_MS4525DO 0x28 /**< 7-bit address. Depends on the order code (this is for code "I") */
|
||||
#include "MS4525.hpp"
|
||||
|
||||
/* Register address */
|
||||
#define ADDR_READ_MR 0x00 /* write to this address to start conversion */
|
||||
@@ -72,44 +40,27 @@ enum MS_DEVICE_TYPE {
|
||||
#define MEAS_RATE 100
|
||||
#define CONVERSION_INTERVAL (1000000 / MEAS_RATE) /* microseconds */
|
||||
|
||||
class MEASAirspeed : public device::I2C, public I2CSPIDriver<MEASAirspeed>
|
||||
{
|
||||
public:
|
||||
MEASAirspeed(I2CSPIBusOption bus_option, const int bus, int bus_frequency, int address = I2C_ADDRESS_MS4525DO);
|
||||
|
||||
virtual ~MEASAirspeed() = default;
|
||||
|
||||
static I2CSPIDriverBase *instantiate(const BusCLIArguments &cli, const BusInstanceIterator &iterator,
|
||||
int runtime_instance);
|
||||
static void print_usage();
|
||||
|
||||
void RunImpl();
|
||||
|
||||
private:
|
||||
int measure();
|
||||
int collect();
|
||||
|
||||
bool _sensor_ok{false};
|
||||
int _measure_interval{0};
|
||||
bool _collect_phase{false};
|
||||
unsigned _conversion_interval{0};
|
||||
|
||||
int16_t _dp_raw_prev{0};
|
||||
int16_t _dT_raw_prev{0};
|
||||
|
||||
uORB::PublicationMulti<sensor_differential_pressure_s> _differential_pressure_pub{ORB_ID(sensor_differential_pressure)};
|
||||
|
||||
perf_counter_t _sample_perf{perf_alloc(PC_ELAPSED, MODULE_NAME": read")};
|
||||
perf_counter_t _comms_errors{perf_alloc(PC_COUNT, MODULE_NAME": com err")};
|
||||
};
|
||||
|
||||
MEASAirspeed::MEASAirspeed(I2CSPIBusOption bus_option, const int bus, int bus_frequency, int address) :
|
||||
MS4525::MS4525(I2CSPIBusOption bus_option, const int bus, int bus_frequency, int address) :
|
||||
I2C(DRV_DIFF_PRESS_DEVTYPE_MS4525, MODULE_NAME, bus, address, bus_frequency),
|
||||
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(get_device_id()), bus_option, bus, address)
|
||||
{
|
||||
}
|
||||
|
||||
int MEASAirspeed::measure()
|
||||
MS4525::~MS4525()
|
||||
{
|
||||
perf_free(_sample_perf);
|
||||
perf_free(_comms_errors);
|
||||
}
|
||||
|
||||
int MS4525::probe()
|
||||
{
|
||||
uint8_t cmd = 0;
|
||||
int ret = transfer(&cmd, 1, nullptr, 0);
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
int MS4525::measure()
|
||||
{
|
||||
// Send the command to begin a measurement.
|
||||
uint8_t cmd = 0;
|
||||
@@ -122,15 +73,14 @@ int MEASAirspeed::measure()
|
||||
return ret;
|
||||
}
|
||||
|
||||
int MEASAirspeed::collect()
|
||||
int MS4525::collect()
|
||||
{
|
||||
/* read from the sensor */
|
||||
uint8_t val[4] {};
|
||||
|
||||
perf_begin(_sample_perf);
|
||||
|
||||
const hrt_abstime timestamp_sample = hrt_absolute_time();
|
||||
|
||||
uint8_t val[4] {};
|
||||
int ret = transfer(nullptr, 0, &val[0], 4);
|
||||
|
||||
if (ret < 0) {
|
||||
@@ -172,7 +122,7 @@ int MEASAirspeed::collect()
|
||||
}
|
||||
|
||||
// only publish changes
|
||||
if ((dp_raw != _dp_raw_prev) && (dT_raw != _dT_raw_prev)) {
|
||||
if ((dp_raw != _dp_raw_prev) || (dT_raw != _dT_raw_prev)) {
|
||||
|
||||
_dp_raw_prev = dp_raw;
|
||||
_dT_raw_prev = dT_raw;
|
||||
@@ -215,7 +165,7 @@ int MEASAirspeed::collect()
|
||||
return PX4_OK;
|
||||
}
|
||||
|
||||
void MEASAirspeed::RunImpl()
|
||||
void MS4525::RunImpl()
|
||||
{
|
||||
int ret;
|
||||
|
||||
@@ -264,11 +214,10 @@ void MEASAirspeed::RunImpl()
|
||||
ScheduleDelayed(CONVERSION_INTERVAL);
|
||||
}
|
||||
|
||||
I2CSPIDriverBase *MEASAirspeed::instantiate(const BusCLIArguments &cli, const BusInstanceIterator &iterator,
|
||||
int runtime_instance)
|
||||
I2CSPIDriverBase *MS4525::instantiate(const BusCLIArguments &cli, const BusInstanceIterator &iterator,
|
||||
int runtime_instance)
|
||||
{
|
||||
MEASAirspeed *instance = new MEASAirspeed(iterator.configuredBusOption(), iterator.bus(), cli.bus_frequency,
|
||||
cli.i2c_address);
|
||||
MS4525 *instance = new MS4525(iterator.configuredBusOption(), iterator.bus(), cli.bus_frequency, cli.i2c_address);
|
||||
|
||||
if (instance == nullptr) {
|
||||
PX4_ERR("alloc failed");
|
||||
@@ -284,48 +233,30 @@ I2CSPIDriverBase *MEASAirspeed::instantiate(const BusCLIArguments &cli, const Bu
|
||||
return instance;
|
||||
}
|
||||
|
||||
void MEASAirspeed::print_usage()
|
||||
void MS4525::print_usage()
|
||||
{
|
||||
PRINT_MODULE_USAGE_NAME("ms4525_airspeed", "driver");
|
||||
PRINT_MODULE_USAGE_NAME("ms4525", "driver");
|
||||
PRINT_MODULE_USAGE_SUBCATEGORY("airspeed_sensor");
|
||||
PRINT_MODULE_USAGE_COMMAND("start");
|
||||
PRINT_MODULE_USAGE_PARAMS_I2C_SPI_DRIVER(true, false);
|
||||
PRINT_MODULE_USAGE_PARAM_STRING('T', "4525", "4525|4515", "Device type", true);
|
||||
PRINT_MODULE_USAGE_DEFAULT_COMMANDS();
|
||||
}
|
||||
|
||||
extern "C" __EXPORT int ms4525_airspeed_main(int argc, char *argv[])
|
||||
extern "C" __EXPORT int ms4525_main(int argc, char *argv[])
|
||||
{
|
||||
int ch;
|
||||
using ThisDriver = MEASAirspeed;
|
||||
using ThisDriver = MS4525;
|
||||
BusCLIArguments cli{true, false};
|
||||
cli.default_i2c_frequency = 100000;
|
||||
int device_type = DEVICE_TYPE_MS4525;
|
||||
cli.i2c_address = I2C_ADDRESS_MS4525DO;
|
||||
|
||||
while ((ch = cli.getopt(argc, argv, "T:")) != EOF) {
|
||||
switch (ch) {
|
||||
case 'T':
|
||||
device_type = atoi(cli.optarg());
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
const char *verb = cli.optarg();
|
||||
const char *verb = cli.parseDefaultArguments(argc, argv);
|
||||
|
||||
if (!verb) {
|
||||
ThisDriver::print_usage();
|
||||
return -1;
|
||||
}
|
||||
|
||||
if (device_type == DEVICE_TYPE_MS4525) {
|
||||
cli.i2c_address = I2C_ADDRESS_MS4525DO;
|
||||
|
||||
} else {
|
||||
cli.i2c_address = I2C_ADDRESS_MS4515DO;
|
||||
}
|
||||
|
||||
BusInstanceIterator iterator(MODULE_NAME, cli,
|
||||
DRV_DIFF_PRESS_DEVTYPE_MS4525);
|
||||
BusInstanceIterator iterator(MODULE_NAME, cli, DRV_DIFF_PRESS_DEVTYPE_MS4525);
|
||||
|
||||
if (!strcmp(verb, "start")) {
|
||||
return ThisDriver::module_start(cli, iterator);
|
||||
@@ -0,0 +1,94 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2013, 2014 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file MS4525.hpp
|
||||
* @author Lorenz Meier
|
||||
* @author Sarthak Kaingade
|
||||
* @author Simon Wilks
|
||||
* @author Thomas Gubler
|
||||
*
|
||||
* Driver for the MEAS Spec series connected via I2C.
|
||||
*
|
||||
* Supported sensors:
|
||||
*
|
||||
* - MS4525DO (http://www.meas-spec.com/downloads/MS4525DO.pdf)
|
||||
*
|
||||
* Interface application notes:
|
||||
*
|
||||
* - Interfacing to MEAS Digital Pressure Modules (http://www.meas-spec.com/downloads/Interfacing_to_MEAS_Digital_Pressure_Modules.pdf)
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <px4_platform_common/getopt.h>
|
||||
#include <px4_platform_common/module.h>
|
||||
#include <px4_platform_common/i2c_spi_buses.h>
|
||||
#include <drivers/device/i2c.h>
|
||||
#include <uORB/topics/sensor_differential_pressure.h>
|
||||
#include <uORB/PublicationMulti.hpp>
|
||||
|
||||
#define I2C_ADDRESS_MS4525DO 0x28 /**< 7-bit address. Depends on the order code (this is for code "I") */
|
||||
|
||||
class MS4525 : public device::I2C, public I2CSPIDriver<MS4525>
|
||||
{
|
||||
public:
|
||||
MS4525(I2CSPIBusOption bus_option, const int bus, int bus_frequency, int address = I2C_ADDRESS_MS4525DO);
|
||||
|
||||
virtual ~MS4525();
|
||||
|
||||
static I2CSPIDriverBase *instantiate(const BusCLIArguments &cli, const BusInstanceIterator &iterator,
|
||||
int runtime_instance);
|
||||
static void print_usage();
|
||||
|
||||
void RunImpl();
|
||||
|
||||
private:
|
||||
int probe() override;
|
||||
|
||||
int measure();
|
||||
int collect();
|
||||
|
||||
bool _sensor_ok{false};
|
||||
int _measure_interval{0};
|
||||
bool _collect_phase{false};
|
||||
unsigned _conversion_interval{0};
|
||||
|
||||
int16_t _dp_raw_prev{0};
|
||||
int16_t _dT_raw_prev{0};
|
||||
|
||||
uORB::PublicationMulti<sensor_differential_pressure_s> _differential_pressure_pub{ORB_ID(sensor_differential_pressure)};
|
||||
|
||||
perf_counter_t _sample_perf{perf_alloc(PC_ELAPSED, MODULE_NAME": read")};
|
||||
perf_counter_t _comms_errors{perf_alloc(PC_COUNT, MODULE_NAME": com err")};
|
||||
};
|
||||
@@ -101,13 +101,14 @@
|
||||
#define DRV_IMU_DEVTYPE_ST_LSM9DS1_AG 0x44
|
||||
#define DRV_MAG_DEVTYPE_ST_LSM9DS1_M 0x45
|
||||
#define DRV_DIFF_PRESS_DEVTYPE_ETS3 0x46
|
||||
#define DRV_DIFF_PRESS_DEVTYPE_MS4525 0x47
|
||||
#define DRV_DIFF_PRESS_DEVTYPE_MS5525 0x48
|
||||
#define DRV_DIFF_PRESS_DEVTYPE_SDP31 0x49
|
||||
#define DRV_DIFF_PRESS_DEVTYPE_SDP32 0x4A
|
||||
#define DRV_DIFF_PRESS_DEVTYPE_SDP33 0x4B
|
||||
#define DRV_BARO_DEVTYPE_LPS33HW 0x4C
|
||||
#define DRV_DIFF_PRESS_DEVTYPE_MS4515 0x47
|
||||
#define DRV_DIFF_PRESS_DEVTYPE_MS4525 0x48
|
||||
#define DRV_DIFF_PRESS_DEVTYPE_MS5525 0x49
|
||||
#define DRV_DIFF_PRESS_DEVTYPE_SDP31 0x4A
|
||||
#define DRV_DIFF_PRESS_DEVTYPE_SDP32 0x4B
|
||||
#define DRV_DIFF_PRESS_DEVTYPE_SDP33 0x4C
|
||||
|
||||
#define DRV_BARO_DEVTYPE_LPS33HW 0x50
|
||||
#define DRV_BARO_DEVTYPE_MPL3115A2 0x51
|
||||
#define DRV_ACC_DEVTYPE_FXOS8701C 0x52
|
||||
|
||||
|
||||
Reference in New Issue
Block a user