15 changed files with 924 additions and 1 deletions
@ -0,0 +1,34 @@ |
|||||||
|
############################################################################ |
||||||
|
# |
||||||
|
# Copyright (c) 2022 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(spl06) |
@ -0,0 +1,3 @@ |
|||||||
|
menu "Goertek" |
||||||
|
rsource "*/Kconfig" |
||||||
|
endmenu #Goertek |
@ -0,0 +1,46 @@ |
|||||||
|
############################################################################ |
||||||
|
# |
||||||
|
# Copyright (c) 2022 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__barometer__spl06 |
||||||
|
MAIN spl06 |
||||||
|
SRCS |
||||||
|
SPL06.cpp |
||||||
|
SPL06.hpp |
||||||
|
SPL06_I2C.cpp |
||||||
|
SPL06_SPI.cpp |
||||||
|
spl06_main.cpp |
||||||
|
DEPENDS |
||||||
|
drivers_barometer |
||||||
|
px4_work_queue |
||||||
|
) |
@ -0,0 +1,5 @@ |
|||||||
|
menuconfig DRIVERS_BAROMETER_GOERTEK_SPL06 |
||||||
|
bool "spl06" |
||||||
|
default n |
||||||
|
---help--- |
||||||
|
Enable support for spl06 |
@ -0,0 +1,243 @@ |
|||||||
|
/****************************************************************************
|
||||||
|
* |
||||||
|
* Copyright (c) 2022 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 "SPL06.hpp" |
||||||
|
|
||||||
|
SPL06::SPL06(const I2CSPIDriverConfig &config, spl06::ISPL06 *interface) : |
||||||
|
I2CSPIDriver(config), |
||||||
|
_px4_baro(interface->get_device_id()), |
||||||
|
_interface(interface), |
||||||
|
_sample_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": sample")), |
||||||
|
_measure_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": measure")), |
||||||
|
_comms_errors(perf_alloc(PC_COUNT, MODULE_NAME": comms errors")) |
||||||
|
{ |
||||||
|
} |
||||||
|
|
||||||
|
SPL06::~SPL06() |
||||||
|
{ |
||||||
|
// free perf counters
|
||||||
|
perf_free(_sample_perf); |
||||||
|
perf_free(_measure_perf); |
||||||
|
perf_free(_comms_errors); |
||||||
|
|
||||||
|
delete _interface; |
||||||
|
} |
||||||
|
|
||||||
|
/*
|
||||||
|
float |
||||||
|
SPL06::scale_factor(int oversampling_rate) |
||||||
|
{ |
||||||
|
float k; |
||||||
|
|
||||||
|
switch (oversampling_rate) { |
||||||
|
case 1: |
||||||
|
k = 524288.0f; |
||||||
|
break; |
||||||
|
|
||||||
|
case 2: |
||||||
|
k = 1572864.0f; |
||||||
|
break; |
||||||
|
|
||||||
|
case 4: |
||||||
|
k = 3670016.0f; |
||||||
|
break; |
||||||
|
|
||||||
|
case 8: |
||||||
|
k = 7864320.0f; |
||||||
|
break; |
||||||
|
|
||||||
|
case 16: |
||||||
|
k = 253952.0f; |
||||||
|
break; |
||||||
|
|
||||||
|
case 32: |
||||||
|
k = 516096.0f; |
||||||
|
break; |
||||||
|
|
||||||
|
case 64: |
||||||
|
k = 1040384.0f; |
||||||
|
break; |
||||||
|
|
||||||
|
case 128: |
||||||
|
k = 2088960.0f; |
||||||
|
break; |
||||||
|
|
||||||
|
default: |
||||||
|
k = 0; |
||||||
|
break; |
||||||
|
} |
||||||
|
|
||||||
|
return k; |
||||||
|
} |
||||||
|
*/ |
||||||
|
|
||||||
|
int |
||||||
|
SPL06::calibrate() |
||||||
|
{ |
||||||
|
uint8_t buf[18]; |
||||||
|
|
||||||
|
_interface->read(SPL06_ADDR_CAL, buf, sizeof(buf)); |
||||||
|
|
||||||
|
_cal.c0 = (uint16_t)buf[0] << 4 | (uint16_t)buf[1] >> 4; |
||||||
|
_cal.c0 = (_cal.c0 & 1 << 11) ? (0xf000 | _cal.c0) : _cal.c0; |
||||||
|
|
||||||
|
_cal.c1 = (uint16_t)(buf[1] & 0x0f) << 8 | (uint16_t)buf[2]; |
||||||
|
_cal.c1 = (_cal.c1 & 1 << 11) ? (0xf000 | _cal.c1) : _cal.c1; |
||||||
|
|
||||||
|
_cal.c00 = (uint32_t)buf[3] << 12 | (uint32_t)buf[4] << 4 | (uint16_t)buf[5] >> 4; |
||||||
|
_cal.c00 = (_cal.c00 & 1 << 19) ? (0xfff00000 | _cal.c00) : _cal.c00; |
||||||
|
|
||||||
|
_cal.c10 = (uint32_t)(buf[5] & 0x0f) << 16 | (uint32_t)buf[6] << 8 | (uint32_t)buf[7]; |
||||||
|
_cal.c10 = (_cal.c10 & 1 << 19) ? (0xfff00000 | _cal.c10) : _cal.c10; |
||||||
|
|
||||||
|
_cal.c01 = (uint16_t)buf[8] << 8 | buf[9]; |
||||||
|
_cal.c11 = (uint16_t)buf[10] << 8 | buf[11]; |
||||||
|
_cal.c20 = (uint16_t)buf[12] << 8 | buf[13]; |
||||||
|
_cal.c21 = (uint16_t)buf[14] << 8 | buf[15]; |
||||||
|
_cal.c30 = (uint16_t)buf[16] << 8 | buf[17]; |
||||||
|
|
||||||
|
// PX4_INFO("c0:%d \nc1:%d \nc00:%d \nc10:%d \nc01:%d \nc11:%d \nc20:%d \nc21:%d \nc30:%d\n",
|
||||||
|
// _cal.c0,_cal.c1,
|
||||||
|
// _cal.c00,_cal.c10,
|
||||||
|
// _cal.c01,_cal.c11,_cal.c20,_cal.c21,_cal.c30
|
||||||
|
// );
|
||||||
|
//PX4_DEBUG("c0:%f",_cal.c0);
|
||||||
|
return OK; |
||||||
|
} |
||||||
|
int |
||||||
|
SPL06::init() |
||||||
|
{ |
||||||
|
int8_t tries = 5; |
||||||
|
// reset sensor
|
||||||
|
_interface->set_reg(SPL06_VALUE_RESET, SPL06_ADDR_RESET); |
||||||
|
usleep(10000); |
||||||
|
|
||||||
|
// check id
|
||||||
|
if (_interface->get_reg(SPL06_ADDR_ID) != SPL06_VALUE_ID) { |
||||||
|
PX4_DEBUG("id of your baro is not: 0x%02x", SPL06_VALUE_ID); |
||||||
|
return -EIO; |
||||||
|
} |
||||||
|
|
||||||
|
while (tries--) { |
||||||
|
uint8_t meas_cfg = _interface->get_reg(SPL06_ADDR_MEAS_CFG); |
||||||
|
|
||||||
|
if (meas_cfg & (1 << 7) && meas_cfg & (1 << 6)) { |
||||||
|
break; |
||||||
|
} |
||||||
|
|
||||||
|
usleep(10000); |
||||||
|
} |
||||||
|
|
||||||
|
if (tries < 0) { |
||||||
|
PX4_DEBUG("spl06 cal failed"); |
||||||
|
return -EIO; |
||||||
|
} |
||||||
|
|
||||||
|
// get calibration and pre process them
|
||||||
|
calibrate(); |
||||||
|
|
||||||
|
// set config, recommended settings
|
||||||
|
_interface->set_reg(_curr_prs_cfg, SPL06_ADDR_PRS_CFG); |
||||||
|
kp = 253952.0f; // refer to scale_factor()
|
||||||
|
_interface->set_reg(_curr_tmp_cfg, SPL06_ADDR_TMP_CFG); |
||||||
|
kt = 524288.0f; |
||||||
|
|
||||||
|
|
||||||
|
_interface->set_reg(1 << 2, SPL06_ADDR_CFG_REG); |
||||||
|
_interface->set_reg(7, SPL06_ADDR_MEAS_CFG); |
||||||
|
|
||||||
|
Start(); |
||||||
|
|
||||||
|
return OK; |
||||||
|
} |
||||||
|
|
||||||
|
void |
||||||
|
SPL06::Start() |
||||||
|
{ |
||||||
|
// schedule a cycle to start things
|
||||||
|
ScheduleNow(); |
||||||
|
} |
||||||
|
|
||||||
|
void |
||||||
|
SPL06::RunImpl() |
||||||
|
{ |
||||||
|
collect(); |
||||||
|
|
||||||
|
ScheduleDelayed(_measure_interval); |
||||||
|
} |
||||||
|
int |
||||||
|
SPL06::collect() |
||||||
|
{ |
||||||
|
perf_begin(_sample_perf); |
||||||
|
|
||||||
|
// this should be fairly close to the end of the conversion, so the best approximation of the time
|
||||||
|
const hrt_abstime timestamp_sample = hrt_absolute_time(); |
||||||
|
|
||||||
|
if (_interface->read(SPL06_ADDR_DATA, (uint8_t *)&_data, sizeof(_data)) != OK) { |
||||||
|
perf_count(_comms_errors); |
||||||
|
perf_cancel(_sample_perf); |
||||||
|
return -EIO; |
||||||
|
} |
||||||
|
|
||||||
|
int32_t temp_raw = (uint32_t)_data.t_msb << 16 | (uint32_t)_data.t_lsb << 8 | (uint32_t)_data.t_xlsb; |
||||||
|
temp_raw = (temp_raw & 1 << 23) ? (0xff000000 | temp_raw) : temp_raw; |
||||||
|
|
||||||
|
int32_t press_raw = (uint32_t)_data.p_msb << 16 | (uint32_t) _data.p_lsb << 8 | (uint32_t) _data.p_xlsb; |
||||||
|
press_raw = (press_raw & 1 << 23) ? (0xff000000 | press_raw) : press_raw; |
||||||
|
|
||||||
|
// calculate
|
||||||
|
float ftsc = (float)temp_raw / kt; |
||||||
|
float fpsc = (float)press_raw / kp; |
||||||
|
float qua2 = (float)_cal.c10 + fpsc * ((float)_cal.c20 + fpsc * (float)_cal.c30); |
||||||
|
float qua3 = ftsc * fpsc * ((float)_cal.c11 + fpsc * (float)_cal.c21); |
||||||
|
|
||||||
|
float fp = (float)_cal.c00 + fpsc * qua2 + ftsc * (float)_cal.c01 + qua3; |
||||||
|
float temperature = (float)_cal.c0 * 0.5f + (float)_cal.c1 * ftsc; |
||||||
|
|
||||||
|
_px4_baro.set_error_count(perf_event_count(_comms_errors)); |
||||||
|
_px4_baro.set_temperature(temperature); |
||||||
|
_px4_baro.update(timestamp_sample, fp / 100.0f); // to millbar
|
||||||
|
//PX4_DEBUG("%d",(int)fp);
|
||||||
|
perf_end(_sample_perf); |
||||||
|
|
||||||
|
return OK; |
||||||
|
} |
||||||
|
|
||||||
|
void |
||||||
|
SPL06::print_status() |
||||||
|
{ |
||||||
|
I2CSPIDriverBase::print_status(); |
||||||
|
perf_print_counter(_sample_perf); |
||||||
|
perf_print_counter(_measure_perf); |
||||||
|
perf_print_counter(_comms_errors); |
||||||
|
} |
@ -0,0 +1,119 @@ |
|||||||
|
/****************************************************************************
|
||||||
|
* |
||||||
|
* Copyright (c) 2022 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 "spl06.h" |
||||||
|
|
||||||
|
#include <drivers/drv_hrt.h> |
||||||
|
#include <px4_platform_common/px4_config.h> |
||||||
|
#include <px4_platform_common/i2c_spi_buses.h> |
||||||
|
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp> |
||||||
|
#include <lib/drivers/barometer/PX4Barometer.hpp> |
||||||
|
#include <lib/perf/perf_counter.h> |
||||||
|
|
||||||
|
class SPL06 : public I2CSPIDriver<SPL06> |
||||||
|
{ |
||||||
|
public: |
||||||
|
SPL06(const I2CSPIDriverConfig &config, spl06::ISPL06 *interface); |
||||||
|
virtual ~SPL06(); |
||||||
|
|
||||||
|
static I2CSPIDriverBase *instantiate(const I2CSPIDriverConfig &config, int runtime_instance); |
||||||
|
static void print_usage(); |
||||||
|
|
||||||
|
int init(); |
||||||
|
void print_status(); |
||||||
|
|
||||||
|
void RunImpl(); |
||||||
|
private: |
||||||
|
void Start(); |
||||||
|
// float scale_factor(int oversampling_rate);
|
||||||
|
|
||||||
|
int collect(); //get results and publish
|
||||||
|
int calibrate(); |
||||||
|
|
||||||
|
PX4Barometer _px4_baro; |
||||||
|
|
||||||
|
spl06::ISPL06 *_interface; |
||||||
|
spl06::data_s _data; |
||||||
|
spl06::calibration_s _cal{}; |
||||||
|
|
||||||
|
// set config, recommended settings
|
||||||
|
//
|
||||||
|
// oversampling rate : single | 2 | 4 | 8 | 16 | 32 | 64 | 128
|
||||||
|
// scale factor(KP/KT): 524288 | 1572864 | 3670016 | 7864320 | 253952 | 516096 | 1040384 | 2088960
|
||||||
|
|
||||||
|
// configuration of pressure measurement rate (PM_RATE) and resolution (PM_PRC)
|
||||||
|
//
|
||||||
|
// bit[7]: reserved
|
||||||
|
//
|
||||||
|
// PM_RATE[6:4] : 0 | 1 | 2 | 3 | 4 | 5 | 6 | 7
|
||||||
|
// measurement rate: 1 | 2 | 4 | 8 | 16 | 32 | 64 | 128
|
||||||
|
// note: applicable for measurements in background mode only
|
||||||
|
//
|
||||||
|
// PM_PRC[3:0] : 0 | 1 | 2 | 3 | 4 | 5 | 6 | 7
|
||||||
|
// oversampling (times): single | 2 | 4 | 8 | 16 | 32 | 64 | 128
|
||||||
|
// measurement time(ms): 3.6 | 5.2 | 8.4 | 14.8 | 27.6 | 53.2 | 104.4 | 206.8
|
||||||
|
// precision(PaRMS) : 5.0 | | 2.5 | | 1.2 | 0.9 | 0.5 |
|
||||||
|
// note: use in combination with a bit shift when the oversampling rate is > 8 times. see CFG_REG(0x19) register
|
||||||
|
static constexpr uint8_t _curr_prs_cfg{4 << 4 | 4}; |
||||||
|
|
||||||
|
// configuration of temperature measurment rate (TMP_RATE) and resolution (TMP_PRC)
|
||||||
|
//
|
||||||
|
// temperature measurement: internal sensor (in ASIC) | external sensor (in pressure sensor MEMS element)
|
||||||
|
// TMP_EXT[7] : 0 | 1
|
||||||
|
// note: it is highly recommended to use the same temperature sensor as the source of the calibration coefficients wihch can be read from reg 0x28
|
||||||
|
//
|
||||||
|
// TMP_RATE[6:4] : 0 | 1 | 2 | 3 | 4 | 5 | 6 | 7
|
||||||
|
// measurement rate: 1 | 2 | 4 | 8 | 16 | 32 | 64 | 128
|
||||||
|
// note: applicable for measurements in background mode only
|
||||||
|
//
|
||||||
|
// bit[3]: reserved
|
||||||
|
//
|
||||||
|
// TMP_PRC[2:0] : 0 | 1 | 2 | 3 | 4 | 5 | 6 | 7
|
||||||
|
// oversampling (times): single | 2 | 4 | 8 | 16 | 32 | 64 | 128
|
||||||
|
// note: single(default) measurement time 3.6ms, other settings are optional, and may not be relevant
|
||||||
|
// note: use in combination with a bit shift when the oversampling rate is > 8 times. see CFG_REG(0x19) register
|
||||||
|
static constexpr uint8_t _curr_tmp_cfg{1 << 7 | 4 << 4 | 0}; |
||||||
|
|
||||||
|
bool _collect_phase{false}; |
||||||
|
float kp; |
||||||
|
float kt; |
||||||
|
|
||||||
|
perf_counter_t _sample_perf; |
||||||
|
perf_counter_t _measure_perf; |
||||||
|
perf_counter_t _comms_errors; |
||||||
|
|
||||||
|
static constexpr uint32_t _sample_rate{16}; |
||||||
|
static constexpr uint32_t _measure_interval{1000000 / _sample_rate / 2}; |
||||||
|
}; |
@ -0,0 +1,102 @@ |
|||||||
|
/****************************************************************************
|
||||||
|
* |
||||||
|
* Copyright (c) 2022 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 spl06_i2c.cpp |
||||||
|
* |
||||||
|
* SPI interface for Goertek SPL06 |
||||||
|
*/ |
||||||
|
|
||||||
|
#include "spl06.h" |
||||||
|
|
||||||
|
#include <px4_platform_common/px4_config.h> |
||||||
|
#include <drivers/device/i2c.h> |
||||||
|
|
||||||
|
#if defined(CONFIG_I2C) |
||||||
|
|
||||||
|
class SPL06_I2C: public device::I2C, public spl06::ISPL06 |
||||||
|
{ |
||||||
|
public: |
||||||
|
SPL06_I2C(uint8_t bus, uint32_t device, int bus_frequency); |
||||||
|
virtual ~SPL06_I2C() override = default; |
||||||
|
|
||||||
|
int init() override { return I2C::init(); } |
||||||
|
|
||||||
|
uint8_t get_reg(uint8_t addr) override; |
||||||
|
int set_reg(uint8_t value, uint8_t addr) override; |
||||||
|
|
||||||
|
int read(uint8_t addr, uint8_t *buf, uint8_t len) override; |
||||||
|
//spl06::data_s *get_data(uint8_t addr) override;
|
||||||
|
//spl06::calibration_s *get_calibration(uint8_t addr) override;
|
||||||
|
|
||||||
|
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: |
||||||
|
spl06::calibration_s _cal{}; |
||||||
|
spl06::data_s _data{}; |
||||||
|
}; |
||||||
|
|
||||||
|
spl06::ISPL06 *spl06_i2c_interface(uint8_t busnum, uint32_t device, int bus_frequency) |
||||||
|
{ |
||||||
|
return new SPL06_I2C(busnum, device, bus_frequency); |
||||||
|
} |
||||||
|
|
||||||
|
SPL06_I2C::SPL06_I2C(uint8_t bus, uint32_t device, int bus_frequency) : |
||||||
|
I2C(DRV_BARO_DEVTYPE_SPL06, MODULE_NAME, bus, device, bus_frequency) |
||||||
|
{ |
||||||
|
} |
||||||
|
|
||||||
|
uint8_t |
||||||
|
SPL06_I2C::get_reg(uint8_t addr) |
||||||
|
{ |
||||||
|
uint8_t cmd[2] = { (uint8_t)(addr), 0}; |
||||||
|
transfer(&cmd[0], 1, &cmd[1], 1); |
||||||
|
|
||||||
|
return cmd[1]; |
||||||
|
} |
||||||
|
|
||||||
|
int |
||||||
|
SPL06_I2C::set_reg(uint8_t value, uint8_t addr) |
||||||
|
{ |
||||||
|
uint8_t cmd[2] = { (uint8_t)(addr), value}; |
||||||
|
return transfer(cmd, sizeof(cmd), nullptr, 0); |
||||||
|
} |
||||||
|
|
||||||
|
int |
||||||
|
SPL06_I2C::read(uint8_t addr, uint8_t *buf, uint8_t len) |
||||||
|
{ |
||||||
|
return transfer(&addr, 1, buf, len); |
||||||
|
} |
||||||
|
|
||||||
|
#endif // CONFIG_I2C
|
@ -0,0 +1,104 @@ |
|||||||
|
/****************************************************************************
|
||||||
|
* |
||||||
|
* Copyright (c) 2022 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 spl06_spi.cpp |
||||||
|
* |
||||||
|
* SPI interface for Goertek SPL06 |
||||||
|
*/ |
||||||
|
|
||||||
|
#include "spl06.h" |
||||||
|
|
||||||
|
#include <px4_platform_common/px4_config.h> |
||||||
|
#include <drivers/device/spi.h> |
||||||
|
|
||||||
|
#if defined(CONFIG_SPI) |
||||||
|
|
||||||
|
/* SPI protocol address bits */ |
||||||
|
#define DIR_READ (1<<7) //for set
|
||||||
|
#define DIR_WRITE ~(1<<7) //for clear
|
||||||
|
|
||||||
|
class SPL06_SPI: public device::SPI, public spl06::ISPL06 |
||||||
|
{ |
||||||
|
public: |
||||||
|
SPL06_SPI(uint8_t bus, uint32_t device, int bus_frequency, spi_mode_e spi_mode); |
||||||
|
virtual ~SPL06_SPI() override = default; |
||||||
|
|
||||||
|
int init() override { return SPI::init(); } |
||||||
|
|
||||||
|
uint8_t get_reg(uint8_t addr) override; |
||||||
|
int set_reg(uint8_t value, uint8_t addr) override; |
||||||
|
|
||||||
|
int read(uint8_t addr, uint8_t *buf, uint8_t len) override; |
||||||
|
|
||||||
|
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(); } |
||||||
|
}; |
||||||
|
|
||||||
|
spl06::ISPL06 * |
||||||
|
spl06_spi_interface(uint8_t busnum, uint32_t device, int bus_frequency, spi_mode_e spi_mode) |
||||||
|
{ |
||||||
|
return new SPL06_SPI(busnum, device, bus_frequency, spi_mode); |
||||||
|
} |
||||||
|
|
||||||
|
SPL06_SPI::SPL06_SPI(uint8_t bus, uint32_t device, int bus_frequency, spi_mode_e spi_mode) : |
||||||
|
SPI(DRV_BARO_DEVTYPE_SPL06, MODULE_NAME, bus, device, spi_mode, bus_frequency) |
||||||
|
{ |
||||||
|
} |
||||||
|
|
||||||
|
uint8_t |
||||||
|
SPL06_SPI::get_reg(uint8_t addr) |
||||||
|
{ |
||||||
|
uint8_t cmd[2] = { (uint8_t)(addr | DIR_READ), 0}; // set MSB bit
|
||||||
|
transfer(&cmd[0], &cmd[0], 2); |
||||||
|
|
||||||
|
return cmd[1]; |
||||||
|
} |
||||||
|
|
||||||
|
int |
||||||
|
SPL06_SPI::set_reg(uint8_t value, uint8_t addr) |
||||||
|
{ |
||||||
|
uint8_t cmd[2] = { (uint8_t)(addr & DIR_WRITE), value}; // clear MSB bit
|
||||||
|
return transfer(&cmd[0], nullptr, 2); |
||||||
|
} |
||||||
|
|
||||||
|
int |
||||||
|
SPL06_SPI::read(uint8_t addr, uint8_t *buf, uint8_t len) |
||||||
|
{ |
||||||
|
uint8_t tx_buf[len + 1] = {(uint8_t)(addr | DIR_READ)}; // GCC support VLA, let's use it
|
||||||
|
|
||||||
|
return transfer(tx_buf, buf, len); |
||||||
|
} |
||||||
|
|
||||||
|
#endif // CONFIG_SPI
|
@ -0,0 +1,8 @@ |
|||||||
|
/**
|
||||||
|
* Goertek SPL06 Barometer (external I2C)
|
||||||
|
*
|
||||||
|
* @reboot_required true
|
||||||
|
* @group Sensors
|
||||||
|
* @boolean
|
||||||
|
*/
|
||||||
|
PARAM_DEFINE_INT32(SENS_EN_SPL06, 0);
|
@ -0,0 +1,108 @@ |
|||||||
|
/****************************************************************************
|
||||||
|
* |
||||||
|
* Copyright (c) 2022 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 spl06.h |
||||||
|
* |
||||||
|
* Shared defines for the spl06 driver. |
||||||
|
*/ |
||||||
|
#pragma once |
||||||
|
|
||||||
|
#include <px4_platform_common/i2c_spi_buses.h> |
||||||
|
|
||||||
|
#define SPL06_ADDR_ID 0x0d |
||||||
|
#define SPL06_ADDR_RESET 0x0c // set to reset
|
||||||
|
#define SPL06_ADDR_CAL 0x10 |
||||||
|
#define SPL06_ADDR_PRS_CFG 0x06 |
||||||
|
#define SPL06_ADDR_TMP_CFG 0x07 |
||||||
|
#define SPL06_ADDR_MEAS_CFG 0x08 |
||||||
|
#define SPL06_ADDR_CFG_REG 0x09 |
||||||
|
#define SPL06_ADDR_DATA 0x00 |
||||||
|
|
||||||
|
|
||||||
|
#define SPL06_VALUE_RESET 9 |
||||||
|
#define SPL06_VALUE_ID 0x10 |
||||||
|
|
||||||
|
namespace spl06 |
||||||
|
{ |
||||||
|
|
||||||
|
#pragma pack(push,1) |
||||||
|
struct calibration_s { |
||||||
|
int16_t c0, c1; |
||||||
|
int32_t c00, c10; |
||||||
|
int16_t c01, c11, c20, c21, c30; |
||||||
|
}; //calibration data
|
||||||
|
|
||||||
|
struct data_s { |
||||||
|
uint8_t p_msb; |
||||||
|
uint8_t p_lsb; |
||||||
|
uint8_t p_xlsb; |
||||||
|
|
||||||
|
uint8_t t_msb; |
||||||
|
uint8_t t_lsb; |
||||||
|
uint8_t t_xlsb; |
||||||
|
}; // data
|
||||||
|
#pragma pack(pop) |
||||||
|
|
||||||
|
class ISPL06 |
||||||
|
{ |
||||||
|
public: |
||||||
|
virtual ~ISPL06() = default; |
||||||
|
|
||||||
|
virtual int init() = 0; |
||||||
|
|
||||||
|
// read reg value
|
||||||
|
virtual uint8_t get_reg(uint8_t addr) = 0; |
||||||
|
|
||||||
|
// write reg value
|
||||||
|
virtual int set_reg(uint8_t value, uint8_t addr) = 0; |
||||||
|
|
||||||
|
// bulk read of data into buffer, return same pointer
|
||||||
|
virtual int read(uint8_t addr, uint8_t *buf, uint8_t len) = 0; |
||||||
|
// bulk read of calibration data into buffer, return same pointer
|
||||||
|
|
||||||
|
virtual uint32_t get_device_id() const = 0; |
||||||
|
|
||||||
|
virtual uint8_t get_device_address() const = 0; |
||||||
|
}; |
||||||
|
|
||||||
|
} /* namespace */ |
||||||
|
|
||||||
|
|
||||||
|
/* interface factories */ |
||||||
|
#if defined(CONFIG_SPI) |
||||||
|
extern spl06::ISPL06 *spl06_spi_interface(uint8_t busnum, uint32_t device, int bus_frequency, spi_mode_e spi_mode); |
||||||
|
#endif // CONFIG_SPI
|
||||||
|
#if defined(CONFIG_I2C) |
||||||
|
extern spl06::ISPL06 *spl06_i2c_interface(uint8_t busnum, uint32_t device, int bus_frequency); |
||||||
|
#endif // CONFIG_I2C
|
@ -0,0 +1,141 @@ |
|||||||
|
/****************************************************************************
|
||||||
|
* |
||||||
|
* Copyright (c) 2022 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 <px4_platform_common/px4_config.h> |
||||||
|
#include <px4_platform_common/getopt.h> |
||||||
|
#include <px4_platform_common/module.h> |
||||||
|
|
||||||
|
#include "SPL06.hpp" |
||||||
|
|
||||||
|
#include <drivers/drv_sensor.h> |
||||||
|
|
||||||
|
extern "C" { __EXPORT int spl06_main(int argc, char *argv[]); } |
||||||
|
|
||||||
|
void |
||||||
|
SPL06::print_usage() |
||||||
|
{ |
||||||
|
PRINT_MODULE_USAGE_NAME("spl06", "driver"); |
||||||
|
PRINT_MODULE_USAGE_SUBCATEGORY("baro"); |
||||||
|
PRINT_MODULE_USAGE_COMMAND("start"); |
||||||
|
#if defined(CONFIG_I2C) |
||||||
|
PRINT_MODULE_USAGE_PARAMS_I2C_SPI_DRIVER(true, true); |
||||||
|
PRINT_MODULE_USAGE_PARAMS_I2C_ADDRESS(0x76); |
||||||
|
#else |
||||||
|
PRINT_MODULE_USAGE_PARAMS_I2C_SPI_DRIVER(false, true); |
||||||
|
#endif |
||||||
|
PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); |
||||||
|
} |
||||||
|
|
||||||
|
I2CSPIDriverBase *SPL06::instantiate(const I2CSPIDriverConfig &config, int runtime_instance) |
||||||
|
{ |
||||||
|
spl06::ISPL06 *interface = nullptr; |
||||||
|
|
||||||
|
#if defined(CONFIG_I2C) |
||||||
|
|
||||||
|
if (config.bus_type == BOARD_I2C_BUS) { |
||||||
|
interface = spl06_i2c_interface(config.bus, config.i2c_address, config.bus_frequency); |
||||||
|
|
||||||
|
} |
||||||
|
|
||||||
|
#endif // CONFIG_I2C
|
||||||
|
#if defined(CONFIG_SPI) |
||||||
|
|
||||||
|
if (config.bus_type == BOARD_SPI_BUS) { |
||||||
|
interface = spl06_spi_interface(config.bus, config.spi_devid, config.bus_frequency, config.spi_mode); |
||||||
|
} |
||||||
|
|
||||||
|
#endif // CONFIG_SPI
|
||||||
|
|
||||||
|
if (interface == nullptr) { |
||||||
|
PX4_ERR("failed creating interface for bus %i", config.bus); |
||||||
|
return nullptr; |
||||||
|
} |
||||||
|
|
||||||
|
if (interface->init() != OK) { |
||||||
|
delete interface; |
||||||
|
PX4_DEBUG("no device on bus %i", config.bus); |
||||||
|
return nullptr; |
||||||
|
} |
||||||
|
|
||||||
|
SPL06 *dev = new SPL06(config, interface); |
||||||
|
|
||||||
|
if (dev == nullptr) { |
||||||
|
delete interface; |
||||||
|
return nullptr; |
||||||
|
} |
||||||
|
|
||||||
|
if (OK != dev->init()) { |
||||||
|
delete dev; |
||||||
|
return nullptr; |
||||||
|
} |
||||||
|
|
||||||
|
return dev; |
||||||
|
} |
||||||
|
|
||||||
|
int |
||||||
|
spl06_main(int argc, char *argv[]) |
||||||
|
{ |
||||||
|
using ThisDriver = SPL06; |
||||||
|
BusCLIArguments cli{true, true}; |
||||||
|
#if defined(CONFIG_I2C) |
||||||
|
cli.i2c_address = 0x76; |
||||||
|
cli.default_i2c_frequency = 100 * 1000; |
||||||
|
#endif // CONFIG_I2C
|
||||||
|
#if defined(CONFIG_SPI) |
||||||
|
cli.default_spi_frequency = 10 * 1000 * 1000; |
||||||
|
#endif // CONFIG_SPI
|
||||||
|
|
||||||
|
const char *verb = cli.parseDefaultArguments(argc, argv); |
||||||
|
|
||||||
|
if (!verb) { |
||||||
|
ThisDriver::print_usage(); |
||||||
|
return -1; |
||||||
|
} |
||||||
|
|
||||||
|
BusInstanceIterator iterator(MODULE_NAME, cli, DRV_BARO_DEVTYPE_SPL06); |
||||||
|
|
||||||
|
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; |
||||||
|
} |
Loading…
Reference in new issue