aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2013-09-13 17:35:17 +0200
committerLorenz Meier <lm@inf.ethz.ch>2013-09-13 17:35:17 +0200
commit09c37515bb847e6469ce4a0f7d9a0157e2648c05 (patch)
tree02bea15fc7b04024c1a7c3550bb67db0adb3b84e
parentecbb319153955dac3287548703d40ba866ddf070 (diff)
parent24648b529402abb665c1b7c0064a9ee3150999fe (diff)
downloadpx4-firmware-09c37515bb847e6469ce4a0f7d9a0157e2648c05.tar.gz
px4-firmware-09c37515bb847e6469ce4a0f7d9a0157e2648c05.tar.bz2
px4-firmware-09c37515bb847e6469ce4a0f7d9a0157e2648c05.zip
Merge branch 'fat-dma-spi'
-rwxr-xr-xROMFS/px4fmu_common/init.d/rcS18
-rw-r--r--nuttx-configs/px4fmu-v2/nsh/defconfig123
-rw-r--r--src/drivers/boards/px4fmu-v2/px4fmu2_init.c68
-rw-r--r--src/drivers/device/spi.cpp34
-rw-r--r--src/drivers/device/spi.h11
-rw-r--r--src/drivers/hmc5883/hmc5883.cpp4
-rw-r--r--src/drivers/l3gd20/l3gd20.cpp3
-rw-r--r--src/drivers/lsm303d/lsm303d.cpp6
-rw-r--r--src/drivers/ms5611/ms5611_spi.cpp16
-rw-r--r--src/systemcmds/tests/tests_file.c43
10 files changed, 219 insertions, 107 deletions
diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS
index 4c4b0129e..cd4d4487d 100755
--- a/ROMFS/px4fmu_common/init.d/rcS
+++ b/ROMFS/px4fmu_common/init.d/rcS
@@ -73,20 +73,20 @@ then
#
# Load microSD params
#
- if ramtron start
- then
- param select /ramtron/params
- if [ -f /ramtron/params ]
- then
- param load /ramtron/params
- fi
- else
+ #if ramtron start
+ #then
+ # param select /ramtron/params
+ # if [ -f /ramtron/params ]
+ # then
+ # param load /ramtron/params
+ # fi
+ #else
param select /fs/microsd/params
if [ -f /fs/microsd/params ]
then
param load /fs/microsd/params
fi
- fi
+ #fi
#
# Start system state indicator
diff --git a/nuttx-configs/px4fmu-v2/nsh/defconfig b/nuttx-configs/px4fmu-v2/nsh/defconfig
index 2867f9113..8e2ae2d00 100644
--- a/nuttx-configs/px4fmu-v2/nsh/defconfig
+++ b/nuttx-configs/px4fmu-v2/nsh/defconfig
@@ -38,7 +38,31 @@ CONFIG_ARCH_MATH_H=y
#
# 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
#
@@ -86,6 +110,7 @@ CONFIG_ARCH_HAVE_FPU=y
CONFIG_ARCH_FPU=y
CONFIG_ARCH_HAVE_MPU=y
# CONFIG_ARMV7M_MPU is not set
+# CONFIG_DEBUG_HARDFAULT is not set
#
# ARMV7M Configuration Options
@@ -94,7 +119,9 @@ CONFIG_ARCH_HAVE_MPU=y
CONFIG_ARMV7M_TOOLCHAIN_GNU_EABI=y
CONFIG_ARMV7M_STACKCHECK=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
@@ -240,9 +267,6 @@ CONFIG_STM32_ADC=y
CONFIG_STM32_SPI=y
CONFIG_STM32_I2C=y
-CONFIG_ARCH_HAVE_LEDS=y
-# CONFIG_ARCH_LEDS is not set
-
#
# Alternate Pin Mapping
#
@@ -254,7 +278,7 @@ CONFIG_STM32_JTAG_SW_ENABLE=y
CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG=y
# CONFIG_STM32_FORCEPOWER 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_TIM1_PWM is not set
# CONFIG_STM32_TIM3_PWM is not set
@@ -271,40 +295,22 @@ CONFIG_STM32_USART=y
# U[S]ART Configuration
#
# CONFIG_USART1_RS485 is not set
-CONFIG_USART1_RXDMA=y
+# CONFIG_USART1_RXDMA is not set
# CONFIG_USART2_RS485 is not set
CONFIG_USART2_RXDMA=y
# CONFIG_USART3_RS485 is not set
# CONFIG_USART3_RXDMA is not set
# CONFIG_UART4_RS485 is not set
# CONFIG_UART4_RXDMA is not set
-# 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_UART7_RS485 is not set
+# 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
-
-# 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
#
@@ -323,25 +329,7 @@ CONFIG_STM32_I2CTIMEOTICKS=500
#
# SDIO Configuration
#
-
-#
-# 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
+CONFIG_SDIO_PRI=128
#
# USB Host Configuration
@@ -393,15 +381,14 @@ CONFIG_BOOT_RUNFROMFLASH=y
#
# Board Selection
#
-CONFIG_ARCH_BOARD_PX4FMU_V2=y
-# CONFIG_ARCH_BOARD_CUSTOM is not set
-CONFIG_ARCH_BOARD="px4fmu-v2"
+CONFIG_ARCH_BOARD_CUSTOM=y
+CONFIG_ARCH_BOARD=""
#
# Common Board Options
#
-CONFIG_NSH_MMCSDSLOTNO=0
CONFIG_NSH_MMCSDMINOR=0
+CONFIG_NSH_MMCSDSLOTNO=0
#
# Board-Specific Options
@@ -497,7 +484,16 @@ CONFIG_WATCHDOG=y
# CONFIG_BCH is not set
# CONFIG_INPUT 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
#
@@ -536,6 +532,7 @@ CONFIG_ARCH_HAVE_USART6=y
CONFIG_MCU_SERIAL=y
CONFIG_STANDARD_SERIAL=y
CONFIG_SERIAL_NPOLLWAITERS=2
+# CONFIG_SERIAL_TIOCSERGSTRUCT is not set
# CONFIG_USART1_SERIAL_CONSOLE is not set
# CONFIG_USART2_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_BUSPOWERED=y
CONFIG_USBDEV_MAXPOWER=500
-# CONFIG_USBDEV_REMOTEWAKEUP is not set
# CONFIG_USBDEV_DMA is not set
# CONFIG_USBDEV_TRACE is not set
@@ -650,7 +646,7 @@ CONFIG_USBDEV_MAXPOWER=500
# CONFIG_USBDEV_COMPOSITE is not set
# CONFIG_PL2303 is not set
CONFIG_CDCACM=y
-CONFIG_CDCACM_CONSOLE=n
+# CONFIG_CDCACM_CONSOLE is not set
CONFIG_CDCACM_EP0MAXPACKET=64
CONFIG_CDCACM_EPINTIN=1
CONFIG_CDCACM_EPINTIN_FSSIZE=64
@@ -702,7 +698,7 @@ CONFIG_FAT_LCNAMES=y
CONFIG_FAT_LFN=y
CONFIG_FAT_MAXFNAME=32
CONFIG_FS_FATTIME=y
-# CONFIG_FAT_DMAMEMORY is not set
+CONFIG_FAT_DMAMEMORY=y
CONFIG_FS_NXFFS=y
CONFIG_NXFFS_PREALLOCATED=y
CONFIG_NXFFS_ERASEDSTATE=0xff
@@ -716,10 +712,8 @@ CONFIG_FS_BINFS=y
#
# System Logging
#
-CONFIG_SYSLOG_ENABLE=y
-CONFIG_SYSLOG=y
-CONFIG_SYSLOG_CHAR=y
-CONFIG_SYSLOG_DEVPATH="/dev/ttyS6"
+# CONFIG_SYSLOG_ENABLE is not set
+# CONFIG_SYSLOG is not set
#
# Graphics Support
@@ -733,8 +727,9 @@ CONFIG_SYSLOG_DEVPATH="/dev/ttyS6"
# CONFIG_MM_SMALL is not set
CONFIG_MM_REGIONS=2
CONFIG_GRAN=y
-CONFIG_GRAN_SINGLE=y
-CONFIG_GRAN_INTR=y
+# CONFIG_GRAN_SINGLE is not set
+# CONFIG_GRAN_INTR is not set
+# CONFIG_DEBUG_GRAN is not set
#
# Audio Support
@@ -1002,6 +997,7 @@ CONFIG_NSH_CONSOLE=y
#
# USB Trace Support
#
+# CONFIG_NSH_USBDEV_TRACE is not set
# CONFIG_NSH_CONDEV is not set
CONFIG_NSH_ARCHINIT=y
@@ -1031,6 +1027,7 @@ CONFIG_NSH_ARCHINIT=y
#
# FLASH Erase-all Command
#
+# CONFIG_SYSTEM_FLASH_ERASEALL is not set
#
# readline()
diff --git a/src/drivers/boards/px4fmu-v2/px4fmu2_init.c b/src/drivers/boards/px4fmu-v2/px4fmu2_init.c
index 135767b26..ae2a645f7 100644
--- a/src/drivers/boards/px4fmu-v2/px4fmu2_init.c
+++ b/src/drivers/boards/px4fmu-v2/px4fmu2_init.c
@@ -58,6 +58,7 @@
#include <nuttx/sdio.h>
#include <nuttx/mmcsd.h>
#include <nuttx/analog/adc.h>
+#include <nuttx/gran.h>
#include <stm32.h>
#include "board_config.h"
@@ -69,6 +70,7 @@
#include <drivers/drv_led.h>
#include <systemlib/cpuload.h>
+#include <systemlib/perf_counter.h>
/****************************************************************************
* Pre-Processor Definitions
@@ -96,10 +98,70 @@
* 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
****************************************************************************/
+/*
+ * 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
*
@@ -110,7 +172,8 @@
*
************************************************************************************/
-__EXPORT void stm32_boardinitialize(void)
+__EXPORT void
+stm32_boardinitialize(void)
{
/* configure SPI interfaces */
stm32_spiinitialize();
@@ -170,6 +233,9 @@ __EXPORT int nsh_archinitialize(void)
/* configure the high-resolution time/callout interface */
hrt_init();
+ /* configure the DMA allocator */
+ dma_alloc_init();
+
/* configure CPU load estimation */
#ifdef CONFIG_SCHED_INSTRUMENTATION
cpuload_initialize_once();
diff --git a/src/drivers/device/spi.cpp b/src/drivers/device/spi.cpp
index 8fffd60cb..fa6b78d64 100644
--- a/src/drivers/device/spi.cpp
+++ b/src/drivers/device/spi.cpp
@@ -67,6 +67,7 @@ SPI::SPI(const char *name,
CDev(name, devname, irq),
// public
// protected
+ locking_mode(LOCK_PREEMPTION),
// private
_bus(bus),
_device(device),
@@ -132,13 +133,25 @@ SPI::probe()
int
SPI::transfer(uint8_t *send, uint8_t *recv, unsigned len)
{
+ irqstate_t state;
if ((send == nullptr) && (recv == nullptr))
return -EINVAL;
- /* do common setup */
- if (!up_interrupt_context())
- SPI_LOCK(_dev, true);
+ /* lock the bus as required */
+ if (!up_interrupt_context()) {
+ 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_SETMODE(_dev, _mode);
@@ -151,8 +164,19 @@ SPI::transfer(uint8_t *send, uint8_t *recv, unsigned len)
/* and clean up */
SPI_SELECT(_dev, _device, false);
- if (!up_interrupt_context())
- SPI_LOCK(_dev, false);
+ if (!up_interrupt_context()) {
+ switch (locking_mode) {
+ default:
+ case LOCK_PREEMPTION:
+ irqrestore(state);
+ break;
+ case LOCK_THREADS:
+ SPI_LOCK(_dev, false);
+ break;
+ case LOCK_NONE:
+ break;
+ }
+ }
return OK;
}
diff --git a/src/drivers/device/spi.h b/src/drivers/device/spi.h
index e0122372a..9103dca2e 100644
--- a/src/drivers/device/spi.h
+++ b/src/drivers/device/spi.h
@@ -101,6 +101,17 @@ protected:
*/
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:
int _bus;
enum spi_dev_e _device;
diff --git a/src/drivers/hmc5883/hmc5883.cpp b/src/drivers/hmc5883/hmc5883.cpp
index 58a1593ed..5e891d7bb 100644
--- a/src/drivers/hmc5883/hmc5883.cpp
+++ b/src/drivers/hmc5883/hmc5883.cpp
@@ -1292,10 +1292,6 @@ test()
if (fd < 0)
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 */
sz = read(fd, &report, sizeof(report));
diff --git a/src/drivers/l3gd20/l3gd20.cpp b/src/drivers/l3gd20/l3gd20.cpp
index 4c3b0ce51..748809d3f 100644
--- a/src/drivers/l3gd20/l3gd20.cpp
+++ b/src/drivers/l3gd20/l3gd20.cpp
@@ -367,7 +367,6 @@ out:
int
L3GD20::probe()
{
- irqstate_t flags = irqsave();
/* read dummy value to void to clear SPI statemachine on sensor */
(void)read_reg(ADDR_WHO_AM_I);
@@ -393,8 +392,6 @@ L3GD20::probe()
success = true;
}
- irqrestore(flags);
-
if (success)
return OK;
diff --git a/src/drivers/lsm303d/lsm303d.cpp b/src/drivers/lsm303d/lsm303d.cpp
index a90cd0a3d..2c56b6035 100644
--- a/src/drivers/lsm303d/lsm303d.cpp
+++ b/src/drivers/lsm303d/lsm303d.cpp
@@ -525,7 +525,6 @@ out:
void
LSM303D::reset()
{
- irqstate_t flags = irqsave();
/* enable accel*/
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_samplerate(LSM303D_MAG_DEFAULT_RATE);
- irqrestore(flags);
_accel_read = 0;
_mag_read = 0;
@@ -549,15 +547,12 @@ LSM303D::reset()
int
LSM303D::probe()
{
- irqstate_t flags = irqsave();
/* read dummy value to void to clear SPI statemachine on sensor */
(void)read_reg(ADDR_WHO_AM_I);
/* verify that the device is attached and functioning */
bool success = (read_reg(ADDR_WHO_AM_I) == WHO_I_AM);
- irqrestore(flags);
-
if (success)
return OK;
@@ -1013,6 +1008,7 @@ LSM303D::accel_set_range(unsigned max_g)
_accel_range_scale = new_scale_g_digit * LSM303D_ONE_G;
+
modify_reg(ADDR_CTRL_REG2, clearbits, setbits);
return OK;
diff --git a/src/drivers/ms5611/ms5611_spi.cpp b/src/drivers/ms5611/ms5611_spi.cpp
index 21caed2ff..e547c913b 100644
--- a/src/drivers/ms5611/ms5611_spi.cpp
+++ b/src/drivers/ms5611/ms5611_spi.cpp
@@ -142,23 +142,15 @@ MS5611_SPI::init()
goto out;
}
- /* disable interrupts, make this section atomic */
- flags = irqsave();
/* send reset command */
ret = _reset();
- /* re-enable interrupts */
- irqrestore(flags);
if (ret != OK) {
debug("reset failed");
goto out;
}
- /* disable interrupts, make this section atomic */
- flags = irqsave();
/* read PROM */
ret = _read_prom();
- /* re-enable interrupts */
- irqrestore(flags);
if (ret != OK) {
debug("prom readout failed");
goto out;
@@ -270,13 +262,7 @@ MS5611_SPI::_reg16(unsigned reg)
int
MS5611_SPI::_transfer(uint8_t *send, uint8_t *recv, unsigned len)
{
- irqstate_t flags = irqsave();
-
- int ret = transfer(send, recv, len);
-
- irqrestore(flags);
-
- return ret;
+ return transfer(send, recv, len);
}
#endif /* PX4_SPIDEV_BARO */
diff --git a/src/systemcmds/tests/tests_file.c b/src/systemcmds/tests/tests_file.c
index 47f480758..588d648bd 100644
--- a/src/systemcmds/tests/tests_file.c
+++ b/src/systemcmds/tests/tests_file.c
@@ -52,6 +52,44 @@
int
test_file(int argc, char *argv[])
{
+ const iterations = 10;
+
+ /* 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);
+ 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)) {
@@ -67,7 +105,7 @@ test_file(int argc, char *argv[])
memset(buf, 0, sizeof(buf));
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);
@@ -78,7 +116,7 @@ test_file(int argc, char *argv[])
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_free(wperf);
@@ -112,3 +150,4 @@ test_file(int argc, char *argv[])
return 0;
}
+#endif