mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-02 03:49:12 +08:00
Merge branch 'fat-dma-spi'
This commit is contained in:
@@ -73,20 +73,20 @@ then
|
|||||||
#
|
#
|
||||||
# Load microSD params
|
# Load microSD params
|
||||||
#
|
#
|
||||||
if ramtron start
|
#if ramtron start
|
||||||
then
|
#then
|
||||||
param select /ramtron/params
|
# param select /ramtron/params
|
||||||
if [ -f /ramtron/params ]
|
# if [ -f /ramtron/params ]
|
||||||
then
|
# then
|
||||||
param load /ramtron/params
|
# param load /ramtron/params
|
||||||
fi
|
# fi
|
||||||
else
|
#else
|
||||||
param select /fs/microsd/params
|
param select /fs/microsd/params
|
||||||
if [ -f /fs/microsd/params ]
|
if [ -f /fs/microsd/params ]
|
||||||
then
|
then
|
||||||
param load /fs/microsd/params
|
param load /fs/microsd/params
|
||||||
fi
|
fi
|
||||||
fi
|
#fi
|
||||||
|
|
||||||
#
|
#
|
||||||
# Start system state indicator
|
# Start system state indicator
|
||||||
|
|||||||
@@ -38,7 +38,31 @@ CONFIG_ARCH_MATH_H=y
|
|||||||
#
|
#
|
||||||
# Debug Options
|
# Debug Options
|
||||||
#
|
#
|
||||||
# CONFIG_DEBUG is not set
|
CONFIG_DEBUG=n
|
||||||
|
CONFIG_DEBUG_VERBOSE=n
|
||||||
|
|
||||||
|
#
|
||||||
|
# Subsystem Debug Options
|
||||||
|
#
|
||||||
|
# CONFIG_DEBUG_MM is not set
|
||||||
|
# CONFIG_DEBUG_SCHED is not set
|
||||||
|
# CONFIG_DEBUG_USB is not set
|
||||||
|
CONFIG_DEBUG_FS=y
|
||||||
|
# CONFIG_DEBUG_LIB is not set
|
||||||
|
# CONFIG_DEBUG_BINFMT is not set
|
||||||
|
# CONFIG_DEBUG_GRAPHICS is not set
|
||||||
|
|
||||||
|
#
|
||||||
|
# Driver Debug Options
|
||||||
|
#
|
||||||
|
# CONFIG_DEBUG_ANALOG is not set
|
||||||
|
# CONFIG_DEBUG_I2C is not set
|
||||||
|
# CONFIG_DEBUG_SPI is not set
|
||||||
|
# CONFIG_DEBUG_SDIO is not set
|
||||||
|
# CONFIG_DEBUG_GPIO is not set
|
||||||
|
CONFIG_DEBUG_DMA=y
|
||||||
|
# CONFIG_DEBUG_WATCHDOG is not set
|
||||||
|
# CONFIG_DEBUG_AUDIO is not set
|
||||||
CONFIG_DEBUG_SYMBOLS=y
|
CONFIG_DEBUG_SYMBOLS=y
|
||||||
|
|
||||||
#
|
#
|
||||||
@@ -86,6 +110,7 @@ CONFIG_ARCH_HAVE_FPU=y
|
|||||||
CONFIG_ARCH_FPU=y
|
CONFIG_ARCH_FPU=y
|
||||||
CONFIG_ARCH_HAVE_MPU=y
|
CONFIG_ARCH_HAVE_MPU=y
|
||||||
# CONFIG_ARMV7M_MPU is not set
|
# CONFIG_ARMV7M_MPU is not set
|
||||||
|
# CONFIG_DEBUG_HARDFAULT is not set
|
||||||
|
|
||||||
#
|
#
|
||||||
# ARMV7M Configuration Options
|
# ARMV7M Configuration Options
|
||||||
@@ -94,7 +119,9 @@ CONFIG_ARCH_HAVE_MPU=y
|
|||||||
CONFIG_ARMV7M_TOOLCHAIN_GNU_EABI=y
|
CONFIG_ARMV7M_TOOLCHAIN_GNU_EABI=y
|
||||||
CONFIG_ARMV7M_STACKCHECK=y
|
CONFIG_ARMV7M_STACKCHECK=y
|
||||||
CONFIG_SERIAL_TERMIOS=y
|
CONFIG_SERIAL_TERMIOS=y
|
||||||
CONFIG_SERIAL_DISABLE_REORDERING=y
|
CONFIG_SDIO_DMA=y
|
||||||
|
CONFIG_SDIO_DMAPRIO=0x00010000
|
||||||
|
# CONFIG_SDIO_WIDTH_D1_ONLY is not set
|
||||||
|
|
||||||
#
|
#
|
||||||
# STM32 Configuration Options
|
# STM32 Configuration Options
|
||||||
@@ -240,9 +267,6 @@ CONFIG_STM32_ADC=y
|
|||||||
CONFIG_STM32_SPI=y
|
CONFIG_STM32_SPI=y
|
||||||
CONFIG_STM32_I2C=y
|
CONFIG_STM32_I2C=y
|
||||||
|
|
||||||
CONFIG_ARCH_HAVE_LEDS=y
|
|
||||||
# CONFIG_ARCH_LEDS is not set
|
|
||||||
|
|
||||||
#
|
#
|
||||||
# Alternate Pin Mapping
|
# Alternate Pin Mapping
|
||||||
#
|
#
|
||||||
@@ -254,7 +278,7 @@ CONFIG_STM32_JTAG_SW_ENABLE=y
|
|||||||
CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG=y
|
CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG=y
|
||||||
# CONFIG_STM32_FORCEPOWER is not set
|
# CONFIG_STM32_FORCEPOWER is not set
|
||||||
# CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG is not set
|
# CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG is not set
|
||||||
CONFIG_STM32_CCMEXCLUDE=y
|
# CONFIG_STM32_CCMEXCLUDE is not set
|
||||||
CONFIG_STM32_DMACAPABLE=y
|
CONFIG_STM32_DMACAPABLE=y
|
||||||
# CONFIG_STM32_TIM1_PWM is not set
|
# CONFIG_STM32_TIM1_PWM is not set
|
||||||
# CONFIG_STM32_TIM3_PWM is not set
|
# CONFIG_STM32_TIM3_PWM is not set
|
||||||
@@ -271,40 +295,22 @@ CONFIG_STM32_USART=y
|
|||||||
# U[S]ART Configuration
|
# U[S]ART Configuration
|
||||||
#
|
#
|
||||||
# CONFIG_USART1_RS485 is not set
|
# CONFIG_USART1_RS485 is not set
|
||||||
CONFIG_USART1_RXDMA=y
|
# CONFIG_USART1_RXDMA is not set
|
||||||
# CONFIG_USART2_RS485 is not set
|
# CONFIG_USART2_RS485 is not set
|
||||||
CONFIG_USART2_RXDMA=y
|
CONFIG_USART2_RXDMA=y
|
||||||
# CONFIG_USART3_RS485 is not set
|
# CONFIG_USART3_RS485 is not set
|
||||||
# CONFIG_USART3_RXDMA is not set
|
# CONFIG_USART3_RXDMA is not set
|
||||||
# CONFIG_UART4_RS485 is not set
|
# CONFIG_UART4_RS485 is not set
|
||||||
# CONFIG_UART4_RXDMA is not set
|
# CONFIG_UART4_RXDMA is not set
|
||||||
# CONFIG_UART5_RXDMA is not set
|
|
||||||
# CONFIG_USART6_RS485 is not set
|
# CONFIG_USART6_RS485 is not set
|
||||||
# CONFIG_USART6_RXDMA is not set
|
# CONFIG_USART6_RXDMA is not set
|
||||||
# CONFIG_USART7_RXDMA is not set
|
# CONFIG_UART7_RS485 is not set
|
||||||
CONFIG_USART8_RXDMA=y
|
# CONFIG_UART7_RXDMA is not set
|
||||||
|
# CONFIG_UART8_RS485 is not set
|
||||||
|
# CONFIG_UART8_RXDMA is not set
|
||||||
|
CONFIG_SERIAL_DISABLE_REORDERING=y
|
||||||
CONFIG_STM32_USART_SINGLEWIRE=y
|
CONFIG_STM32_USART_SINGLEWIRE=y
|
||||||
|
|
||||||
|
|
||||||
# Previous:
|
|
||||||
## CONFIG_USART1_RS485 is not set
|
|
||||||
#CONFIG_USART1_RXDMA=y
|
|
||||||
## CONFIG_USART2_RS485 is not set
|
|
||||||
#CONFIG_USART2_RXDMA=y
|
|
||||||
## CONFIG_USART3_RS485 is not set
|
|
||||||
#CONFIG_USART3_RXDMA=y
|
|
||||||
## CONFIG_UART4_RS485 is not set
|
|
||||||
#CONFIG_UART4_RXDMA=y
|
|
||||||
## CONFIG_UART5_RXDMA is not set
|
|
||||||
## CONFIG_USART6_RS485 is not set
|
|
||||||
## CONFIG_USART6_RXDMA is not set
|
|
||||||
## CONFIG_USART7_RXDMA is not set
|
|
||||||
#CONFIG_USART8_RXDMA=y
|
|
||||||
#CONFIG_STM32_USART_SINGLEWIRE=y
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
#
|
#
|
||||||
# SPI Configuration
|
# SPI Configuration
|
||||||
#
|
#
|
||||||
@@ -323,25 +329,7 @@ CONFIG_STM32_I2CTIMEOTICKS=500
|
|||||||
#
|
#
|
||||||
# SDIO Configuration
|
# SDIO Configuration
|
||||||
#
|
#
|
||||||
|
CONFIG_SDIO_PRI=128
|
||||||
#
|
|
||||||
# Maintain legacy build behavior (revisit)
|
|
||||||
#
|
|
||||||
|
|
||||||
CONFIG_MMCSD=y
|
|
||||||
#CONFIG_MMCSD_SPI=y
|
|
||||||
CONFIG_MMCSD_SDIO=y
|
|
||||||
CONFIG_MTD=y
|
|
||||||
|
|
||||||
#
|
|
||||||
# STM32 SDIO-based MMC/SD driver
|
|
||||||
#
|
|
||||||
CONFIG_SDIO_DMA=y
|
|
||||||
# CONFIG_SDIO_DMAPRIO is not set
|
|
||||||
# CONFIG_SDIO_WIDTH_D1_ONLY is not set
|
|
||||||
CONFIG_MMCSD_MULTIBLOCK_DISABLE=y
|
|
||||||
CONFIG_MMCSD_MMCSUPPORT=n
|
|
||||||
CONFIG_MMCSD_HAVECARDDETECT=n
|
|
||||||
|
|
||||||
#
|
#
|
||||||
# USB Host Configuration
|
# USB Host Configuration
|
||||||
@@ -393,15 +381,14 @@ CONFIG_BOOT_RUNFROMFLASH=y
|
|||||||
#
|
#
|
||||||
# Board Selection
|
# Board Selection
|
||||||
#
|
#
|
||||||
CONFIG_ARCH_BOARD_PX4FMU_V2=y
|
CONFIG_ARCH_BOARD_CUSTOM=y
|
||||||
# CONFIG_ARCH_BOARD_CUSTOM is not set
|
CONFIG_ARCH_BOARD=""
|
||||||
CONFIG_ARCH_BOARD="px4fmu-v2"
|
|
||||||
|
|
||||||
#
|
#
|
||||||
# Common Board Options
|
# Common Board Options
|
||||||
#
|
#
|
||||||
CONFIG_NSH_MMCSDSLOTNO=0
|
|
||||||
CONFIG_NSH_MMCSDMINOR=0
|
CONFIG_NSH_MMCSDMINOR=0
|
||||||
|
CONFIG_NSH_MMCSDSLOTNO=0
|
||||||
|
|
||||||
#
|
#
|
||||||
# Board-Specific Options
|
# Board-Specific Options
|
||||||
@@ -497,7 +484,16 @@ CONFIG_WATCHDOG=y
|
|||||||
# CONFIG_BCH is not set
|
# CONFIG_BCH is not set
|
||||||
# CONFIG_INPUT is not set
|
# CONFIG_INPUT is not set
|
||||||
# CONFIG_LCD is not set
|
# CONFIG_LCD is not set
|
||||||
# CONFIG_MMCSD is not set
|
CONFIG_MMCSD=y
|
||||||
|
CONFIG_MMCSD_NSLOTS=1
|
||||||
|
# CONFIG_MMCSD_READONLY is not set
|
||||||
|
CONFIG_MMCSD_MULTIBLOCK_DISABLE=y
|
||||||
|
# CONFIG_MMCSD_MMCSUPPORT is not set
|
||||||
|
# CONFIG_MMCSD_HAVECARDDETECT is not set
|
||||||
|
# CONFIG_MMCSD_SPI is not set
|
||||||
|
CONFIG_MMCSD_SDIO=y
|
||||||
|
# CONFIG_SDIO_MUXBUS is not set
|
||||||
|
# CONFIG_SDIO_BLOCKSETUP is not set
|
||||||
CONFIG_MTD=y
|
CONFIG_MTD=y
|
||||||
|
|
||||||
#
|
#
|
||||||
@@ -536,6 +532,7 @@ CONFIG_ARCH_HAVE_USART6=y
|
|||||||
CONFIG_MCU_SERIAL=y
|
CONFIG_MCU_SERIAL=y
|
||||||
CONFIG_STANDARD_SERIAL=y
|
CONFIG_STANDARD_SERIAL=y
|
||||||
CONFIG_SERIAL_NPOLLWAITERS=2
|
CONFIG_SERIAL_NPOLLWAITERS=2
|
||||||
|
# CONFIG_SERIAL_TIOCSERGSTRUCT is not set
|
||||||
# CONFIG_USART1_SERIAL_CONSOLE is not set
|
# CONFIG_USART1_SERIAL_CONSOLE is not set
|
||||||
# CONFIG_USART2_SERIAL_CONSOLE is not set
|
# CONFIG_USART2_SERIAL_CONSOLE is not set
|
||||||
# CONFIG_USART3_SERIAL_CONSOLE is not set
|
# CONFIG_USART3_SERIAL_CONSOLE is not set
|
||||||
@@ -640,7 +637,6 @@ CONFIG_USBDEV=y
|
|||||||
# CONFIG_USBDEV_SELFPOWERED is not set
|
# CONFIG_USBDEV_SELFPOWERED is not set
|
||||||
CONFIG_USBDEV_BUSPOWERED=y
|
CONFIG_USBDEV_BUSPOWERED=y
|
||||||
CONFIG_USBDEV_MAXPOWER=500
|
CONFIG_USBDEV_MAXPOWER=500
|
||||||
# CONFIG_USBDEV_REMOTEWAKEUP is not set
|
|
||||||
# CONFIG_USBDEV_DMA is not set
|
# CONFIG_USBDEV_DMA is not set
|
||||||
# CONFIG_USBDEV_TRACE is not set
|
# CONFIG_USBDEV_TRACE is not set
|
||||||
|
|
||||||
@@ -650,7 +646,7 @@ CONFIG_USBDEV_MAXPOWER=500
|
|||||||
# CONFIG_USBDEV_COMPOSITE is not set
|
# CONFIG_USBDEV_COMPOSITE is not set
|
||||||
# CONFIG_PL2303 is not set
|
# CONFIG_PL2303 is not set
|
||||||
CONFIG_CDCACM=y
|
CONFIG_CDCACM=y
|
||||||
CONFIG_CDCACM_CONSOLE=n
|
# CONFIG_CDCACM_CONSOLE is not set
|
||||||
CONFIG_CDCACM_EP0MAXPACKET=64
|
CONFIG_CDCACM_EP0MAXPACKET=64
|
||||||
CONFIG_CDCACM_EPINTIN=1
|
CONFIG_CDCACM_EPINTIN=1
|
||||||
CONFIG_CDCACM_EPINTIN_FSSIZE=64
|
CONFIG_CDCACM_EPINTIN_FSSIZE=64
|
||||||
@@ -702,7 +698,7 @@ CONFIG_FAT_LCNAMES=y
|
|||||||
CONFIG_FAT_LFN=y
|
CONFIG_FAT_LFN=y
|
||||||
CONFIG_FAT_MAXFNAME=32
|
CONFIG_FAT_MAXFNAME=32
|
||||||
CONFIG_FS_FATTIME=y
|
CONFIG_FS_FATTIME=y
|
||||||
# CONFIG_FAT_DMAMEMORY is not set
|
CONFIG_FAT_DMAMEMORY=y
|
||||||
CONFIG_FS_NXFFS=y
|
CONFIG_FS_NXFFS=y
|
||||||
CONFIG_NXFFS_PREALLOCATED=y
|
CONFIG_NXFFS_PREALLOCATED=y
|
||||||
CONFIG_NXFFS_ERASEDSTATE=0xff
|
CONFIG_NXFFS_ERASEDSTATE=0xff
|
||||||
@@ -716,10 +712,8 @@ CONFIG_FS_BINFS=y
|
|||||||
#
|
#
|
||||||
# System Logging
|
# System Logging
|
||||||
#
|
#
|
||||||
CONFIG_SYSLOG_ENABLE=y
|
# CONFIG_SYSLOG_ENABLE is not set
|
||||||
CONFIG_SYSLOG=y
|
# CONFIG_SYSLOG is not set
|
||||||
CONFIG_SYSLOG_CHAR=y
|
|
||||||
CONFIG_SYSLOG_DEVPATH="/dev/ttyS6"
|
|
||||||
|
|
||||||
#
|
#
|
||||||
# Graphics Support
|
# Graphics Support
|
||||||
@@ -733,8 +727,9 @@ CONFIG_SYSLOG_DEVPATH="/dev/ttyS6"
|
|||||||
# CONFIG_MM_SMALL is not set
|
# CONFIG_MM_SMALL is not set
|
||||||
CONFIG_MM_REGIONS=2
|
CONFIG_MM_REGIONS=2
|
||||||
CONFIG_GRAN=y
|
CONFIG_GRAN=y
|
||||||
CONFIG_GRAN_SINGLE=y
|
# CONFIG_GRAN_SINGLE is not set
|
||||||
CONFIG_GRAN_INTR=y
|
# CONFIG_GRAN_INTR is not set
|
||||||
|
# CONFIG_DEBUG_GRAN is not set
|
||||||
|
|
||||||
#
|
#
|
||||||
# Audio Support
|
# Audio Support
|
||||||
@@ -1002,6 +997,7 @@ CONFIG_NSH_CONSOLE=y
|
|||||||
#
|
#
|
||||||
# USB Trace Support
|
# USB Trace Support
|
||||||
#
|
#
|
||||||
|
# CONFIG_NSH_USBDEV_TRACE is not set
|
||||||
# CONFIG_NSH_CONDEV is not set
|
# CONFIG_NSH_CONDEV is not set
|
||||||
CONFIG_NSH_ARCHINIT=y
|
CONFIG_NSH_ARCHINIT=y
|
||||||
|
|
||||||
@@ -1031,6 +1027,7 @@ CONFIG_NSH_ARCHINIT=y
|
|||||||
#
|
#
|
||||||
# FLASH Erase-all Command
|
# FLASH Erase-all Command
|
||||||
#
|
#
|
||||||
|
# CONFIG_SYSTEM_FLASH_ERASEALL is not set
|
||||||
|
|
||||||
#
|
#
|
||||||
# readline()
|
# readline()
|
||||||
|
|||||||
@@ -58,6 +58,7 @@
|
|||||||
#include <nuttx/sdio.h>
|
#include <nuttx/sdio.h>
|
||||||
#include <nuttx/mmcsd.h>
|
#include <nuttx/mmcsd.h>
|
||||||
#include <nuttx/analog/adc.h>
|
#include <nuttx/analog/adc.h>
|
||||||
|
#include <nuttx/gran.h>
|
||||||
|
|
||||||
#include <stm32.h>
|
#include <stm32.h>
|
||||||
#include "board_config.h"
|
#include "board_config.h"
|
||||||
@@ -69,6 +70,7 @@
|
|||||||
#include <drivers/drv_led.h>
|
#include <drivers/drv_led.h>
|
||||||
|
|
||||||
#include <systemlib/cpuload.h>
|
#include <systemlib/cpuload.h>
|
||||||
|
#include <systemlib/perf_counter.h>
|
||||||
|
|
||||||
/****************************************************************************
|
/****************************************************************************
|
||||||
* Pre-Processor Definitions
|
* Pre-Processor Definitions
|
||||||
@@ -96,10 +98,70 @@
|
|||||||
* Protected Functions
|
* Protected Functions
|
||||||
****************************************************************************/
|
****************************************************************************/
|
||||||
|
|
||||||
|
#if defined(CONFIG_FAT_DMAMEMORY)
|
||||||
|
# if !defined(CONFIG_GRAN) || !defined(CONFIG_FAT_DMAMEMORY)
|
||||||
|
# error microSD DMA support requires CONFIG_GRAN
|
||||||
|
# endif
|
||||||
|
|
||||||
|
static GRAN_HANDLE dma_allocator;
|
||||||
|
|
||||||
|
/*
|
||||||
|
* The DMA heap size constrains the total number of things that can be
|
||||||
|
* ready to do DMA at a time.
|
||||||
|
*
|
||||||
|
* For example, FAT DMA depends on one sector-sized buffer per filesystem plus
|
||||||
|
* one sector-sized buffer per file.
|
||||||
|
*
|
||||||
|
* We use a fundamental alignment / granule size of 64B; this is sufficient
|
||||||
|
* to guarantee alignment for the largest STM32 DMA burst (16 beats x 32bits).
|
||||||
|
*/
|
||||||
|
static uint8_t g_dma_heap[8192] __attribute__((aligned(64)));
|
||||||
|
static perf_counter_t g_dma_perf;
|
||||||
|
|
||||||
|
static void
|
||||||
|
dma_alloc_init(void)
|
||||||
|
{
|
||||||
|
dma_allocator = gran_initialize(g_dma_heap,
|
||||||
|
sizeof(g_dma_heap),
|
||||||
|
7, /* 128B granule - must be > alignment (XXX bug?) */
|
||||||
|
6); /* 64B alignment */
|
||||||
|
if (dma_allocator == NULL) {
|
||||||
|
message("[boot] DMA allocator setup FAILED");
|
||||||
|
} else {
|
||||||
|
g_dma_perf = perf_alloc(PC_COUNT, "DMA allocations");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
/****************************************************************************
|
/****************************************************************************
|
||||||
* Public Functions
|
* Public Functions
|
||||||
****************************************************************************/
|
****************************************************************************/
|
||||||
|
|
||||||
|
/*
|
||||||
|
* DMA-aware allocator stubs for the FAT filesystem.
|
||||||
|
*/
|
||||||
|
|
||||||
|
__EXPORT void *fat_dma_alloc(size_t size);
|
||||||
|
__EXPORT void fat_dma_free(FAR void *memory, size_t size);
|
||||||
|
|
||||||
|
void *
|
||||||
|
fat_dma_alloc(size_t size)
|
||||||
|
{
|
||||||
|
perf_count(g_dma_perf);
|
||||||
|
return gran_alloc(dma_allocator, size);
|
||||||
|
}
|
||||||
|
|
||||||
|
void
|
||||||
|
fat_dma_free(FAR void *memory, size_t size)
|
||||||
|
{
|
||||||
|
gran_free(dma_allocator, memory, size);
|
||||||
|
}
|
||||||
|
|
||||||
|
#else
|
||||||
|
|
||||||
|
# define dma_alloc_init()
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
/************************************************************************************
|
/************************************************************************************
|
||||||
* Name: stm32_boardinitialize
|
* Name: stm32_boardinitialize
|
||||||
*
|
*
|
||||||
@@ -110,7 +172,8 @@
|
|||||||
*
|
*
|
||||||
************************************************************************************/
|
************************************************************************************/
|
||||||
|
|
||||||
__EXPORT void stm32_boardinitialize(void)
|
__EXPORT void
|
||||||
|
stm32_boardinitialize(void)
|
||||||
{
|
{
|
||||||
/* configure SPI interfaces */
|
/* configure SPI interfaces */
|
||||||
stm32_spiinitialize();
|
stm32_spiinitialize();
|
||||||
@@ -170,6 +233,9 @@ __EXPORT int nsh_archinitialize(void)
|
|||||||
/* configure the high-resolution time/callout interface */
|
/* configure the high-resolution time/callout interface */
|
||||||
hrt_init();
|
hrt_init();
|
||||||
|
|
||||||
|
/* configure the DMA allocator */
|
||||||
|
dma_alloc_init();
|
||||||
|
|
||||||
/* configure CPU load estimation */
|
/* configure CPU load estimation */
|
||||||
#ifdef CONFIG_SCHED_INSTRUMENTATION
|
#ifdef CONFIG_SCHED_INSTRUMENTATION
|
||||||
cpuload_initialize_once();
|
cpuload_initialize_once();
|
||||||
|
|||||||
@@ -67,6 +67,7 @@ SPI::SPI(const char *name,
|
|||||||
CDev(name, devname, irq),
|
CDev(name, devname, irq),
|
||||||
// public
|
// public
|
||||||
// protected
|
// protected
|
||||||
|
locking_mode(LOCK_PREEMPTION),
|
||||||
// private
|
// private
|
||||||
_bus(bus),
|
_bus(bus),
|
||||||
_device(device),
|
_device(device),
|
||||||
@@ -132,13 +133,25 @@ SPI::probe()
|
|||||||
int
|
int
|
||||||
SPI::transfer(uint8_t *send, uint8_t *recv, unsigned len)
|
SPI::transfer(uint8_t *send, uint8_t *recv, unsigned len)
|
||||||
{
|
{
|
||||||
|
irqstate_t state;
|
||||||
|
|
||||||
if ((send == nullptr) && (recv == nullptr))
|
if ((send == nullptr) && (recv == nullptr))
|
||||||
return -EINVAL;
|
return -EINVAL;
|
||||||
|
|
||||||
/* do common setup */
|
/* lock the bus as required */
|
||||||
if (!up_interrupt_context())
|
if (!up_interrupt_context()) {
|
||||||
SPI_LOCK(_dev, true);
|
switch (locking_mode) {
|
||||||
|
default:
|
||||||
|
case LOCK_PREEMPTION:
|
||||||
|
state = irqsave();
|
||||||
|
break;
|
||||||
|
case LOCK_THREADS:
|
||||||
|
SPI_LOCK(_dev, true);
|
||||||
|
break;
|
||||||
|
case LOCK_NONE:
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
SPI_SETFREQUENCY(_dev, _frequency);
|
SPI_SETFREQUENCY(_dev, _frequency);
|
||||||
SPI_SETMODE(_dev, _mode);
|
SPI_SETMODE(_dev, _mode);
|
||||||
@@ -151,8 +164,19 @@ SPI::transfer(uint8_t *send, uint8_t *recv, unsigned len)
|
|||||||
/* and clean up */
|
/* and clean up */
|
||||||
SPI_SELECT(_dev, _device, false);
|
SPI_SELECT(_dev, _device, false);
|
||||||
|
|
||||||
if (!up_interrupt_context())
|
if (!up_interrupt_context()) {
|
||||||
SPI_LOCK(_dev, false);
|
switch (locking_mode) {
|
||||||
|
default:
|
||||||
|
case LOCK_PREEMPTION:
|
||||||
|
irqrestore(state);
|
||||||
|
break;
|
||||||
|
case LOCK_THREADS:
|
||||||
|
SPI_LOCK(_dev, false);
|
||||||
|
break;
|
||||||
|
case LOCK_NONE:
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
return OK;
|
return OK;
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -101,6 +101,17 @@ protected:
|
|||||||
*/
|
*/
|
||||||
int transfer(uint8_t *send, uint8_t *recv, unsigned len);
|
int transfer(uint8_t *send, uint8_t *recv, unsigned len);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Locking modes supported by the driver.
|
||||||
|
*/
|
||||||
|
enum LockMode {
|
||||||
|
LOCK_PREEMPTION, /**< the default; lock against all forms of preemption. */
|
||||||
|
LOCK_THREADS, /**< lock only against other threads, using SPI_LOCK */
|
||||||
|
LOCK_NONE /**< perform no locking, only safe if the bus is entirely private */
|
||||||
|
};
|
||||||
|
|
||||||
|
LockMode locking_mode; /**< selected locking mode */
|
||||||
|
|
||||||
private:
|
private:
|
||||||
int _bus;
|
int _bus;
|
||||||
enum spi_dev_e _device;
|
enum spi_dev_e _device;
|
||||||
|
|||||||
@@ -1292,10 +1292,6 @@ test()
|
|||||||
if (fd < 0)
|
if (fd < 0)
|
||||||
err(1, "%s open failed (try 'hmc5883 start' if the driver is not running", MAG_DEVICE_PATH);
|
err(1, "%s open failed (try 'hmc5883 start' if the driver is not running", MAG_DEVICE_PATH);
|
||||||
|
|
||||||
/* set the queue depth to 10 */
|
|
||||||
if (OK != ioctl(fd, SENSORIOCSQUEUEDEPTH, 10))
|
|
||||||
errx(1, "failed to set queue depth");
|
|
||||||
|
|
||||||
/* do a simple demand read */
|
/* do a simple demand read */
|
||||||
sz = read(fd, &report, sizeof(report));
|
sz = read(fd, &report, sizeof(report));
|
||||||
|
|
||||||
|
|||||||
@@ -367,7 +367,6 @@ out:
|
|||||||
int
|
int
|
||||||
L3GD20::probe()
|
L3GD20::probe()
|
||||||
{
|
{
|
||||||
irqstate_t flags = irqsave();
|
|
||||||
/* read dummy value to void to clear SPI statemachine on sensor */
|
/* read dummy value to void to clear SPI statemachine on sensor */
|
||||||
(void)read_reg(ADDR_WHO_AM_I);
|
(void)read_reg(ADDR_WHO_AM_I);
|
||||||
|
|
||||||
@@ -393,8 +392,6 @@ L3GD20::probe()
|
|||||||
success = true;
|
success = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
irqrestore(flags);
|
|
||||||
|
|
||||||
if (success)
|
if (success)
|
||||||
return OK;
|
return OK;
|
||||||
|
|
||||||
|
|||||||
@@ -525,7 +525,6 @@ out:
|
|||||||
void
|
void
|
||||||
LSM303D::reset()
|
LSM303D::reset()
|
||||||
{
|
{
|
||||||
irqstate_t flags = irqsave();
|
|
||||||
/* enable accel*/
|
/* enable accel*/
|
||||||
write_reg(ADDR_CTRL_REG1, REG1_X_ENABLE_A | REG1_Y_ENABLE_A | REG1_Z_ENABLE_A | REG1_BDU_UPDATE);
|
write_reg(ADDR_CTRL_REG1, REG1_X_ENABLE_A | REG1_Y_ENABLE_A | REG1_Z_ENABLE_A | REG1_BDU_UPDATE);
|
||||||
|
|
||||||
@@ -540,7 +539,6 @@ LSM303D::reset()
|
|||||||
|
|
||||||
mag_set_range(LSM303D_MAG_DEFAULT_RANGE_GA);
|
mag_set_range(LSM303D_MAG_DEFAULT_RANGE_GA);
|
||||||
mag_set_samplerate(LSM303D_MAG_DEFAULT_RATE);
|
mag_set_samplerate(LSM303D_MAG_DEFAULT_RATE);
|
||||||
irqrestore(flags);
|
|
||||||
|
|
||||||
_accel_read = 0;
|
_accel_read = 0;
|
||||||
_mag_read = 0;
|
_mag_read = 0;
|
||||||
@@ -549,15 +547,12 @@ LSM303D::reset()
|
|||||||
int
|
int
|
||||||
LSM303D::probe()
|
LSM303D::probe()
|
||||||
{
|
{
|
||||||
irqstate_t flags = irqsave();
|
|
||||||
/* read dummy value to void to clear SPI statemachine on sensor */
|
/* read dummy value to void to clear SPI statemachine on sensor */
|
||||||
(void)read_reg(ADDR_WHO_AM_I);
|
(void)read_reg(ADDR_WHO_AM_I);
|
||||||
|
|
||||||
/* verify that the device is attached and functioning */
|
/* verify that the device is attached and functioning */
|
||||||
bool success = (read_reg(ADDR_WHO_AM_I) == WHO_I_AM);
|
bool success = (read_reg(ADDR_WHO_AM_I) == WHO_I_AM);
|
||||||
|
|
||||||
irqrestore(flags);
|
|
||||||
|
|
||||||
if (success)
|
if (success)
|
||||||
return OK;
|
return OK;
|
||||||
|
|
||||||
@@ -1013,6 +1008,7 @@ LSM303D::accel_set_range(unsigned max_g)
|
|||||||
|
|
||||||
_accel_range_scale = new_scale_g_digit * LSM303D_ONE_G;
|
_accel_range_scale = new_scale_g_digit * LSM303D_ONE_G;
|
||||||
|
|
||||||
|
|
||||||
modify_reg(ADDR_CTRL_REG2, clearbits, setbits);
|
modify_reg(ADDR_CTRL_REG2, clearbits, setbits);
|
||||||
|
|
||||||
return OK;
|
return OK;
|
||||||
|
|||||||
@@ -142,23 +142,15 @@ MS5611_SPI::init()
|
|||||||
goto out;
|
goto out;
|
||||||
}
|
}
|
||||||
|
|
||||||
/* disable interrupts, make this section atomic */
|
|
||||||
flags = irqsave();
|
|
||||||
/* send reset command */
|
/* send reset command */
|
||||||
ret = _reset();
|
ret = _reset();
|
||||||
/* re-enable interrupts */
|
|
||||||
irqrestore(flags);
|
|
||||||
if (ret != OK) {
|
if (ret != OK) {
|
||||||
debug("reset failed");
|
debug("reset failed");
|
||||||
goto out;
|
goto out;
|
||||||
}
|
}
|
||||||
|
|
||||||
/* disable interrupts, make this section atomic */
|
|
||||||
flags = irqsave();
|
|
||||||
/* read PROM */
|
/* read PROM */
|
||||||
ret = _read_prom();
|
ret = _read_prom();
|
||||||
/* re-enable interrupts */
|
|
||||||
irqrestore(flags);
|
|
||||||
if (ret != OK) {
|
if (ret != OK) {
|
||||||
debug("prom readout failed");
|
debug("prom readout failed");
|
||||||
goto out;
|
goto out;
|
||||||
@@ -270,13 +262,7 @@ MS5611_SPI::_reg16(unsigned reg)
|
|||||||
int
|
int
|
||||||
MS5611_SPI::_transfer(uint8_t *send, uint8_t *recv, unsigned len)
|
MS5611_SPI::_transfer(uint8_t *send, uint8_t *recv, unsigned len)
|
||||||
{
|
{
|
||||||
irqstate_t flags = irqsave();
|
return transfer(send, recv, len);
|
||||||
|
|
||||||
int ret = transfer(send, recv, len);
|
|
||||||
|
|
||||||
irqrestore(flags);
|
|
||||||
|
|
||||||
return ret;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif /* PX4_SPIDEV_BARO */
|
#endif /* PX4_SPIDEV_BARO */
|
||||||
|
|||||||
@@ -52,6 +52,8 @@
|
|||||||
int
|
int
|
||||||
test_file(int argc, char *argv[])
|
test_file(int argc, char *argv[])
|
||||||
{
|
{
|
||||||
|
const iterations = 10;
|
||||||
|
|
||||||
/* check if microSD card is mounted */
|
/* check if microSD card is mounted */
|
||||||
struct stat buffer;
|
struct stat buffer;
|
||||||
if (stat("/fs/microsd/", &buffer)) {
|
if (stat("/fs/microsd/", &buffer)) {
|
||||||
@@ -67,7 +69,43 @@ test_file(int argc, char *argv[])
|
|||||||
memset(buf, 0, sizeof(buf));
|
memset(buf, 0, sizeof(buf));
|
||||||
|
|
||||||
start = hrt_absolute_time();
|
start = hrt_absolute_time();
|
||||||
for (unsigned i = 0; i < 1024; i++) {
|
for (unsigned i = 0; i < iterations; i++) {
|
||||||
|
perf_begin(wperf);
|
||||||
|
write(fd, buf, sizeof(buf));
|
||||||
|
perf_end(wperf);
|
||||||
|
}
|
||||||
|
end = hrt_absolute_time();
|
||||||
|
|
||||||
|
close(fd);
|
||||||
|
|
||||||
|
warnx("%dKiB in %llu microseconds", iterations / 2, end - start);
|
||||||
|
perf_print_counter(wperf);
|
||||||
|
perf_free(wperf);
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
#if 0
|
||||||
|
int
|
||||||
|
test_file(int argc, char *argv[])
|
||||||
|
{
|
||||||
|
const iterations = 1024;
|
||||||
|
|
||||||
|
/* check if microSD card is mounted */
|
||||||
|
struct stat buffer;
|
||||||
|
if (stat("/fs/microsd/", &buffer)) {
|
||||||
|
warnx("no microSD card mounted, aborting file test");
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint8_t buf[512];
|
||||||
|
hrt_abstime start, end;
|
||||||
|
perf_counter_t wperf = perf_alloc(PC_ELAPSED, "SD writes");
|
||||||
|
|
||||||
|
int fd = open("/fs/microsd/testfile", O_TRUNC | O_WRONLY | O_CREAT);
|
||||||
|
memset(buf, 0, sizeof(buf));
|
||||||
|
|
||||||
|
start = hrt_absolute_time();
|
||||||
|
for (unsigned i = 0; i < iterations; i++) {
|
||||||
perf_begin(wperf);
|
perf_begin(wperf);
|
||||||
write(fd, buf, sizeof(buf));
|
write(fd, buf, sizeof(buf));
|
||||||
perf_end(wperf);
|
perf_end(wperf);
|
||||||
@@ -78,7 +116,7 @@ test_file(int argc, char *argv[])
|
|||||||
|
|
||||||
unlink("/fs/microsd/testfile");
|
unlink("/fs/microsd/testfile");
|
||||||
|
|
||||||
warnx("512KiB in %llu microseconds", end - start);
|
warnx("%dKiB in %llu microseconds", iterations / 2, end - start);
|
||||||
perf_print_counter(wperf);
|
perf_print_counter(wperf);
|
||||||
perf_free(wperf);
|
perf_free(wperf);
|
||||||
|
|
||||||
@@ -112,3 +150,4 @@ test_file(int argc, char *argv[])
|
|||||||
|
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|||||||
Reference in New Issue
Block a user