drivers/barometer/mpc2520: MaierTek MPC2520 barometer support

- used in the Advanced Technolgy Labs (ATL) Mantis EDU
This commit is contained in:
Daniel Agar 2021-07-13 21:26:29 -04:00
parent 6ab8153f32
commit 5d06ef8256
8 changed files with 756 additions and 0 deletions

View File

@ -38,5 +38,7 @@ add_subdirectory(lps22hb)
#add_subdirectory(lps25h) # not ready for general inclusion
add_subdirectory(lps33hw)
#add_subdirectory(mpl3115a2) # not ready for general inclusion
add_subdirectory(maiertek)
add_subdirectory(ms5611)
#add_subdirectory(tcbp001ta) # only for users who really need this

View File

@ -0,0 +1,34 @@
############################################################################
#
# Copyright (c) 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.
#
############################################################################
add_subdirectory(mpc2520)

View File

@ -0,0 +1,46 @@
############################################################################
#
# Copyright (c) 2020-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__maiertek__mpc2520
MAIN mpc2520
COMPILE_FLAGS
SRCS
MaierTek_MPC2520_registers.hpp
mpc2520_main.cpp
MPC2520.cpp
MPC2520.hpp
DEPENDS
drivers_barometer
px4_work_queue
)

View File

@ -0,0 +1,350 @@
/****************************************************************************
*
* Copyright (c) 2020-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 "MPC2520.hpp"
using namespace time_literals;
static constexpr int32_t combine(uint8_t h, uint8_t m, uint8_t l)
{
// 24 bit sign extend
int32_t ret = (uint32_t)(h << 24) | (uint32_t)(m << 16) | (uint32_t)(l << 8);
return ret >> 8;
}
MPC2520::MPC2520(const I2CSPIDriverConfig &config) :
I2C(config),
I2CSPIDriver(config),
_px4_baro(get_device_id())
{
//_debug_enabled = true;
}
MPC2520::~MPC2520()
{
perf_free(_reset_perf);
perf_free(_bad_register_perf);
perf_free(_bad_transfer_perf);
}
int MPC2520::init()
{
int ret = I2C::init();
if (ret != PX4_OK) {
DEVICE_DEBUG("I2C::init failed (%i)", ret);
return ret;
}
return Reset() ? 0 : -1;
}
bool MPC2520::Reset()
{
_state = STATE::RESET;
ScheduleClear();
ScheduleNow();
return true;
}
void MPC2520::print_status()
{
I2CSPIDriverBase::print_status();
perf_print_counter(_reset_perf);
perf_print_counter(_bad_register_perf);
perf_print_counter(_bad_transfer_perf);
}
int MPC2520::probe()
{
const uint8_t ID = RegisterRead(Register::ID);
uint8_t PROD_ID = ID & 0xF0 >> 4; // Product ID Bits 7:4
if (PROD_ID != Product_ID) {
DEVICE_DEBUG("unexpected PROD_ID 0x%02x", PROD_ID);
return PX4_ERROR;
}
return PX4_OK;
}
void MPC2520::RunImpl()
{
const hrt_abstime now = hrt_absolute_time();
switch (_state) {
case STATE::RESET:
// RESET: SOFT_RST
RegisterWrite(Register::RESET, RESET_BIT::SOFT_RST);
_reset_timestamp = now;
_failure_count = 0;
_state = STATE::WAIT_FOR_RESET;
perf_count(_reset_perf);
ScheduleDelayed(50_ms); // Power On Reset: max 50ms
break;
case STATE::WAIT_FOR_RESET: {
// check MEAS_CFG SENSOR_RDY
const uint8_t ID = RegisterRead(Register::ID);
uint8_t PROD_ID = ID & 0xF0 >> 4; // Product ID Bits 7:4
if (PROD_ID == Product_ID) {
// if reset succeeded then read prom
_state = STATE::READ_PROM;
ScheduleDelayed(40_ms); // Time to coefficients are available.
} else {
// RESET not complete
if (hrt_elapsed_time(&_reset_timestamp) > 1000_ms) {
PX4_DEBUG("Reset failed, retrying");
_state = STATE::RESET;
ScheduleDelayed(100_ms);
} else {
PX4_DEBUG("Reset not complete, check again in 10 ms");
ScheduleDelayed(10_ms);
}
}
}
break;
case STATE::READ_PROM: {
uint8_t prom_buf[3] {};
uint8_t cmd = 0x10;
transfer(&cmd, 1, &prom_buf[0], 2);
_prom.c0 = (int16_t)prom_buf[0] << 4 | prom_buf[1] >> 4;
_prom.c0 = (_prom.c0 & 0x0800) ? (0xF000 | _prom.c0) : _prom.c0;
cmd = 0x11;
transfer(&cmd, 1, &prom_buf[0], 2);
_prom.c1 = (int16_t)(prom_buf[0] & 0x0F) << 8 | prom_buf[1];
_prom.c1 = (_prom.c1 & 0x0800) ? (0xF000 | _prom.c1) : _prom.c1;
cmd = 0x13;
transfer(&cmd, 1, &prom_buf[0], 3);
_prom.c00 = (int32_t)prom_buf[0] << 12 | (int32_t)prom_buf[1] << 4 | (int32_t)prom_buf[2] >> 4;
_prom.c00 = (_prom.c00 & 0x080000) ? (0xFFF00000 | _prom.c00) : _prom.c00;
cmd = 0x15;
transfer(&cmd, 1, &prom_buf[0], 3);
_prom.c10 = (int32_t)prom_buf[0] << 16 | (int32_t)prom_buf[1] << 8 | prom_buf[2];
_prom.c10 = (_prom.c10 & 0x080000) ? (0xFFF00000 | _prom.c10) : _prom.c10;
cmd = 0x18;
transfer(&cmd, 1, &prom_buf[0], 2);
_prom.c01 = (int16_t)prom_buf[0] << 8 | prom_buf[1];
cmd = 0x1A;
transfer(&cmd, 1, &prom_buf[0], 2);
_prom.c11 = (int16_t)prom_buf[0] << 8 | prom_buf[1];
cmd = 0x1C;
transfer(&cmd, 1, &prom_buf[0], 2);
_prom.c20 = (int16_t)prom_buf[0] << 8 | prom_buf[1];
cmd = 0x1E;
transfer(&cmd, 1, &prom_buf[0], 2);
_prom.c21 = (int16_t)prom_buf[0] << 8 | prom_buf[1];
cmd = 0x20;
transfer(&cmd, 1, &prom_buf[0], 2);
_prom.c30 = (int16_t)prom_buf[0] << 8 | prom_buf[1];
_state = STATE::CONFIGURE;
ScheduleDelayed(10_ms);
}
break;
case STATE::CONFIGURE:
if (Configure()) {
// if configure succeeded then start measurement cycle
_state = STATE::READ;
ScheduleOnInterval(1000000 / 32); // 32 Hz
} else {
// CONFIGURE not complete
if (hrt_elapsed_time(&_reset_timestamp) > 1000_ms) {
PX4_DEBUG("Configure failed, resetting");
_state = STATE::RESET;
} else {
PX4_DEBUG("Configure failed, retrying");
}
ScheduleDelayed(100_ms);
}
break;
case STATE::READ: {
bool success = false;
// read temperature first
struct TransferBuffer {
uint8_t PSR_B2;
uint8_t PSR_B1;
uint8_t PSR_B0;
uint8_t TMP_B2;
uint8_t TMP_B1;
uint8_t TMP_B0;
} buffer{};
uint8_t cmd = static_cast<uint8_t>(Register::PSR_B2);
if (transfer(&cmd, 1, (uint8_t *)&buffer, sizeof(buffer)) == PX4_OK) {
int32_t Traw = (int32_t)(buffer.TMP_B2 << 16) | (int32_t)(buffer.TMP_B1 << 8) | (int32_t)buffer.TMP_B0;
Traw = (Traw & 0x800000) ? (0xFF000000 | Traw) : Traw;
static constexpr float kT = 7864320; // temperature 8 times oversampling
float Traw_sc = static_cast<float>(Traw) / kT;
float Tcomp = _prom.c0 * 0.5f + _prom.c1 * Traw_sc;
_px4_baro.set_temperature(Tcomp);
int32_t Praw = (int32_t)(buffer.PSR_B2 << 16) | (int32_t)(buffer.PSR_B1 << 8) | (int32_t)buffer.PSR_B1;
Praw = (Praw & 0x800000) ? (0xFF000000 | Praw) : Praw;
static constexpr float kP = 7864320; // pressure 8 times oversampling
float Praw_sc = static_cast<float>(Praw) / kP;
// Calculate compensated measurement results.
float Pcomp = _prom.c00 + Praw_sc * (_prom.c10 + Praw_sc * (_prom.c20 + Praw_sc * _prom.c30)) + Traw_sc * _prom.c01 +
Traw_sc * Praw_sc * (_prom.c11 + Praw_sc * _prom.c21);
float pressure_mbar = Pcomp / 100.0f; // convert to millibar
_px4_baro.update(now, pressure_mbar);
success = true;
if (_failure_count > 0) {
_failure_count--;
}
} else {
perf_count(_bad_transfer_perf);
}
if (!success) {
_failure_count++;
// full reset if things are failing consistently
if (_failure_count > 10) {
Reset();
return;
}
}
if (!success || hrt_elapsed_time(&_last_config_check_timestamp) > 100_ms) {
// check configuration registers periodically or immediately following any failure
if (RegisterCheck(_register_cfg[_checked_register])) {
_last_config_check_timestamp = now;
_checked_register = (_checked_register + 1) % size_register_cfg;
} else {
// register check failed, force reset
perf_count(_bad_register_perf);
Reset();
return;
}
}
}
break;
}
}
bool MPC2520::Configure()
{
// first set and clear all configured register bits
for (const auto &reg_cfg : _register_cfg) {
RegisterSetAndClearBits(reg_cfg.reg, reg_cfg.set_bits, reg_cfg.clear_bits);
}
// now check that all are configured
bool success = true;
for (const auto &reg_cfg : _register_cfg) {
if (!RegisterCheck(reg_cfg)) {
success = false;
}
}
return success;
}
bool MPC2520::RegisterCheck(const register_config_t &reg_cfg)
{
bool success = true;
const uint8_t reg_value = RegisterRead(reg_cfg.reg);
if (reg_cfg.set_bits && ((reg_value & reg_cfg.set_bits) != reg_cfg.set_bits)) {
PX4_DEBUG("0x%02hhX: 0x%02hhX (0x%02hhX not set)", (uint8_t)reg_cfg.reg, reg_value, reg_cfg.set_bits);
success = false;
}
if (reg_cfg.clear_bits && ((reg_value & reg_cfg.clear_bits) != 0)) {
PX4_DEBUG("0x%02hhX: 0x%02hhX (0x%02hhX not cleared)", (uint8_t)reg_cfg.reg, reg_value, reg_cfg.clear_bits);
success = false;
}
return success;
}
uint8_t MPC2520::RegisterRead(Register reg)
{
const uint8_t cmd = static_cast<uint8_t>(reg);
uint8_t buffer{};
transfer(&cmd, 1, &buffer, 1);
return buffer;
}
void MPC2520::RegisterWrite(Register reg, uint8_t value)
{
uint8_t buffer[2] { (uint8_t)reg, value };
transfer(buffer, sizeof(buffer), nullptr, 0);
}
void MPC2520::RegisterSetAndClearBits(Register reg, uint8_t setbits, uint8_t clearbits)
{
const uint8_t orig_val = RegisterRead(reg);
uint8_t val = (orig_val & ~clearbits) | setbits;
if (orig_val != val) {
RegisterWrite(reg, val);
}
}

View File

@ -0,0 +1,120 @@
/****************************************************************************
*
* Copyright (c) 2020-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.
*
****************************************************************************/
#pragma once
#include "MaierTek_MPC2520_registers.hpp"
#include <drivers/drv_hrt.h>
#include <lib/drivers/device/i2c.h>
#include <lib/drivers/barometer/PX4Barometer.hpp>
#include <lib/perf/perf_counter.h>
#include <px4_platform_common/i2c_spi_buses.h>
using namespace MaierTek_MPC2520;
class MPC2520 : public device::I2C, public I2CSPIDriver<MPC2520>
{
public:
MPC2520(const I2CSPIDriverConfig &config);
~MPC2520() override;
static void print_usage();
void RunImpl();
int init() override;
void print_status() override;
private:
// Sensor Configuration
struct register_config_t {
Register reg;
uint8_t set_bits{0};
uint8_t clear_bits{0};
};
int probe() override;
bool Reset();
bool Configure();
bool RegisterCheck(const register_config_t &reg_cfg);
uint8_t RegisterRead(Register reg);
void RegisterWrite(Register reg, uint8_t value);
void RegisterSetAndClearBits(Register reg, uint8_t setbits, uint8_t clearbits);
PX4Barometer _px4_baro;
perf_counter_t _bad_register_perf{perf_alloc(PC_COUNT, MODULE_NAME": bad register")};
perf_counter_t _bad_transfer_perf{perf_alloc(PC_COUNT, MODULE_NAME": bad transfer")};
perf_counter_t _reset_perf{perf_alloc(PC_COUNT, MODULE_NAME": reset")};
hrt_abstime _reset_timestamp{0};
hrt_abstime _last_config_check_timestamp{0};
int _failure_count{0};
#pragma pack(push,1)
struct prom_s {
int16_t c0;
int16_t c1;
int32_t c00;
int32_t c10;
int16_t c01;
int16_t c11;
int16_t c20;
int16_t c21;
int16_t c30;
} _prom{};
#pragma pack(pop)
enum class STATE : uint8_t {
RESET,
WAIT_FOR_RESET,
READ_PROM,
CONFIGURE,
READ,
} _state{STATE::RESET};
uint8_t _checked_register{0};
static constexpr uint8_t size_register_cfg{4};
register_config_t _register_cfg[size_register_cfg] {
// Register | Set bits, Clear bits
{ Register::PRS_CFG, PRS_CFG_BIT::PM_RATE_32_SET | PRS_CFG_BIT::PM_PRC_8_SET, PRS_CFG_BIT::PM_RATE_32_CLEAR | PRS_CFG_BIT::PM_PRC_8_CLEAR },
{ Register::TMP_CFG, TMP_CFG_BIT::TMP_EXT | TMP_CFG_BIT::TMP_RATE_32_SET | TMP_CFG_BIT::TMP_PRC_8_SET, TMP_CFG_BIT::TMP_RATE_32_CLEAR | TMP_CFG_BIT::TMP_PRC_8_CLEAR },
{ Register::MEAS_CFG, MEAS_CFG_BIT::MEAS_CTRL_CONT_PRES_TEMP, 0 },
{ Register::CFG_REG, 0, CFG_REG_BIT::T_SHIFT | CFG_REG_BIT::P_SHIFT },
};
};

View File

@ -0,0 +1,126 @@
/****************************************************************************
*
* Copyright (c) 2020-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.
*
****************************************************************************/
/**
* @file MaierTek_MPC2520_registers.hpp
*
* MaierTek MPC2520 registers.
*
*/
#pragma once
#include <cstdint>
// TODO: move to a central header
static constexpr uint8_t Bit0 = (1 << 0);
static constexpr uint8_t Bit1 = (1 << 1);
static constexpr uint8_t Bit2 = (1 << 2);
static constexpr uint8_t Bit3 = (1 << 3);
static constexpr uint8_t Bit4 = (1 << 4);
static constexpr uint8_t Bit5 = (1 << 5);
static constexpr uint8_t Bit6 = (1 << 6);
static constexpr uint8_t Bit7 = (1 << 7);
namespace MaierTek_MPC2520
{
static constexpr uint32_t I2C_SPEED = 400 * 1000; // 400 kHz I2C serial interface
static constexpr uint8_t I2C_ADDRESS_DEFAULT = 0x76;
static constexpr uint8_t Product_ID = 0x0;
static constexpr uint8_t Revision_ID = 0x0;
enum class Register : uint8_t {
PSR_B2 = 0x00, // PSR[23:16] (r)
PSR_B1 = 0x01, // PSR[15:8] (r)
PSR_B0 = 0x02, // PSR[7:0] (r)
TMP_B2 = 0x03, // TMP[23:16] (r)
TMP_B1 = 0x04, // TMP[15:8] (r)
TMP_B0 = 0x05, // TMP[7:0] (r)
PRS_CFG = 0x06,
TMP_CFG = 0x07,
MEAS_CFG = 0x08,
CFG_REG = 0x09,
RESET = 0x0C,
ID = 0x0D, // PROD_ID [3:0] (r) REV_ID [3:0] (r)
COEF = 0x10,
};
// PRS_CFG
enum PRS_CFG_BIT : uint8_t {
// PM_RATE[6:4]
PM_RATE_32_SET = Bit6 | Bit4, // 101 - 32 measurements pr. sec.
PM_RATE_32_CLEAR = Bit5,
// PM_PRC[3:0]
PM_PRC_8_SET = Bit1 | Bit0, // 0011 - 8 times.
PM_PRC_8_CLEAR = Bit3 | Bit2,
};
// TMP_CFG
enum TMP_CFG_BIT : uint8_t {
TMP_EXT = Bit7,
// TMP_RATE[6:4]
TMP_RATE_32_SET = Bit6 | Bit4, // 101 - 32 measurements pr. sec.
TMP_RATE_32_CLEAR = Bit5,
// PM_PRC[2:0]
TMP_PRC_8_SET = Bit1 | Bit0, // 011 - 8 times.
TMP_PRC_8_CLEAR = Bit2,
};
// MEAS_CFG
enum MEAS_CFG_BIT : uint8_t {
COEF_RDY = Bit7,
SENSOR_RDY = Bit6,
TMP_RDY = Bit5,
PRS_RDY = Bit4,
MEAS_CTRL_CONT_PRES_TEMP = Bit2 | Bit1 | Bit0, // 111 - Continuous pressure and temperature measurement
};
// RESET
enum RESET_BIT : uint8_t {
SOFT_RST = Bit3 | Bit0, // Write '1001' to generate a soft reset.
};
// CFG_REG
enum CFG_REG_BIT : uint8_t {
T_SHIFT = Bit3, // Temperature result bit-shift, Note: Must be set to '1' when the oversampling rate is >8 times.
P_SHIFT = Bit2, // Pressure result bit-shift, Note: Must be set to '1' when the oversampling rate is >8 times.
};
} // namespace MaierTek_MPC2520

View File

@ -0,0 +1,77 @@
/****************************************************************************
*
* Copyright (c) 2020-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 "MPC2520.hpp"
#include <px4_platform_common/getopt.h>
#include <px4_platform_common/module.h>
void MPC2520::print_usage()
{
PRINT_MODULE_USAGE_NAME("mpc2520", "driver");
PRINT_MODULE_USAGE_SUBCATEGORY("baro");
PRINT_MODULE_USAGE_COMMAND("start");
PRINT_MODULE_USAGE_PARAMS_I2C_SPI_DRIVER(true, false);
PRINT_MODULE_USAGE_PARAMS_I2C_ADDRESS(0x76);
PRINT_MODULE_USAGE_DEFAULT_COMMANDS();
}
extern "C" int mpc2520_main(int argc, char *argv[])
{
using ThisDriver = MPC2520;
BusCLIArguments cli{true, false};
cli.i2c_address = I2C_ADDRESS_DEFAULT;
cli.default_i2c_frequency = I2C_SPEED;
const char *verb = cli.parseDefaultArguments(argc, argv);
if (!verb) {
ThisDriver::print_usage();
return -1;
}
BusInstanceIterator iterator(MODULE_NAME, cli, DRV_BARO_DEVTYPE_MPC2520);
if (!strcmp(verb, "start")) {
return ThisDriver::module_start(cli, iterator);
} else if (!strcmp(verb, "stop")) {
return ThisDriver::module_stop(iterator);
} else if (!strcmp(verb, "status")) {
return ThisDriver::module_status(iterator);
}
ThisDriver::print_usage();
return -1;
}

View File

@ -118,6 +118,7 @@
#define DRV_IMU_DEVTYPE_ADIS16470 0x58
#define DRV_IMU_DEVTYPE_ADIS16477 0x59
#define DRV_BARO_DEVTYPE_MPC2520 0x5F
#define DRV_BARO_DEVTYPE_LPS22HB 0x60
#define DRV_ACC_DEVTYPE_LSM303AGR 0x61