forked from Archive/PX4-Autopilot
i2c_spi_buses: respect CONFIG_I2C and CONFIG_SPI
- bmp280, dps310, and ms5611 barometers support boards without I2C
This commit is contained in:
parent
eade2915c1
commit
7b7b7acd36
|
@ -124,10 +124,6 @@
|
|||
#define GPIO_CAN1_RX GPIO_CAN1_RX_2
|
||||
#define GPIO_CAN1_TX GPIO_CAN1_TX_2
|
||||
|
||||
/* I2C */
|
||||
#define GPIO_I2C1_SCL GPIO_I2C1_SCL_1
|
||||
#define GPIO_I2C1_SDA GPIO_I2C1_SDA_1
|
||||
|
||||
/* SPI */
|
||||
#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1
|
||||
#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_1
|
||||
|
|
|
@ -57,8 +57,6 @@ CONFIG_GRAN=y
|
|||
CONFIG_GRAN_INTR=y
|
||||
CONFIG_HAVE_CXX=y
|
||||
CONFIG_HAVE_CXXINITIALIZE=y
|
||||
CONFIG_I2C=y
|
||||
CONFIG_I2C_RESET=y
|
||||
CONFIG_IDLETHREAD_STACKSIZE=750
|
||||
CONFIG_LIBC_FLOATINGPOINT=y
|
||||
CONFIG_LIBC_LONG_LONG=y
|
||||
|
@ -127,7 +125,6 @@ CONFIG_STM32_DMA1=y
|
|||
CONFIG_STM32_DMA2=y
|
||||
CONFIG_STM32_FLASH_PREFETCH=y
|
||||
CONFIG_STM32_FLOWCONTROL_BROKEN=y
|
||||
CONFIG_STM32_I2C1=y
|
||||
CONFIG_STM32_JTAG_SW_ENABLE=y
|
||||
CONFIG_STM32_PWR=y
|
||||
CONFIG_STM32_RTC=y
|
||||
|
|
|
@ -49,7 +49,6 @@ if("${PX4_BOARD_LABEL}" STREQUAL "canbootloader")
|
|||
else()
|
||||
add_library(drivers_board
|
||||
can.c
|
||||
i2c.cpp
|
||||
init.c
|
||||
led.c
|
||||
spi.cpp
|
||||
|
|
|
@ -1,38 +0,0 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#include <px4_arch/i2c_hw_description.h>
|
||||
|
||||
constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = {
|
||||
initI2CBusExternal(1),
|
||||
};
|
|
@ -48,11 +48,16 @@
|
|||
|
||||
|
||||
// I2C
|
||||
#define CONFIG_I2C 1
|
||||
#define PX4_NUMBER_I2C_BUSES 2
|
||||
|
||||
#define PX4_I2C_OBDEV_MPU9250 0x68
|
||||
|
||||
|
||||
// SPI
|
||||
#define CONFIG_SPI 1
|
||||
|
||||
|
||||
// ADC channels:
|
||||
#define ADC_CHANNELS (1 << 5)
|
||||
#define BOARD_ADC_POS_REF_V (1.8f)
|
||||
|
|
|
@ -35,4 +35,8 @@
|
|||
#include <drivers/drv_sensor.h>
|
||||
|
||||
constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = {
|
||||
initSPIBus(1, {
|
||||
initSPIDevice(DRV_DEVTYPE_UNUSED, 1), // spidev1.1
|
||||
initSPIDevice(DRV_DEVTYPE_UNUSED, 2), // spidev1.2
|
||||
}),
|
||||
};
|
||||
|
|
|
@ -164,7 +164,4 @@
|
|||
|
||||
#define BOARD_NUM_IO_TIMERS 3
|
||||
|
||||
#define BOARD_DISABLE_I2C_SPI
|
||||
|
||||
|
||||
#include <px4_platform_common/board_common.h>
|
||||
|
|
|
@ -49,9 +49,13 @@
|
|||
|
||||
|
||||
// I2C
|
||||
#define CONFIG_I2C 1
|
||||
#define PX4_NUMBER_I2C_BUSES 1
|
||||
|
||||
|
||||
// SPI
|
||||
#define CONFIG_SPI 1
|
||||
|
||||
// ADC channels:
|
||||
// A0 - board voltage (shows 5V)
|
||||
// A1 - servo rail voltage
|
||||
|
|
|
@ -164,6 +164,4 @@
|
|||
|
||||
#define BOARD_NUM_IO_TIMERS 3
|
||||
|
||||
#define BOARD_DISABLE_I2C_SPI
|
||||
|
||||
#include <px4_platform_common/board_common.h>
|
||||
|
|
|
@ -42,11 +42,16 @@
|
|||
#define BOARD_OVERRIDE_UUID "RPIID00000000000" // must be of length 16
|
||||
#define PX4_SOC_ARCH_ID PX4_SOC_ARCH_ID_RPI
|
||||
|
||||
/*
|
||||
* I2C busses
|
||||
*/
|
||||
|
||||
// I2C
|
||||
#define CONFIG_I2C 1
|
||||
#define PX4_NUMBER_I2C_BUSES 2
|
||||
|
||||
|
||||
// SPI
|
||||
#define CONFIG_SPI 1
|
||||
|
||||
|
||||
#define ADC_BATTERY_VOLTAGE_CHANNEL 0
|
||||
#define ADC_BATTERY_CURRENT_CHANNEL -1
|
||||
#define ADC_AIRSPEED_VOLTAGE_CHANNEL 2
|
||||
|
|
|
@ -33,7 +33,5 @@
|
|||
|
||||
add_library(drivers_board
|
||||
board_shutdown.cpp
|
||||
i2c.cpp
|
||||
sitl_led.c
|
||||
spi.cpp
|
||||
)
|
||||
|
|
|
@ -1,38 +0,0 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2020 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_arch/i2c_hw_description.h>
|
||||
|
||||
constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = {
|
||||
};
|
||||
|
|
@ -1,38 +0,0 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2020 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_arch/spi_hw_description.h>
|
||||
#include <drivers/drv_sensor.h>
|
||||
|
||||
constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = {
|
||||
};
|
|
@ -42,11 +42,16 @@
|
|||
#define BOARD_OVERRIDE_UUID "RPIID00000000000" // must be of length 16
|
||||
#define PX4_SOC_ARCH_ID PX4_SOC_ARCH_ID_RPI
|
||||
|
||||
/*
|
||||
* I2C busses
|
||||
*/
|
||||
|
||||
// I2C
|
||||
#define CONFIG_I2C 1
|
||||
#define PX4_NUMBER_I2C_BUSES 2
|
||||
|
||||
|
||||
// SPI
|
||||
#define CONFIG_SPI 1
|
||||
|
||||
|
||||
#define ADC_BATTERY_VOLTAGE_CHANNEL 0
|
||||
#define ADC_BATTERY_CURRENT_CHANNEL -1
|
||||
#define ADC_AIRSPEED_VOLTAGE_CHANNEL 2
|
||||
|
|
|
@ -32,10 +32,11 @@
|
|||
****************************************************************************/
|
||||
|
||||
#include <board_config.h>
|
||||
#ifndef BOARD_DISABLE_I2C_SPI
|
||||
|
||||
#include <px4_platform_common/i2c.h>
|
||||
|
||||
#if defined(CONFIG_I2C)
|
||||
|
||||
#ifndef BOARD_OVERRIDE_I2C_BUS_EXTERNAL
|
||||
bool px4_i2c_bus_external(const px4_i2c_bus_t &bus)
|
||||
{
|
||||
|
@ -85,4 +86,4 @@ bool I2CBusIterator::next()
|
|||
return false;
|
||||
}
|
||||
|
||||
#endif /* BOARD_DISABLE_I2C_SPI */
|
||||
#endif // CONFIG_I2C
|
||||
|
|
|
@ -32,7 +32,6 @@
|
|||
****************************************************************************/
|
||||
|
||||
#include <board_config.h>
|
||||
#ifndef BOARD_DISABLE_I2C_SPI
|
||||
|
||||
#ifndef MODULE_NAME
|
||||
#define MODULE_NAME "SPI_I2C"
|
||||
|
@ -57,11 +56,15 @@ I2CSPIDriverConfig::I2CSPIDriverConfig(const BusCLIArguments &cli, const BusInst
|
|||
bus_option(iterator.configuredBusOption()),
|
||||
bus_type(iterator.busType()),
|
||||
bus(iterator.bus()),
|
||||
#if defined(CONFIG_I2C)
|
||||
i2c_address(cli.i2c_address),
|
||||
#endif // CONFIG_I2C
|
||||
bus_frequency(cli.bus_frequency),
|
||||
#if defined(CONFIG_SPI)
|
||||
drdy_gpio(iterator.DRDYGPIO()),
|
||||
spi_mode(cli.spi_mode),
|
||||
spi_devid(iterator.devid()),
|
||||
#endif // CONFIG_SPI
|
||||
bus_device_index(iterator.busDeviceIndex()),
|
||||
rotation(cli.rotation),
|
||||
quiet_start(cli.quiet_start),
|
||||
|
@ -93,6 +96,8 @@ int BusCLIArguments::getOpt(int argc, char *argv[], const char *options)
|
|||
|
||||
char *p = (char *)&_options;
|
||||
|
||||
#if defined(CONFIG_I2C)
|
||||
|
||||
if (_i2c_support) {
|
||||
*(p++) = 'X'; // external
|
||||
*(p++) = 'I'; // internal
|
||||
|
@ -102,6 +107,9 @@ int BusCLIArguments::getOpt(int argc, char *argv[], const char *options)
|
|||
}
|
||||
}
|
||||
|
||||
#endif // CONFIG_I2C
|
||||
#if defined(CONFIG_SPI)
|
||||
|
||||
if (_spi_support) {
|
||||
*(p++) = 'S'; // external
|
||||
*(p++) = 's'; // internal
|
||||
|
@ -109,6 +117,8 @@ int BusCLIArguments::getOpt(int argc, char *argv[], const char *options)
|
|||
*(p++) = 'm'; *(p++) = ':'; // spi mode
|
||||
}
|
||||
|
||||
#endif // CONFIG_SPI
|
||||
|
||||
if (support_keep_running) {
|
||||
*(p++) = 'k';
|
||||
}
|
||||
|
@ -148,6 +158,8 @@ int BusCLIArguments::getOpt(int argc, char *argv[], const char *options)
|
|||
|
||||
while ((ch = px4_getopt(argc, argv, _options, &_optind, &_optarg)) != EOF) {
|
||||
switch (ch) {
|
||||
#if defined(CONFIG_I2C)
|
||||
|
||||
case 'X':
|
||||
bus_option = I2CSPIBusOption::I2CExternal;
|
||||
break;
|
||||
|
@ -163,6 +175,8 @@ int BusCLIArguments::getOpt(int argc, char *argv[], const char *options)
|
|||
|
||||
i2c_address = (int)strtol(_optarg, nullptr, 0);
|
||||
break;
|
||||
#endif // CONFIG_I2C
|
||||
#if defined(CONFIG_SPI)
|
||||
|
||||
case 'S':
|
||||
bus_option = I2CSPIBusOption::SPIExternal;
|
||||
|
@ -175,6 +189,7 @@ int BusCLIArguments::getOpt(int argc, char *argv[], const char *options)
|
|||
case 'c':
|
||||
chipselect_index = atoi(_optarg);
|
||||
break;
|
||||
#endif // CONFIG_SPI
|
||||
|
||||
case 'b':
|
||||
requested_bus = atoi(_optarg);
|
||||
|
@ -183,10 +198,12 @@ int BusCLIArguments::getOpt(int argc, char *argv[], const char *options)
|
|||
case 'f':
|
||||
bus_frequency = 1000 * atoi(_optarg);
|
||||
break;
|
||||
#if defined(CONFIG_SPI)
|
||||
|
||||
case 'm':
|
||||
spi_mode = (spi_mode_e)atoi(_optarg);
|
||||
break;
|
||||
#endif // CONFIG_SPI
|
||||
|
||||
case 'q':
|
||||
quiet_start = true;
|
||||
|
@ -216,12 +233,21 @@ int BusCLIArguments::getOpt(int argc, char *argv[], const char *options)
|
|||
|
||||
// apply defaults if not provided
|
||||
if (bus_frequency == 0) {
|
||||
#if defined(CONFIG_I2C)
|
||||
|
||||
if (bus_option == I2CSPIBusOption::I2CExternal || bus_option == I2CSPIBusOption::I2CInternal) {
|
||||
bus_frequency = default_i2c_frequency;
|
||||
|
||||
} else if (bus_option == I2CSPIBusOption::SPIExternal || bus_option == I2CSPIBusOption::SPIInternal) {
|
||||
}
|
||||
|
||||
#endif // CONFIG_I2C
|
||||
#if defined(CONFIG_SPI)
|
||||
|
||||
if (bus_option == I2CSPIBusOption::SPIExternal || bus_option == I2CSPIBusOption::SPIInternal) {
|
||||
bus_frequency = default_spi_frequency;
|
||||
}
|
||||
|
||||
#endif // CONFIG_SPI
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -232,16 +258,22 @@ bool BusCLIArguments::validateConfiguration()
|
|||
{
|
||||
bool success = true;
|
||||
|
||||
#if defined(CONFIG_I2C)
|
||||
|
||||
if (_i2c_support && default_i2c_frequency == -1) {
|
||||
PX4_ERR("Bug: driver %s does not set default_i2c_frequency", px4_get_taskname());
|
||||
success = false;
|
||||
}
|
||||
|
||||
#endif // CONFIG_I2C
|
||||
#if defined(CONFIG_SPI)
|
||||
|
||||
if (_spi_support && default_spi_frequency == -1) {
|
||||
PX4_ERR("Bug: driver %s does not set default_spi_frequency", px4_get_taskname());
|
||||
success = false;
|
||||
}
|
||||
|
||||
#endif // CONFIG_SPI
|
||||
return success;
|
||||
}
|
||||
|
||||
|
@ -249,11 +281,17 @@ bool BusCLIArguments::validateConfiguration()
|
|||
BusInstanceIterator::BusInstanceIterator(const char *module_name,
|
||||
const BusCLIArguments &cli_arguments, uint16_t devid_driver_index)
|
||||
: _module_name(module_name), _bus_option(cli_arguments.bus_option), _devid_driver_index(devid_driver_index),
|
||||
#if defined(CONFIG_I2C)
|
||||
_i2c_address(cli_arguments.i2c_address),
|
||||
#endif // CONFIG_I2C
|
||||
#if defined(CONFIG_SPI)
|
||||
_spi_bus_iterator(spiFilter(cli_arguments.bus_option),
|
||||
cli_arguments.bus_option == I2CSPIBusOption::SPIExternal ? cli_arguments.chipselect_index : devid_driver_index,
|
||||
cli_arguments.requested_bus),
|
||||
#endif // CONFIG_SPI
|
||||
#if defined(CONFIG_I2C)
|
||||
_i2c_bus_iterator(i2cFilter(cli_arguments.bus_option), cli_arguments.requested_bus),
|
||||
#endif // CONFIG_I2C
|
||||
_current_instance(i2c_spi_module_instances.end())
|
||||
{
|
||||
// We lock the module instance list as long as this object is alive, since we iterate over the list.
|
||||
|
@ -290,20 +328,31 @@ bool BusInstanceIterator::next()
|
|||
|
||||
return false;
|
||||
|
||||
#if defined(CONFIG_SPI)
|
||||
|
||||
} else if (busType() == BOARD_SPI_BUS) {
|
||||
if (_spi_bus_iterator.next()) {
|
||||
bus = _spi_bus_iterator.bus().bus;
|
||||
}
|
||||
|
||||
} else {
|
||||
#endif // CONFIG_SPI
|
||||
#if defined(CONFIG_I2C)
|
||||
|
||||
} else if (busType() == BOARD_I2C_BUS) {
|
||||
if (_i2c_bus_iterator.next()) {
|
||||
bus = _i2c_bus_iterator.bus().bus;
|
||||
}
|
||||
|
||||
#endif // CONFIG_I2C
|
||||
}
|
||||
|
||||
if (bus != -1) {
|
||||
// find matching runtime instance
|
||||
#if defined(CONFIG_I2C)
|
||||
bool is_i2c = busType() == BOARD_I2C_BUS;
|
||||
#else
|
||||
bool is_i2c = false;
|
||||
#endif
|
||||
|
||||
for (_current_instance = i2c_spi_module_instances.begin(); _current_instance != i2c_spi_module_instances.end();
|
||||
++_current_instance) {
|
||||
|
@ -314,7 +363,12 @@ bool BusInstanceIterator::next()
|
|||
if (_bus_option == (*_current_instance)->_bus_option && bus == (*_current_instance)->_bus &&
|
||||
_devid_driver_index == (*_current_instance)->_devid_driver_index &&
|
||||
busDeviceIndex() == (*_current_instance)->_bus_device_index &&
|
||||
(!is_i2c || _i2c_address == (*_current_instance)->_i2c_address)) {
|
||||
(!is_i2c
|
||||
#if defined(CONFIG_I2C)
|
||||
|| _i2c_address == (*_current_instance)->_i2c_address
|
||||
#endif // CONFIG_I2C
|
||||
)
|
||||
) {
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
@ -371,13 +425,19 @@ board_bus_types BusInstanceIterator::busType() const
|
|||
case I2CSPIBusOption::All:
|
||||
return BOARD_INVALID_BUS;
|
||||
|
||||
#if defined(CONFIG_I2C)
|
||||
|
||||
case I2CSPIBusOption::I2CInternal:
|
||||
case I2CSPIBusOption::I2CExternal:
|
||||
return BOARD_I2C_BUS;
|
||||
#endif // CONFIG_I2C
|
||||
|
||||
#if defined(CONFIG_SPI)
|
||||
|
||||
case I2CSPIBusOption::SPIInternal:
|
||||
case I2CSPIBusOption::SPIExternal:
|
||||
return BOARD_SPI_BUS;
|
||||
#endif // CONFIG_SPI
|
||||
}
|
||||
|
||||
return BOARD_INVALID_BUS;
|
||||
|
@ -385,78 +445,104 @@ board_bus_types BusInstanceIterator::busType() const
|
|||
|
||||
int BusInstanceIterator::bus() const
|
||||
{
|
||||
if (busType() == BOARD_INVALID_BUS) {
|
||||
return -1;
|
||||
#if defined(CONFIG_SPI)
|
||||
|
||||
} else if (busType() == BOARD_SPI_BUS) {
|
||||
if (busType() == BOARD_SPI_BUS) {
|
||||
return _spi_bus_iterator.bus().bus;
|
||||
}
|
||||
|
||||
} else {
|
||||
#endif // CONFIG_SPI
|
||||
#if defined(CONFIG_I2C)
|
||||
|
||||
if (busType() == BOARD_I2C_BUS) {
|
||||
return _i2c_bus_iterator.bus().bus;
|
||||
}
|
||||
}
|
||||
|
||||
uint32_t BusInstanceIterator::devid() const
|
||||
{
|
||||
if (busType() == BOARD_INVALID_BUS) {
|
||||
return 0;
|
||||
|
||||
} else if (busType() == BOARD_SPI_BUS) {
|
||||
return _spi_bus_iterator.devid();
|
||||
|
||||
} else {
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
|
||||
spi_drdy_gpio_t BusInstanceIterator::DRDYGPIO() const
|
||||
{
|
||||
if (busType() == BOARD_INVALID_BUS) {
|
||||
return 0;
|
||||
|
||||
} else if (busType() == BOARD_SPI_BUS) {
|
||||
return _spi_bus_iterator.DRDYGPIO();
|
||||
|
||||
} else {
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
|
||||
bool BusInstanceIterator::external() const
|
||||
{
|
||||
if (busType() == BOARD_INVALID_BUS) {
|
||||
return false;
|
||||
|
||||
} else if (busType() == BOARD_SPI_BUS) {
|
||||
return _spi_bus_iterator.external();
|
||||
|
||||
} else {
|
||||
return _i2c_bus_iterator.external();
|
||||
}
|
||||
}
|
||||
|
||||
int BusInstanceIterator::externalBusIndex() const
|
||||
{
|
||||
if (busType() == BOARD_INVALID_BUS) {
|
||||
return 0;
|
||||
|
||||
} else if (busType() == BOARD_SPI_BUS) {
|
||||
return _spi_bus_iterator.externalBusIndex();
|
||||
|
||||
} else {
|
||||
return _i2c_bus_iterator.externalBusIndex();
|
||||
}
|
||||
}
|
||||
|
||||
int BusInstanceIterator::busDeviceIndex() const
|
||||
{
|
||||
if (busType() == BOARD_SPI_BUS) {
|
||||
return _spi_bus_iterator.busDeviceIndex();
|
||||
}
|
||||
#endif // CONFIG_I2C
|
||||
|
||||
return -1;
|
||||
}
|
||||
|
||||
uint32_t BusInstanceIterator::devid() const
|
||||
{
|
||||
#if defined(CONFIG_SPI)
|
||||
|
||||
if (busType() == BOARD_SPI_BUS) {
|
||||
return _spi_bus_iterator.devid();
|
||||
}
|
||||
|
||||
#endif // CONFIG_SPI
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
#if defined(CONFIG_SPI)
|
||||
spi_drdy_gpio_t BusInstanceIterator::DRDYGPIO() const
|
||||
{
|
||||
if (busType() == BOARD_SPI_BUS) {
|
||||
return _spi_bus_iterator.DRDYGPIO();
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
#endif // CONFIG_SPI
|
||||
|
||||
bool BusInstanceIterator::external() const
|
||||
{
|
||||
#if defined(CONFIG_SPI)
|
||||
|
||||
if (busType() == BOARD_SPI_BUS) {
|
||||
return _spi_bus_iterator.external();
|
||||
}
|
||||
|
||||
#endif // CONFIG_SPI
|
||||
|
||||
#if defined(CONFIG_I2C)
|
||||
|
||||
if (busType() == BOARD_I2C_BUS) {
|
||||
return _i2c_bus_iterator.external();
|
||||
}
|
||||
|
||||
#endif // CONFIG_I2C
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
int BusInstanceIterator::externalBusIndex() const
|
||||
{
|
||||
#if defined(CONFIG_SPI)
|
||||
|
||||
if (busType() == BOARD_SPI_BUS) {
|
||||
return _spi_bus_iterator.externalBusIndex();
|
||||
}
|
||||
|
||||
#endif // CONFIG_SPI
|
||||
|
||||
#if defined(CONFIG_I2C)
|
||||
|
||||
if (busType() == BOARD_I2C_BUS) {
|
||||
return _i2c_bus_iterator.externalBusIndex();
|
||||
}
|
||||
|
||||
#endif // CONFIG_I2C
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int BusInstanceIterator::busDeviceIndex() const
|
||||
{
|
||||
#if defined(CONFIG_SPI)
|
||||
|
||||
if (busType() == BOARD_SPI_BUS) {
|
||||
return _spi_bus_iterator.busDeviceIndex();
|
||||
}
|
||||
|
||||
#endif // CONFIG_SPI
|
||||
|
||||
return -1;
|
||||
}
|
||||
|
||||
#if defined(CONFIG_I2C)
|
||||
I2CBusIterator::FilterType BusInstanceIterator::i2cFilter(I2CSPIBusOption bus_option)
|
||||
{
|
||||
switch (bus_option) {
|
||||
|
@ -471,7 +557,9 @@ I2CBusIterator::FilterType BusInstanceIterator::i2cFilter(I2CSPIBusOption bus_op
|
|||
|
||||
return I2CBusIterator::FilterType::All;
|
||||
}
|
||||
#endif // CONFIG_I2C
|
||||
|
||||
#if defined(CONFIG_SPI)
|
||||
SPIBusIterator::FilterType BusInstanceIterator::spiFilter(I2CSPIBusOption bus_option)
|
||||
{
|
||||
switch (bus_option) {
|
||||
|
@ -484,6 +572,7 @@ SPIBusIterator::FilterType BusInstanceIterator::spiFilter(I2CSPIBusOption bus_op
|
|||
|
||||
return SPIBusIterator::FilterType::InternalBus;
|
||||
}
|
||||
#endif // CONFIG_SPI
|
||||
|
||||
struct I2CSPIDriverInitializing {
|
||||
const I2CSPIDriverConfig &config;
|
||||
|
@ -520,9 +609,15 @@ int I2CSPIDriverBase::module_start(const BusCLIArguments &cli, BusInstanceIterat
|
|||
device_id.devid_s.bus = iterator.bus();
|
||||
|
||||
switch (iterator.busType()) {
|
||||
#if defined(CONFIG_I2C)
|
||||
|
||||
case BOARD_I2C_BUS: device_id.devid_s.bus_type = device::Device::DeviceBusType_I2C; break;
|
||||
#endif // CONFIG_I2C
|
||||
|
||||
#if defined(CONFIG_SPI)
|
||||
|
||||
case BOARD_SPI_BUS: device_id.devid_s.bus_type = device::Device::DeviceBusType_SPI; break;
|
||||
#endif // CONFIG_SPI
|
||||
|
||||
case BOARD_INVALID_BUS: device_id.devid_s.bus_type = device::Device::DeviceBusType_UNKNOWN; break;
|
||||
}
|
||||
|
@ -543,15 +638,21 @@ int I2CSPIDriverBase::module_start(const BusCLIArguments &cli, BusInstanceIterat
|
|||
continue;
|
||||
}
|
||||
|
||||
#if defined(CONFIG_I2C)
|
||||
|
||||
if (cli.i2c_address != 0 && instance->_i2c_address == 0) {
|
||||
PX4_ERR("Bug: driver %s does not pass the I2C address to I2CSPIDriverBase", instance->ItemName());
|
||||
}
|
||||
|
||||
#endif // CONFIG_I2C
|
||||
|
||||
iterator.addInstance(instance);
|
||||
started = true;
|
||||
|
||||
// print some info that we are running
|
||||
switch (iterator.busType()) {
|
||||
#if defined(CONFIG_I2C)
|
||||
|
||||
case BOARD_I2C_BUS:
|
||||
PX4_INFO_RAW("%s #%i on I2C bus %d", instance->ItemName(), runtime_instance, iterator.bus());
|
||||
|
||||
|
@ -570,6 +671,8 @@ int I2CSPIDriverBase::module_start(const BusCLIArguments &cli, BusInstanceIterat
|
|||
PX4_INFO_RAW("\n");
|
||||
|
||||
break;
|
||||
#endif // CONFIG_I2C
|
||||
#if defined(CONFIG_SPI)
|
||||
|
||||
case BOARD_SPI_BUS:
|
||||
PX4_INFO_RAW("%s #%i on SPI bus %d", instance->ItemName(), runtime_instance, iterator.bus());
|
||||
|
@ -585,6 +688,7 @@ int I2CSPIDriverBase::module_start(const BusCLIArguments &cli, BusInstanceIterat
|
|||
PX4_INFO_RAW("\n");
|
||||
|
||||
break;
|
||||
#endif // CONFIG_SPI
|
||||
|
||||
case BOARD_INVALID_BUS:
|
||||
break;
|
||||
|
@ -594,15 +698,18 @@ int I2CSPIDriverBase::module_start(const BusCLIArguments &cli, BusInstanceIterat
|
|||
if (!started && !cli.quiet_start) {
|
||||
PX4_WARN("%s: no instance started (no device on bus?)", px4_get_taskname());
|
||||
|
||||
#if defined(CONFIG_I2C)
|
||||
|
||||
if (iterator.busType() == BOARD_I2C_BUS && cli.i2c_address == 0) {
|
||||
PX4_ERR("%s: driver does not set i2c address", px4_get_taskname());
|
||||
}
|
||||
|
||||
#endif // CONFIG_I2C
|
||||
}
|
||||
|
||||
return started ? 0 : -1;
|
||||
}
|
||||
|
||||
|
||||
int I2CSPIDriverBase::module_stop(BusInstanceIterator &iterator)
|
||||
{
|
||||
bool is_running = false;
|
||||
|
@ -680,14 +787,23 @@ int I2CSPIDriverBase::module_custom_method(const BusCLIArguments &cli, BusInstan
|
|||
|
||||
void I2CSPIDriverBase::print_status()
|
||||
{
|
||||
bool is_i2c_bus = _bus_option == I2CSPIBusOption::I2CExternal || _bus_option == I2CSPIBusOption::I2CInternal;
|
||||
#if defined(CONFIG_I2C)
|
||||
|
||||
if (is_i2c_bus) {
|
||||
if (_bus_option == I2CSPIBusOption::I2CExternal || _bus_option == I2CSPIBusOption::I2CInternal) {
|
||||
PX4_INFO("Running on I2C Bus %i, Address 0x%02X", _bus, get_i2c_address());
|
||||
|
||||
} else {
|
||||
PX4_INFO("Running on SPI Bus %i", _bus);
|
||||
return;
|
||||
}
|
||||
|
||||
#endif // CONFIG_I2C
|
||||
|
||||
#if defined(CONFIG_SPI)
|
||||
|
||||
if (_bus_option == I2CSPIBusOption::SPIExternal || _bus_option == I2CSPIBusOption::SPIInternal) {
|
||||
PX4_INFO("Running on SPI Bus %i", _bus);
|
||||
return;
|
||||
}
|
||||
|
||||
#endif // CONFIG_SPI
|
||||
}
|
||||
|
||||
void I2CSPIDriverBase::request_stop_and_wait()
|
||||
|
@ -705,5 +821,3 @@ void I2CSPIDriverBase::request_stop_and_wait()
|
|||
PX4_ERR("Module did not respond to stop request");
|
||||
}
|
||||
}
|
||||
|
||||
#endif /* BOARD_DISABLE_I2C_SPI */
|
||||
|
|
|
@ -1015,8 +1015,12 @@ int board_register_power_state_notification_cb(power_button_state_notification_t
|
|||
|
||||
enum board_bus_types {
|
||||
BOARD_INVALID_BUS = 0,
|
||||
#if defined(CONFIG_SPI)
|
||||
BOARD_SPI_BUS = 1,
|
||||
#endif // CONFIG_SPI
|
||||
#if defined(CONFIG_I2C)
|
||||
BOARD_I2C_BUS = 2
|
||||
#endif // CONFIG_I2C
|
||||
};
|
||||
|
||||
#if defined(BOARD_HAS_BUS_MANIFEST)
|
||||
|
|
|
@ -35,6 +35,8 @@
|
|||
|
||||
#include <board_config.h>
|
||||
|
||||
#if defined(CONFIG_I2C)
|
||||
|
||||
#define I2C_BUS_MAX_BUS_ITEMS PX4_NUMBER_I2C_BUSES
|
||||
|
||||
struct px4_i2c_bus_t {
|
||||
|
@ -99,3 +101,5 @@ private:
|
|||
int _index{-1};
|
||||
int _external_bus_counter{0};
|
||||
};
|
||||
|
||||
#endif // CONFIG_I2C
|
||||
|
|
|
@ -33,8 +33,7 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include "i2c.h"
|
||||
#include "spi.h"
|
||||
#include <board_config.h>
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
|
@ -43,15 +42,29 @@
|
|||
#include <px4_platform_common/atomic.h>
|
||||
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
|
||||
#include <px4_platform_common/sem.h>
|
||||
#include <board_config.h>
|
||||
#include <drivers/device/spi.h>
|
||||
|
||||
#if defined(CONFIG_I2C)
|
||||
# include "i2c.h"
|
||||
#endif // CONFIG_I2C
|
||||
|
||||
#if defined(CONFIG_SPI)
|
||||
# include "spi.h"
|
||||
#endif // CONFIG_SPI
|
||||
|
||||
#if defined(CONFIG_SPI)
|
||||
# include <drivers/device/spi.h>
|
||||
#endif // CONFIG_SPI
|
||||
|
||||
enum class I2CSPIBusOption : uint8_t {
|
||||
All = 0, ///< select all runnning instances
|
||||
#if defined(CONFIG_I2C)
|
||||
I2CInternal,
|
||||
I2CExternal,
|
||||
#endif // CONFIG_I2C
|
||||
#if defined(CONFIG_SPI)
|
||||
SPIInternal,
|
||||
SPIExternal,
|
||||
#endif // CONFIG_SPI
|
||||
};
|
||||
|
||||
class BusCLIArguments;
|
||||
|
@ -66,11 +79,15 @@ struct I2CSPIDriverConfig {
|
|||
I2CSPIBusOption bus_option;
|
||||
board_bus_types bus_type;
|
||||
int bus;
|
||||
#if defined(CONFIG_I2C)
|
||||
uint8_t i2c_address;
|
||||
#endif // CONFIG_I2C
|
||||
int bus_frequency;
|
||||
#if defined(CONFIG_SPI)
|
||||
spi_drdy_gpio_t drdy_gpio;
|
||||
spi_mode_e spi_mode;
|
||||
uint32_t spi_devid;
|
||||
#endif // CONFIG_SPI
|
||||
int bus_device_index;
|
||||
|
||||
Rotation rotation;
|
||||
|
@ -93,13 +110,17 @@ class I2CSPIInstance : public ListNode<I2CSPIInstance *>
|
|||
{
|
||||
public:
|
||||
virtual ~I2CSPIInstance() = default;
|
||||
#if defined(CONFIG_I2C)
|
||||
virtual int8_t get_i2c_address() {return _i2c_address;}
|
||||
|
||||
#endif // CONFIG_I2C
|
||||
private:
|
||||
I2CSPIInstance(const I2CSPIDriverConfig &config)
|
||||
: _module_name(config.module_name), _bus_option(config.bus_option), _bus(config.bus),
|
||||
_devid_driver_index(config.devid_driver_index), _bus_device_index(config.bus_device_index),
|
||||
_i2c_address(config.i2c_address) {}
|
||||
_devid_driver_index(config.devid_driver_index), _bus_device_index(config.bus_device_index)
|
||||
#if defined(CONFIG_I2C)
|
||||
, _i2c_address(config.i2c_address)
|
||||
#endif // CONFIG_I2C
|
||||
{}
|
||||
|
||||
|
||||
friend class BusInstanceIterator;
|
||||
|
@ -110,14 +131,28 @@ private:
|
|||
const int _bus;
|
||||
const uint16_t _devid_driver_index;
|
||||
const int8_t _bus_device_index;
|
||||
#if defined(CONFIG_I2C)
|
||||
const int8_t _i2c_address; ///< I2C address (optional)
|
||||
#endif // CONFIG_I2C
|
||||
};
|
||||
|
||||
class BusCLIArguments
|
||||
{
|
||||
public:
|
||||
BusCLIArguments(bool i2c_support, bool spi_support)
|
||||
: _i2c_support(i2c_support), _spi_support(spi_support) {}
|
||||
#if defined(CONFIG_I2C) || defined(CONFIG_SPI)
|
||||
:
|
||||
#endif // CONFIG_I2C || CONFIG_SPI
|
||||
#if defined(CONFIG_I2C)
|
||||
_i2c_support(i2c_support)
|
||||
#endif // CONFIG_I2C
|
||||
#if defined(CONFIG_I2C) && defined(CONFIG_SPI)
|
||||
,
|
||||
#endif // CONFIG_I2C && CONFIG_SPI
|
||||
#if defined(CONFIG_SPI)
|
||||
_spi_support(spi_support)
|
||||
#endif // CONFIG_SPI
|
||||
{}
|
||||
|
||||
/**
|
||||
* Parse CLI arguments (for drivers that don't need any custom arguments, otherwise getopt() should be used)
|
||||
|
@ -139,11 +174,15 @@ public:
|
|||
|
||||
I2CSPIBusOption bus_option{I2CSPIBusOption::All};
|
||||
int requested_bus{-1};
|
||||
int chipselect_index{1};
|
||||
int bus_frequency{0};
|
||||
#if defined(CONFIG_SPI)
|
||||
int chipselect_index {1};
|
||||
spi_mode_e spi_mode{SPIDEV_MODE3};
|
||||
uint8_t i2c_address{0}; ///< I2C address (a driver must set the default address)
|
||||
bool quiet_start{false}; ///< do not print a message when startup fails
|
||||
#endif // CONFIG_SPI
|
||||
#if defined(CONFIG_I2C)
|
||||
uint8_t i2c_address {0}; ///< I2C address (a driver must set the default address)
|
||||
#endif // CONFIG_I2C
|
||||
bool quiet_start {false}; ///< do not print a message when startup fails
|
||||
bool keep_running{false}; ///< keep driver running even if no device is detected on startup
|
||||
|
||||
Rotation rotation{ROTATION_NONE}; ///< sensor rotation (MAV_SENSOR_ROTATION_* or distance_sensor_s::ROTATION_*)
|
||||
|
@ -153,8 +192,12 @@ public:
|
|||
void *custom_data{nullptr}; ///< driver-specific custom argument
|
||||
|
||||
// driver defaults, if not specified via CLI
|
||||
int default_spi_frequency{-1}; ///< default spi bus frequency (driver needs to set this) [Hz]
|
||||
int default_i2c_frequency{-1}; ///< default i2c bus frequency (driver needs to set this) [Hz]
|
||||
#if defined(CONFIG_SPI)
|
||||
int default_spi_frequency {-1}; ///< default spi bus frequency (driver needs to set this) [Hz]
|
||||
#endif // CONFIG_SPI
|
||||
#if defined(CONFIG_I2C)
|
||||
int default_i2c_frequency {-1}; ///< default i2c bus frequency (driver needs to set this) [Hz]
|
||||
#endif // CONFIG_I2C
|
||||
|
||||
bool support_keep_running{false}; ///< true if keep_running (see above) is supported
|
||||
|
||||
|
@ -164,8 +207,12 @@ private:
|
|||
char _options[32] {};
|
||||
int _optind{1};
|
||||
const char *_optarg{nullptr};
|
||||
#if defined(CONFIG_I2C)
|
||||
const bool _i2c_support;
|
||||
#endif // CONFIG_I2C
|
||||
#if defined(CONFIG_SPI)
|
||||
const bool _spi_support;
|
||||
#endif // CONFIG_SPI
|
||||
};
|
||||
|
||||
/**
|
||||
|
@ -189,15 +236,23 @@ public:
|
|||
board_bus_types busType() const;
|
||||
int bus() const;
|
||||
uint32_t devid() const;
|
||||
|
||||
#if defined(CONFIG_SPI)
|
||||
spi_drdy_gpio_t DRDYGPIO() const;
|
||||
#endif // CONFIG_SPI
|
||||
|
||||
bool external() const;
|
||||
int externalBusIndex() const;
|
||||
int busDeviceIndex() const;
|
||||
|
||||
void addInstance(I2CSPIInstance *instance);
|
||||
|
||||
#if defined(CONFIG_I2C)
|
||||
static I2CBusIterator::FilterType i2cFilter(I2CSPIBusOption bus_option);
|
||||
#endif // CONFIG_I2C
|
||||
#if defined(CONFIG_SPI)
|
||||
static SPIBusIterator::FilterType spiFilter(I2CSPIBusOption bus_option);
|
||||
#endif // CONFIG_SPI
|
||||
|
||||
const char *moduleName() const { return _module_name; }
|
||||
uint16_t devidDriverIndex() const { return _devid_driver_index; }
|
||||
|
@ -206,9 +261,15 @@ private:
|
|||
const char *_module_name;
|
||||
const I2CSPIBusOption _bus_option;
|
||||
const uint16_t _devid_driver_index;
|
||||
#if defined(CONFIG_I2C)
|
||||
const uint8_t _i2c_address;
|
||||
#endif // CONFIG_I2C
|
||||
#if defined(CONFIG_SPI)
|
||||
SPIBusIterator _spi_bus_iterator;
|
||||
#endif // CONFIG_SPI
|
||||
#if defined(CONFIG_I2C)
|
||||
I2CBusIterator _i2c_bus_iterator;
|
||||
#endif // CONFIG_I2C
|
||||
List<I2CSPIInstance *>::Iterator _current_instance;
|
||||
};
|
||||
|
||||
|
|
|
@ -36,6 +36,8 @@
|
|||
#include <stdint.h>
|
||||
#include <board_config.h>
|
||||
|
||||
#if defined(CONFIG_SPI)
|
||||
|
||||
/*
|
||||
* Helper macros to handle device ID's. They are used to match drivers against SPI buses and chip-select signals.
|
||||
* They match with corresponding definitions in NuttX.
|
||||
|
@ -168,3 +170,5 @@ private:
|
|||
int _external_bus_counter{1};
|
||||
int _bus_device_index{-1};
|
||||
};
|
||||
|
||||
#endif // CONFIG_SPI
|
||||
|
|
|
@ -32,7 +32,8 @@
|
|||
****************************************************************************/
|
||||
|
||||
#include <board_config.h>
|
||||
#ifndef BOARD_DISABLE_I2C_SPI
|
||||
|
||||
#if defined(CONFIG_SPI)
|
||||
|
||||
#include <px4_platform_common/spi.h>
|
||||
|
||||
|
@ -163,4 +164,4 @@ bool SPIBusIterator::next()
|
|||
return false;
|
||||
}
|
||||
|
||||
#endif /* BOARD_DISABLE_I2C_SPI */
|
||||
#endif // CONFIG_SPI
|
||||
|
|
|
@ -36,6 +36,7 @@
|
|||
#include <px4_arch/hw_description.h>
|
||||
#include <px4_platform_common/i2c.h>
|
||||
|
||||
#if defined(CONFIG_I2C)
|
||||
|
||||
static inline constexpr px4_i2c_bus_t initI2CBusInternal(int bus)
|
||||
{
|
||||
|
@ -52,3 +53,4 @@ static inline constexpr px4_i2c_bus_t initI2CBusExternal(int bus)
|
|||
ret.is_external = true;
|
||||
return ret;
|
||||
}
|
||||
#endif // CONFIG_I2C
|
||||
|
|
|
@ -36,6 +36,8 @@
|
|||
#include <px4_arch/hw_description.h>
|
||||
#include <px4_platform_common/spi.h>
|
||||
|
||||
#if defined(CONFIG_SPI)
|
||||
|
||||
#include <imxrt_gpio.h>
|
||||
|
||||
#define CS_IOMUX (IOMUX_CMOS_OUTPUT | IOMUX_PULL_UP_100K | IOMUX_DRIVE_33OHM | IOMUX_SPEED_LOW | IOMUX_SLEW_FAST)
|
||||
|
@ -135,3 +137,4 @@ static inline constexpr SPI::bus_device_external_cfg_t initSPIConfigExternal(SPI
|
|||
ret.drdy_gpio = drdy_gpio;
|
||||
return ret;
|
||||
}
|
||||
#endif // CONFIG_SPI
|
||||
|
|
|
@ -32,9 +32,12 @@
|
|||
****************************************************************************/
|
||||
#pragma once
|
||||
|
||||
#if defined(CONFIG_SPI)
|
||||
|
||||
#include "../../../kinetis/include/px4_arch/spi_hw_description.h"
|
||||
|
||||
constexpr bool validateSPIConfig(const px4_spi_bus_t spi_busses_conf[SPI_BUS_MAX_BUS_ITEMS])
|
||||
{
|
||||
return true;
|
||||
}
|
||||
#endif // CONFIG_SPI
|
||||
|
|
|
@ -36,6 +36,7 @@
|
|||
#include <px4_arch/hw_description.h>
|
||||
#include <px4_platform_common/i2c.h>
|
||||
|
||||
#if defined(CONFIG_I2C)
|
||||
|
||||
static inline constexpr px4_i2c_bus_t initI2CBusInternal(int bus)
|
||||
{
|
||||
|
@ -52,3 +53,4 @@ static inline constexpr px4_i2c_bus_t initI2CBusExternal(int bus)
|
|||
ret.is_external = true;
|
||||
return ret;
|
||||
}
|
||||
#endif // CONFIG_I2C
|
||||
|
|
|
@ -36,6 +36,8 @@
|
|||
#include <px4_arch/hw_description.h>
|
||||
#include <px4_platform_common/spi.h>
|
||||
|
||||
#if defined(CONFIG_SPI)
|
||||
|
||||
#include <kinetis.h>
|
||||
|
||||
static inline constexpr px4_spi_bus_device_t initSPIDevice(uint32_t devid, SPI::CS cs_gpio, SPI::DRDY drdy_gpio = {})
|
||||
|
@ -129,3 +131,5 @@ static inline constexpr SPI::bus_device_external_cfg_t initSPIConfigExternal(SPI
|
|||
ret.drdy_gpio = drdy_gpio;
|
||||
return ret;
|
||||
}
|
||||
|
||||
#endif // CONFIG_SPI
|
||||
|
|
|
@ -32,9 +32,12 @@
|
|||
****************************************************************************/
|
||||
#pragma once
|
||||
|
||||
#if defined(CONFIG_SPI)
|
||||
|
||||
#include "../../../imxrt/include/px4_arch/spi_hw_description.h"
|
||||
|
||||
constexpr bool validateSPIConfig(const px4_spi_bus_t spi_busses_conf[SPI_BUS_MAX_BUS_ITEMS])
|
||||
{
|
||||
return true;
|
||||
}
|
||||
#endif // CONFIG_SPI
|
||||
|
|
|
@ -35,6 +35,8 @@
|
|||
#include <px4_arch/hw_description.h>
|
||||
#include <px4_platform_common/i2c.h>
|
||||
|
||||
#if defined(CONFIG_I2C)
|
||||
|
||||
static inline constexpr px4_i2c_bus_t initI2CBusInternal(int bus)
|
||||
{
|
||||
px4_i2c_bus_t ret{};
|
||||
|
@ -50,3 +52,4 @@ static inline constexpr px4_i2c_bus_t initI2CBusExternal(int bus)
|
|||
ret.is_external = true;
|
||||
return ret;
|
||||
}
|
||||
#endif // CONFIG_I2C
|
||||
|
|
|
@ -35,6 +35,8 @@
|
|||
#include <px4_arch/hw_description.h>
|
||||
#include <px4_platform_common/i2c.h>
|
||||
|
||||
#if defined(CONFIG_I2C)
|
||||
|
||||
static inline constexpr px4_i2c_bus_t initI2CBusInternal(int bus)
|
||||
{
|
||||
px4_i2c_bus_t ret{};
|
||||
|
@ -50,3 +52,4 @@ static inline constexpr px4_i2c_bus_t initI2CBusExternal(int bus)
|
|||
ret.is_external = true;
|
||||
return ret;
|
||||
}
|
||||
#endif // CONFIG_I2C
|
||||
|
|
|
@ -36,6 +36,7 @@
|
|||
#include <px4_arch/hw_description.h>
|
||||
#include <px4_platform_common/i2c.h>
|
||||
|
||||
#if defined(CONFIG_I2C)
|
||||
|
||||
static inline constexpr px4_i2c_bus_t initI2CBusInternal(int bus)
|
||||
{
|
||||
|
@ -52,3 +53,4 @@ static inline constexpr px4_i2c_bus_t initI2CBusExternal(int bus)
|
|||
ret.is_external = true;
|
||||
return ret;
|
||||
}
|
||||
#endif // CONFIG_I2C
|
||||
|
|
|
@ -36,6 +36,7 @@
|
|||
#include <px4_arch/hw_description.h>
|
||||
#include <px4_platform_common/spi.h>
|
||||
|
||||
#if defined(CONFIG_SPI)
|
||||
|
||||
#include <stm32_gpio.h>
|
||||
|
||||
|
@ -168,3 +169,5 @@ constexpr bool validateSPIConfig(const px4_spi_bus_all_hw_t spi_buses_conf[BOARD
|
|||
|
||||
return false;
|
||||
}
|
||||
|
||||
#endif // CONFIG_SPI
|
||||
|
|
|
@ -34,6 +34,8 @@
|
|||
|
||||
#include "../../../stm32_common/include/px4_arch/spi_hw_description.h"
|
||||
|
||||
#if defined(CONFIG_SPI)
|
||||
|
||||
constexpr bool validateSPIConfig(const px4_spi_bus_t spi_busses_conf[SPI_BUS_MAX_BUS_ITEMS])
|
||||
{
|
||||
const bool nuttx_enabled_spi_buses[] = {
|
||||
|
@ -84,3 +86,5 @@ constexpr bool validateSPIConfig(const px4_spi_bus_t spi_busses_conf[SPI_BUS_MAX
|
|||
|
||||
return false;
|
||||
}
|
||||
|
||||
#endif // CONFIG_SPI
|
||||
|
|
|
@ -32,6 +32,8 @@
|
|||
****************************************************************************/
|
||||
#pragma once
|
||||
|
||||
#if defined(CONFIG_SPI)
|
||||
|
||||
#include "../../../stm32_common/include/px4_arch/spi_hw_description.h"
|
||||
|
||||
constexpr bool validateSPIConfig(const px4_spi_bus_t spi_busses_conf[SPI_BUS_MAX_BUS_ITEMS])
|
||||
|
@ -84,3 +86,5 @@ constexpr bool validateSPIConfig(const px4_spi_bus_t spi_busses_conf[SPI_BUS_MAX
|
|||
|
||||
return false;
|
||||
}
|
||||
|
||||
#endif // CONFIG_SPI
|
||||
|
|
|
@ -34,6 +34,8 @@
|
|||
|
||||
#include "../../../stm32_common/include/px4_arch/spi_hw_description.h"
|
||||
|
||||
#if defined(CONFIG_SPI)
|
||||
|
||||
constexpr bool validateSPIConfig(const px4_spi_bus_t spi_busses_conf[SPI_BUS_MAX_BUS_ITEMS])
|
||||
{
|
||||
const bool nuttx_enabled_spi_buses[] = {
|
||||
|
@ -84,3 +86,5 @@ constexpr bool validateSPIConfig(const px4_spi_bus_t spi_busses_conf[SPI_BUS_MAX
|
|||
|
||||
return false;
|
||||
}
|
||||
|
||||
#endif // CONFIG_SPI
|
||||
|
|
|
@ -35,6 +35,7 @@
|
|||
|
||||
#include <px4_platform_common/i2c.h>
|
||||
|
||||
#if defined(CONFIG_I2C)
|
||||
|
||||
static inline constexpr px4_i2c_bus_t initI2CBusInternal(int bus)
|
||||
{
|
||||
|
@ -51,3 +52,4 @@ static inline constexpr px4_i2c_bus_t initI2CBusExternal(int bus)
|
|||
ret.is_external = true;
|
||||
return ret;
|
||||
}
|
||||
#endif // CONFIG_I2C
|
||||
|
|
|
@ -35,6 +35,8 @@
|
|||
|
||||
#include <px4_platform_common/spi.h>
|
||||
|
||||
#if defined(CONFIG_SPI)
|
||||
|
||||
static inline constexpr px4_spi_bus_device_t initSPIDevice(uint8_t devid_driver, uint8_t cs_index)
|
||||
{
|
||||
px4_spi_bus_device_t ret{};
|
||||
|
@ -57,3 +59,4 @@ static inline constexpr px4_spi_bus_t initSPIBus(int bus, const px4_spi_bus_devi
|
|||
ret.requires_locking = false;
|
||||
return ret;
|
||||
}
|
||||
#endif // CONFIG_SPI
|
||||
|
|
|
@ -42,6 +42,7 @@
|
|||
#include <px4_platform_common/px4_config.h>
|
||||
#include <drivers/device/i2c.h>
|
||||
|
||||
#if defined(CONFIG_I2C)
|
||||
|
||||
class BMP280_I2C: public device::I2C, public bmp280::IBMP280
|
||||
{
|
||||
|
@ -116,3 +117,5 @@ BMP280_I2C::get_calibration(uint8_t addr)
|
|||
return nullptr;
|
||||
}
|
||||
}
|
||||
|
||||
#endif // CONFIG_I2C
|
||||
|
|
|
@ -42,6 +42,8 @@
|
|||
#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
|
||||
|
@ -132,3 +134,4 @@ BMP280_SPI::get_calibration(uint8_t addr)
|
|||
return nullptr;
|
||||
}
|
||||
}
|
||||
#endif // CONFIG_SPI
|
||||
|
|
|
@ -38,7 +38,7 @@
|
|||
*/
|
||||
#pragma once
|
||||
|
||||
#include <drivers/device/spi.h>
|
||||
#include <px4_platform_common/i2c_spi_buses.h>
|
||||
|
||||
#define BMP280_ADDR_CAL 0x88 /* address of 12x 2 bytes calibration data */
|
||||
#define BMP280_ADDR_DATA 0xF7 /* address of 2x 3 bytes p-t data */
|
||||
|
@ -158,5 +158,9 @@ public:
|
|||
|
||||
|
||||
/* interface factories */
|
||||
#if defined(CONFIG_SPI)
|
||||
extern bmp280::IBMP280 *bmp280_spi_interface(uint8_t busnum, uint32_t device, int bus_frequency, spi_mode_e spi_mode);
|
||||
#endif // CONFIG_SPI
|
||||
#if defined(CONFIG_I2C)
|
||||
extern bmp280::IBMP280 *bmp280_i2c_interface(uint8_t busnum, uint32_t device, int bus_frequency);
|
||||
#endif // CONFIG_I2C
|
||||
|
|
|
@ -37,6 +37,8 @@
|
|||
|
||||
#include "BMP280.hpp"
|
||||
|
||||
#include <drivers/drv_sensor.h>
|
||||
|
||||
extern "C" { __EXPORT int bmp280_main(int argc, char *argv[]); }
|
||||
|
||||
void
|
||||
|
@ -45,8 +47,12 @@ BMP280::print_usage()
|
|||
PRINT_MODULE_USAGE_NAME("bmp280", "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();
|
||||
}
|
||||
|
||||
|
@ -54,21 +60,30 @@ I2CSPIDriverBase *BMP280::instantiate(const I2CSPIDriverConfig &config, int runt
|
|||
{
|
||||
bmp280::IBMP280 *interface = nullptr;
|
||||
|
||||
#if defined(CONFIG_I2C)
|
||||
|
||||
if (config.bus_type == BOARD_I2C_BUS) {
|
||||
interface = bmp280_i2c_interface(config.bus, config.i2c_address, config.bus_frequency);
|
||||
|
||||
} else if (config.bus_type == BOARD_SPI_BUS) {
|
||||
}
|
||||
|
||||
#endif // CONFIG_I2C
|
||||
#if defined(CONFIG_SPI)
|
||||
|
||||
if (config.bus_type == BOARD_SPI_BUS) {
|
||||
interface = bmp280_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 (devid 0x%" PRIx32 ")", config.bus, config.spi_devid);
|
||||
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 (devid 0x%" PRIx32 ")", config.bus, config.spi_devid);
|
||||
PX4_DEBUG("no device on bus %i", config.bus);
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
|
@ -92,9 +107,13 @@ bmp280_main(int argc, char *argv[])
|
|||
{
|
||||
using ThisDriver = BMP280;
|
||||
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);
|
||||
|
||||
|
|
|
@ -39,6 +39,8 @@
|
|||
|
||||
#include <lib/drivers/device/i2c.h>
|
||||
|
||||
#if defined(CONFIG_I2C)
|
||||
|
||||
namespace dps310
|
||||
{
|
||||
|
||||
|
@ -89,3 +91,5 @@ DPS310_I2C::write(unsigned address, void *data, unsigned count)
|
|||
}
|
||||
|
||||
} // namespace dps310
|
||||
|
||||
#endif // CONFIG_I2C
|
||||
|
|
|
@ -36,7 +36,9 @@
|
|||
namespace dps310
|
||||
{
|
||||
extern device::Device *DPS310_SPI_interface(uint8_t bus, uint32_t device, int bus_frequency, spi_mode_e spi_mode);
|
||||
#if defined(CONFIG_I2C)
|
||||
extern device::Device *DPS310_I2C_interface(uint8_t bus, uint32_t device, int bus_frequency);
|
||||
#endif // CONFIG_I2C
|
||||
}
|
||||
|
||||
#include <px4_platform_common/getopt.h>
|
||||
|
@ -50,8 +52,12 @@ DPS310::print_usage()
|
|||
PRINT_MODULE_USAGE_NAME("dps310", "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(0x77);
|
||||
#else
|
||||
PRINT_MODULE_USAGE_PARAMS_I2C_SPI_DRIVER(false, true);
|
||||
#endif
|
||||
PRINT_MODULE_USAGE_DEFAULT_COMMANDS();
|
||||
}
|
||||
|
||||
|
@ -59,12 +65,16 @@ I2CSPIDriverBase *DPS310::instantiate(const I2CSPIDriverConfig &config, int runt
|
|||
{
|
||||
device::Device *interface = nullptr;
|
||||
|
||||
#if defined(CONFIG_I2C)
|
||||
|
||||
if (config.bus_type == BOARD_I2C_BUS) {
|
||||
interface = DPS310_I2C_interface(config.bus, config.i2c_address, config.bus_frequency);
|
||||
|
||||
} else if (config.bus_type == BOARD_SPI_BUS) {
|
||||
interface = DPS310_SPI_interface(config.bus, config.spi_devid, config.bus_frequency, config.spi_mode);
|
||||
}
|
||||
} else
|
||||
#endif // CONFIG_I2C
|
||||
if (config.bus_type == BOARD_SPI_BUS) {
|
||||
interface = DPS310_SPI_interface(config.bus, config.spi_devid, config.bus_frequency, config.spi_mode);
|
||||
}
|
||||
|
||||
if (interface == nullptr) {
|
||||
PX4_ERR("failed creating interface for bus %i (devid 0x%" PRIx32 ")", config.bus, config.spi_devid);
|
||||
|
@ -95,9 +105,15 @@ I2CSPIDriverBase *DPS310::instantiate(const I2CSPIDriverConfig &config, int runt
|
|||
extern "C" int dps310_main(int argc, char *argv[])
|
||||
{
|
||||
using ThisDriver = DPS310;
|
||||
BusCLIArguments cli{true, true};
|
||||
|
||||
#if defined(CONFIG_I2C)
|
||||
BusCLIArguments cli {true, true};
|
||||
cli.i2c_address = 0x77;
|
||||
cli.default_i2c_frequency = 400000;
|
||||
#else
|
||||
BusCLIArguments cli {false, true};
|
||||
#endif // CONFIG_I2C
|
||||
|
||||
cli.default_spi_frequency = 10 * 1000 * 1000;
|
||||
|
||||
const char *verb = cli.parseDefaultArguments(argc, argv);
|
||||
|
|
|
@ -39,17 +39,19 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include "board_config.h"
|
||||
|
||||
#include <string.h>
|
||||
|
||||
#include <drivers/device/i2c.h>
|
||||
#if defined(CONFIG_I2C)
|
||||
# include <drivers/device/i2c.h>
|
||||
#endif // CONFIG_I2C
|
||||
|
||||
#include <drivers/device/device.h>
|
||||
#include <drivers/device/spi.h>
|
||||
#include <lib/cdev/CDev.hpp>
|
||||
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
|
||||
#include <systemlib/err.h>
|
||||
#include <uORB/uORB.h>
|
||||
|
||||
#include "board_config.h"
|
||||
|
||||
#define ADDR_RESET_CMD 0x1E /* write to this address to reset chip */
|
||||
#define ADDR_PROM_SETUP 0xA0 /* address of 8x 2 bytes factory and calibration data */
|
||||
|
@ -96,7 +98,10 @@ extern bool crc4(uint16_t *n_prom);
|
|||
/* interface factories */
|
||||
extern device::Device *MS5611_spi_interface(ms5611::prom_u &prom_buf, uint32_t devid, uint8_t busnum, int bus_frequency,
|
||||
spi_mode_e spi_mode);
|
||||
|
||||
#if defined(CONFIG_I2C)
|
||||
extern device::Device *MS5611_i2c_interface(ms5611::prom_u &prom_buf, uint32_t devid, uint8_t busnum,
|
||||
int bus_frequency);
|
||||
#endif // CONFIG_I2C
|
||||
|
||||
typedef device::Device *(*MS5611_constructor)(ms5611::prom_u &prom_buf, uint32_t devid, uint8_t busnum);
|
||||
|
|
|
@ -39,6 +39,8 @@
|
|||
|
||||
#include <drivers/device/i2c.h>
|
||||
|
||||
#if defined(CONFIG_I2C)
|
||||
|
||||
#include "ms5611.h"
|
||||
|
||||
class MS5611_I2C : public device::I2C
|
||||
|
@ -238,3 +240,5 @@ MS5611_I2C::_read_prom()
|
|||
/* calculate CRC and return success/failure accordingly */
|
||||
return (ms5611::crc4(&_prom.c[0]) && !bits_stuck) ? PX4_OK : -EIO;
|
||||
}
|
||||
|
||||
#endif // CONFIG_I2C
|
||||
|
|
|
@ -45,12 +45,16 @@ I2CSPIDriverBase *MS5611::instantiate(const I2CSPIDriverConfig &config, int runt
|
|||
ms5611::prom_u prom_buf;
|
||||
device::Device *interface = nullptr;
|
||||
|
||||
#if defined(CONFIG_I2C)
|
||||
|
||||
if (config.bus_type == BOARD_I2C_BUS) {
|
||||
interface = MS5611_i2c_interface(prom_buf, config.spi_devid, config.bus, config.bus_frequency);
|
||||
|
||||
} else if (config.bus_type == BOARD_SPI_BUS) {
|
||||
interface = MS5611_spi_interface(prom_buf, config.spi_devid, config.bus, config.bus_frequency, config.spi_mode);
|
||||
}
|
||||
} else
|
||||
#endif // CONFIG_I2C
|
||||
if (config.bus_type == BOARD_SPI_BUS) {
|
||||
interface = MS5611_spi_interface(prom_buf, config.spi_devid, config.bus, config.bus_frequency, config.spi_mode);
|
||||
}
|
||||
|
||||
if (interface == nullptr) {
|
||||
PX4_ERR("alloc failed");
|
||||
|
@ -83,7 +87,11 @@ void MS5611::print_usage()
|
|||
PRINT_MODULE_USAGE_NAME("ms5611", "driver");
|
||||
PRINT_MODULE_USAGE_SUBCATEGORY("baro");
|
||||
PRINT_MODULE_USAGE_COMMAND("start");
|
||||
#if defined(CONFIG_I2C)
|
||||
PRINT_MODULE_USAGE_PARAMS_I2C_SPI_DRIVER(true, true);
|
||||
#else
|
||||
PRINT_MODULE_USAGE_PARAMS_I2C_SPI_DRIVER(false, true);
|
||||
#endif
|
||||
PRINT_MODULE_USAGE_PARAM_STRING('T', "5611", "5607|5611", "Device type", true);
|
||||
PRINT_MODULE_USAGE_DEFAULT_COMMANDS();
|
||||
}
|
||||
|
@ -92,8 +100,13 @@ extern "C" int ms5611_main(int argc, char *argv[])
|
|||
{
|
||||
using ThisDriver = MS5611;
|
||||
int ch;
|
||||
BusCLIArguments cli{true, true};
|
||||
#if defined(CONFIG_I2C)
|
||||
BusCLIArguments cli {true, true};
|
||||
cli.default_i2c_frequency = 400000;
|
||||
cli.i2c_address = MS5611_ADDRESS_1;
|
||||
#else
|
||||
BusCLIArguments cli {false, true};
|
||||
#endif
|
||||
cli.default_spi_frequency = 20 * 1000 * 1000;
|
||||
uint16_t dev_type_driver = DRV_BARO_DEVTYPE_MS5611;
|
||||
|
||||
|
@ -120,8 +133,6 @@ extern "C" int ms5611_main(int argc, char *argv[])
|
|||
return -1;
|
||||
}
|
||||
|
||||
cli.i2c_address = MS5611_ADDRESS_1;
|
||||
|
||||
BusInstanceIterator iterator(MODULE_NAME, cli, dev_type_driver);
|
||||
|
||||
if (!strcmp(verb, "start")) {
|
||||
|
|
|
@ -42,6 +42,8 @@
|
|||
|
||||
#include "I2C.hpp"
|
||||
|
||||
#if defined(CONFIG_I2C)
|
||||
|
||||
#include <px4_platform_common/i2c_spi_buses.h>
|
||||
#include <nuttx/i2c/i2c_master.h>
|
||||
|
||||
|
@ -236,3 +238,5 @@ I2C::transfer(const uint8_t *send, const unsigned send_len, uint8_t *recv, const
|
|||
}
|
||||
|
||||
} // namespace device
|
||||
|
||||
#endif // CONFIG_I2C
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
* Copyright (C) 2012-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
|
||||
|
@ -31,26 +31,23 @@
|
|||
*
|
||||
****************************************************************************/
|
||||
|
||||
#pragma once
|
||||
|
||||
/**
|
||||
* @file i2c.h
|
||||
* @file I2C.hpp
|
||||
*
|
||||
* Base class for devices connected via I2C.
|
||||
*/
|
||||
|
||||
#ifndef _DEVICE_I2C_H
|
||||
#define _DEVICE_I2C_H
|
||||
|
||||
#include "../CDev.hpp"
|
||||
#include <px4_platform_common/i2c.h>
|
||||
|
||||
#if defined(CONFIG_I2C)
|
||||
|
||||
#include <nuttx/i2c/i2c_master.h>
|
||||
|
||||
struct I2CSPIDriverConfig;
|
||||
|
||||
#if !defined(CONFIG_I2C)
|
||||
# error I2C support requires CONFIG_I2C
|
||||
#endif
|
||||
|
||||
namespace device __EXPORT
|
||||
{
|
||||
|
||||
|
@ -123,4 +120,4 @@ private:
|
|||
|
||||
} // namespace device
|
||||
|
||||
#endif /* _DEVICE_I2C_H */
|
||||
#endif // CONFIG_I2C
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012-2019, 2021 PX4 Development Team. All rights reserved.
|
||||
* Copyright (C) 2012-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
|
||||
|
@ -32,21 +32,16 @@
|
|||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file spi.cpp
|
||||
* @file SPI.cpp
|
||||
*
|
||||
* Base class for devices connected via SPI.
|
||||
*
|
||||
* @todo Work out if caching the mode/frequency would save any time.
|
||||
*
|
||||
* @todo A separate bus/device abstraction would allow for mixed interrupt-mode
|
||||
* and non-interrupt-mode clients to arbitrate for the bus. As things stand,
|
||||
* a bus shared between clients of both kinds is vulnerable to races between
|
||||
* the two, where an interrupt-mode client will ignore the lock held by the
|
||||
* non-interrupt-mode client.
|
||||
*/
|
||||
|
||||
#include "SPI.hpp"
|
||||
|
||||
#if defined(CONFIG_SPI)
|
||||
|
||||
#include <px4_platform_common/i2c_spi_buses.h>
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
#include <nuttx/arch.h>
|
||||
|
@ -237,3 +232,4 @@ SPI::_transferhword(uint16_t *send, uint16_t *recv, unsigned len)
|
|||
}
|
||||
|
||||
} // namespace device
|
||||
#endif // CONFIG_SPI
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
* Copyright (C) 2012-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
|
||||
|
@ -31,16 +31,18 @@
|
|||
*
|
||||
****************************************************************************/
|
||||
|
||||
#pragma once
|
||||
|
||||
/**
|
||||
* @file SPI.hpp
|
||||
*
|
||||
* Base class for devices connected via SPI.
|
||||
*/
|
||||
|
||||
#ifndef _DEVICE_SPI_H
|
||||
#define _DEVICE_SPI_H
|
||||
|
||||
#include "../CDev.hpp"
|
||||
#include <px4_platform_common/spi.h>
|
||||
|
||||
#if defined(CONFIG_SPI)
|
||||
|
||||
#include <nuttx/spi/spi.h>
|
||||
#include <px4_platform_common/spi.h>
|
||||
|
@ -178,4 +180,4 @@ protected:
|
|||
|
||||
} // namespace device
|
||||
|
||||
#endif /* _DEVICE_SPI_H */
|
||||
#endif // CONFIG_SPI
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2016-2020 PX4 Development Team. All rights reserved.
|
||||
* Copyright (c) 2016-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
|
||||
|
@ -42,6 +42,8 @@
|
|||
|
||||
#include "I2C.hpp"
|
||||
|
||||
#if defined(CONFIG_I2C)
|
||||
|
||||
#ifdef __PX4_LINUX
|
||||
|
||||
#include <linux/i2c.h>
|
||||
|
@ -181,3 +183,5 @@ I2C::transfer(const uint8_t *send, const unsigned send_len, uint8_t *recv, const
|
|||
} // namespace device
|
||||
|
||||
#endif // __PX4_LINUX
|
||||
|
||||
#endif // CONFIG_I2C
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2016-2020 PX4 Development Team. All rights reserved.
|
||||
* Copyright (C) 2016-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
|
||||
|
@ -31,18 +31,19 @@
|
|||
*
|
||||
****************************************************************************/
|
||||
|
||||
#pragma once
|
||||
|
||||
/**
|
||||
* @file I2C.hpp
|
||||
*
|
||||
* Base class for devices connected via I2C.
|
||||
*/
|
||||
|
||||
#ifndef _DEVICE_I2C_H
|
||||
#define _DEVICE_I2C_H
|
||||
|
||||
#include "../CDev.hpp"
|
||||
#include <px4_platform_common/i2c.h>
|
||||
|
||||
#if defined(CONFIG_I2C)
|
||||
|
||||
struct I2CSPIDriverConfig;
|
||||
|
||||
namespace device __EXPORT
|
||||
|
@ -112,4 +113,4 @@ private:
|
|||
|
||||
} // namespace device
|
||||
|
||||
#endif /* _DEVICE_I2C_H */
|
||||
#endif // CONFIG_I2C
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2019 PX4 Development Team. All rights reserved.
|
||||
* Copyright (C) 2019-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
|
||||
|
@ -40,6 +40,8 @@
|
|||
|
||||
#include "SPI.hpp"
|
||||
|
||||
#if defined(CONFIG_SPI)
|
||||
|
||||
#ifdef __PX4_LINUX
|
||||
|
||||
#include <fcntl.h>
|
||||
|
@ -73,7 +75,6 @@ SPI::SPI(const I2CSPIDriverConfig &config)
|
|||
{
|
||||
}
|
||||
|
||||
|
||||
SPI::~SPI()
|
||||
{
|
||||
if (_fd >= 0) {
|
||||
|
@ -197,3 +198,4 @@ SPI::transferhword(uint16_t *send, uint16_t *recv, unsigned len)
|
|||
} // namespace device
|
||||
|
||||
#endif // __PX4_LINUX
|
||||
#endif // CONFIG_SPI
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2019 PX4 Development Team. All rights reserved.
|
||||
* Copyright (C) 2019-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
|
||||
|
@ -31,18 +31,19 @@
|
|||
*
|
||||
****************************************************************************/
|
||||
|
||||
#pragma once
|
||||
|
||||
/**
|
||||
* @file SPI.hpp
|
||||
*
|
||||
* Base class for devices connected via SPI.
|
||||
*/
|
||||
|
||||
#ifndef _DEVICE_SPI_H
|
||||
#define _DEVICE_SPI_H
|
||||
|
||||
#include "../CDev.hpp"
|
||||
#include <px4_platform_common/spi.h>
|
||||
|
||||
#if defined(CONFIG_SPI)
|
||||
|
||||
#ifdef __PX4_LINUX
|
||||
|
||||
#include <fcntl.h>
|
||||
|
@ -201,4 +202,4 @@ enum spi_mode_e {
|
|||
};
|
||||
#endif // __PX4_LINUX
|
||||
|
||||
#endif /* _DEVICE_SPI_H */
|
||||
#endif // CONFIG_SPI
|
||||
|
|
|
@ -84,55 +84,80 @@ bool I2CSPICLITest::test_basic()
|
|||
|
||||
{
|
||||
BusCLIArguments cli{true, true};
|
||||
#if defined(CONFIG_I2C)
|
||||
cli.default_i2c_frequency = 1234;
|
||||
#endif // CONFIG_I2C
|
||||
#if defined(CONFIG_SPI)
|
||||
cli.default_spi_frequency = 12345;
|
||||
#endif // CONFIG_SPI
|
||||
const char *argv[] = { "start", "-I" };
|
||||
CLIArgsHelper cli_args(argv, 2);
|
||||
const char *verb = cli.parseDefaultArguments(cli_args.argc, cli_args.argv);
|
||||
ut_assert_true(verb != nullptr);
|
||||
ut_assert_true(strcmp(verb, "start") == 0);
|
||||
#if defined(CONFIG_I2C)
|
||||
ut_assert_true(cli.bus_option == I2CSPIBusOption::I2CInternal);
|
||||
ut_assert_true(cli.bus_frequency == cli.default_i2c_frequency);
|
||||
#endif // CONFIG_I2C
|
||||
}
|
||||
|
||||
{
|
||||
BusCLIArguments cli{true, true};
|
||||
#if defined(CONFIG_I2C)
|
||||
cli.default_i2c_frequency = 1234;
|
||||
#endif // CONFIG_I2C
|
||||
#if defined(CONFIG_SPI)
|
||||
cli.default_spi_frequency = 12345;
|
||||
#endif // CONFIG_SPI
|
||||
const char *argv[] = { "start", "-s", "-f", "10"};
|
||||
CLIArgsHelper cli_args(argv, 4);
|
||||
const char *verb = cli.parseDefaultArguments(cli_args.argc, cli_args.argv);
|
||||
ut_assert_true(verb != nullptr);
|
||||
ut_assert_true(strcmp(verb, "start") == 0);
|
||||
#if defined(CONFIG_SPI)
|
||||
ut_assert_true(cli.bus_option == I2CSPIBusOption::SPIInternal);
|
||||
#endif // CONFIG_SPI
|
||||
ut_assert_true(cli.bus_frequency == 10000);
|
||||
}
|
||||
|
||||
{
|
||||
BusCLIArguments cli{true, true};
|
||||
#if defined(CONFIG_I2C)
|
||||
cli.default_i2c_frequency = 11111;
|
||||
#endif // CONFIG_I2C
|
||||
#if defined(CONFIG_SPI)
|
||||
cli.default_spi_frequency = 22222;
|
||||
#endif // CONFIG_SPI
|
||||
const char *argv[] = { "-S", "-b", "3", "stop"};
|
||||
CLIArgsHelper cli_args(argv, 4);
|
||||
const char *verb = cli.parseDefaultArguments(cli_args.argc, cli_args.argv);
|
||||
ut_assert_true(verb != nullptr);
|
||||
ut_assert_true(strcmp(verb, "stop") == 0);
|
||||
#if defined(CONFIG_SPI)
|
||||
ut_assert_true(cli.bus_option == I2CSPIBusOption::SPIExternal);
|
||||
#endif // CONFIG_SPI
|
||||
ut_assert_true(cli.requested_bus == 3);
|
||||
}
|
||||
|
||||
{
|
||||
BusCLIArguments cli{true, true};
|
||||
#if defined(CONFIG_I2C)
|
||||
cli.default_i2c_frequency = 11111;
|
||||
cli.default_spi_frequency = 22222;
|
||||
cli.i2c_address = 0xab;
|
||||
#endif // CONFIG_I2C
|
||||
#if defined(CONFIG_SPI)
|
||||
cli.default_spi_frequency = 22222;
|
||||
#endif // CONFIG_SPI
|
||||
|
||||
const char *argv[] = { "start", "-X", "-a", "0x14"};
|
||||
CLIArgsHelper cli_args(argv, 4);
|
||||
const char *verb = cli.parseDefaultArguments(cli_args.argc, cli_args.argv);
|
||||
ut_assert_true(verb != nullptr);
|
||||
ut_assert_true(strcmp(verb, "start") == 0);
|
||||
#if defined(CONFIG_I2C)
|
||||
ut_assert_true(cli.bus_option == I2CSPIBusOption::I2CExternal);
|
||||
ut_assert_true(cli.i2c_address == 0x14);
|
||||
#endif // CONFIG_I2C
|
||||
}
|
||||
|
||||
return true;
|
||||
|
@ -143,7 +168,9 @@ bool I2CSPICLITest::test_invalid()
|
|||
{
|
||||
// SPI disabled, but SPI option provided
|
||||
BusCLIArguments cli{true, false};
|
||||
#if defined(CONFIG_I2C)
|
||||
cli.default_i2c_frequency = 11111;
|
||||
#endif // CONFIG_I2C
|
||||
const char *argv[] = { "start", "-S"};
|
||||
CLIArgsHelper cli_args(argv, 2);
|
||||
const char *verb = cli.parseDefaultArguments(cli_args.argc, cli_args.argv);
|
||||
|
@ -153,8 +180,12 @@ bool I2CSPICLITest::test_invalid()
|
|||
{
|
||||
// Unknown argument
|
||||
BusCLIArguments cli{true, true};
|
||||
#if defined(CONFIG_I2C)
|
||||
cli.default_i2c_frequency = 11111;
|
||||
#endif // CONFIG_I2C
|
||||
#if defined(CONFIG_SPI)
|
||||
cli.default_spi_frequency = 22222;
|
||||
#endif // CONFIG_SPI
|
||||
const char *argv[] = { "start", "-I", "-x", "3"};
|
||||
CLIArgsHelper cli_args(argv, 3);
|
||||
const char *verb = cli.parseDefaultArguments(cli_args.argc, cli_args.argv);
|
||||
|
@ -173,8 +204,12 @@ bool I2CSPICLITest::test_invalid()
|
|||
{
|
||||
// Another unknown argument
|
||||
BusCLIArguments cli{true, true};
|
||||
#if defined(CONFIG_I2C)
|
||||
cli.default_i2c_frequency = 11111;
|
||||
#endif // CONFIG_I2C
|
||||
#if defined(CONFIG_SPI)
|
||||
cli.default_spi_frequency = 22222;
|
||||
#endif // CONFIG_SPI
|
||||
const char *argv[] = { "-x", "start" };
|
||||
CLIArgsHelper cli_args(argv, 2);
|
||||
const char *verb = cli.parseDefaultArguments(cli_args.argc, cli_args.argv);
|
||||
|
@ -188,8 +223,12 @@ bool I2CSPICLITest::test_custom()
|
|||
{
|
||||
// custom argument
|
||||
BusCLIArguments cli{true, true};
|
||||
#if defined(CONFIG_I2C)
|
||||
cli.default_i2c_frequency = 11111;
|
||||
#endif // CONFIG_I2C
|
||||
#if defined(CONFIG_SPI)
|
||||
cli.default_spi_frequency = 22222;
|
||||
#endif // CONFIG_SPI
|
||||
const char *argv[] = { "start", "-T", "432", "-a", "12"};
|
||||
CLIArgsHelper cli_args(argv, 5);
|
||||
int ch;
|
||||
|
@ -216,8 +255,12 @@ bool I2CSPICLITest::test_custom()
|
|||
{
|
||||
// duplicate argument
|
||||
BusCLIArguments cli{true, true};
|
||||
#if defined(CONFIG_I2C)
|
||||
cli.default_i2c_frequency = 11111;
|
||||
#endif // CONFIG_I2C
|
||||
#if defined(CONFIG_SPI)
|
||||
cli.default_spi_frequency = 22222;
|
||||
#endif // CONFIG_SPI
|
||||
const char *argv[] = { "start"};
|
||||
CLIArgsHelper cli_args(argv, 1);
|
||||
int ch;
|
||||
|
|
Loading…
Reference in New Issue