aboutsummaryrefslogtreecommitdiff
path: root/nuttx/include
diff options
context:
space:
mode:
authorpx4dev <px4@purgatory.org>2012-09-14 21:33:19 -0700
committerpx4dev <px4@purgatory.org>2012-09-14 21:33:19 -0700
commita3f21d914038f249e5e141b31410cc8554d94623 (patch)
tree59e60563503a42fce283149f0ca265c21faa19e2 /nuttx/include
parent53fe61a6211a86597834d5d8d7e90187f84717b0 (diff)
parentcfa24e37d6f153dbb5c7e2e0de6484719ea4a9b0 (diff)
downloadpx4-firmware-a3f21d914038f249e5e141b31410cc8554d94623.tar.gz
px4-firmware-a3f21d914038f249e5e141b31410cc8554d94623.tar.bz2
px4-firmware-a3f21d914038f249e5e141b31410cc8554d94623.zip
Merge branch 'NuttX/master'
Diffstat (limited to 'nuttx/include')
-rw-r--r--nuttx/include/nuttx/fs/fat.h36
-rw-r--r--nuttx/include/nuttx/gran.h202
-rw-r--r--nuttx/include/nuttx/net/enc28j60.h43
-rw-r--r--nuttx/include/nuttx/net/uip/uipopt.h18
-rw-r--r--[-rwxr-xr-x]nuttx/include/nuttx/usb/cdc.h0
-rw-r--r--nuttx/include/nuttx/usb/usbdev.h35
-rw-r--r--nuttx/include/nuttx/vt100.h4
-rw-r--r--[-rwxr-xr-x]nuttx/include/nuttx/watchdog.h0
-rw-r--r--nuttx/include/nuttx/wqueue.h84
-rw-r--r--nuttx/include/sys/sendfile.h123
10 files changed, 525 insertions, 20 deletions
diff --git a/nuttx/include/nuttx/fs/fat.h b/nuttx/include/nuttx/fs/fat.h
index f69bd8571..ac85c502f 100644
--- a/nuttx/include/nuttx/fs/fat.h
+++ b/nuttx/include/nuttx/fs/fat.h
@@ -40,6 +40,7 @@
* Included Files
****************************************************************************/
+#include <nuttx/config.h>
#include <stdint.h>
/****************************************************************************
@@ -75,11 +76,44 @@ extern "C" {
#define EXTERN extern
#endif
-/* Non-standard functions to get and set FAT file/directory attributes */
+/****************************************************************************
+ * Name: fat_getattrib and fat_setattrib
+ *
+ * Description:
+ * Non-standard functions to get and set FAT file/directory attributes
+ *
+ ****************************************************************************/
EXTERN int fat_getattrib(const char *path, fat_attrib_t *attrib);
EXTERN int fat_setattrib(const char *path, fat_attrib_t setbits, fat_attrib_t clearbits);
+/****************************************************************************
+ * Name: fat_dma_alloc and fat_dma_free
+ *
+ * Description:
+ * The FAT file system allocates two I/O buffers for data transfer, each
+ * are the size of one device sector. One of the buffers is allocated
+ * once for each FAT volume that is mounted; the other buffers are
+ * allocated each time a FAT file is opened.
+ *
+ * Some hardware, however, may require special DMA-capable memory in
+ * order to perform the the transfers. If CONFIG_FAT_DMAMEMORY is defined
+ * then the architecture-specific hardware must provide the funtions
+ * fat_dma_alloc() and fat_dma_free() as prototyped below: fat_dma_alloc()
+ * will allocate DMA-capable memory of the specified size; fat_dma_free()
+ * is the corresponding function that will be called to free the DMA-
+ * capable memory.
+ *
+ * This functions may be simple wrappers around gran_alloc() and gran_free()
+ * (See nuttx/gran.h).
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_FAT_DMAMEMORY
+EXTERN FAR void *fat_dma_alloc(size_t size);
+EXTERN void fat_dma_free(FAR void *memory, size_t size);
+#endif
+
#undef EXTERN
#ifdef __cplusplus
}
diff --git a/nuttx/include/nuttx/gran.h b/nuttx/include/nuttx/gran.h
new file mode 100644
index 000000000..5e980dd9c
--- /dev/null
+++ b/nuttx/include/nuttx/gran.h
@@ -0,0 +1,202 @@
+/****************************************************************************
+ * include/nuttx/gran.h
+ * General purpose granule memory allocator.
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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 NuttX 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.
+ *
+ ****************************************************************************/
+
+#ifndef __INCLUDE_NUTTX_GRAN_H
+#define __INCLUDE_NUTTX_GRAN_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <stdint.h>
+
+#ifdef CONFIG_GRAN
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+/* Configuration ************************************************************/
+/* CONFIG_GRAN - Enable granual allocator support
+ * CONFIG_GRAN_SINGLE - Select if there is only one instance of the
+ * granule allocator (i.e., gran_initialize will be called only once.
+ * In this case, (1) there are a few optimizations that can can be done
+ * and (2) the GRAN_HANDLE is not needed.
+ * CONFIG_GRAN_INTR - Normally mutual exclusive access to granule allocator
+ * data is assured using a semaphore. If this option is set then, instead,
+ * mutual exclusion logic will disable interrupts. While this options is
+ * more invasive to system performance, it will also support use of the
+ * granule allocator from interrupt level logic.
+ * CONFIG_DEBUG_GRAN - Just like CONFIG_DEBUG_MM, but only generates ouput
+ * from the gran allocation logic.
+ */
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+#ifndef CONFIG_GRAN_SINGLE
+typedef FAR void *GRAN_HANDLE;
+#endif
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+/****************************************************************************
+ * Name: gran_initialize
+ *
+ * Description:
+ * Set up one granule allocator instance. Allocations will be aligned to
+ * the alignment size (log2align; allocations will be in units of the
+ * granule size (log2gran). Larger granules will give better performance
+ * and less overhead but more losses of memory due to quantization waste.
+ * Additional memory waste can occur from alignment; log2align should be
+ * set to 0 unless you are using the granule allocator to manage DMA memory
+ * and your hardware has specific memory alignment requirements.
+ *
+ * Geneneral Usage Summary. This is an example using the GCC section
+ * attribute to position a DMA heap in memory (logic in the linker script
+ * would assign the section .dmaheap to the DMA memory.
+ *
+ * FAR uint32_t g_dmaheap[DMAHEAP_SIZE] __attribute__((section(.dmaheap)));
+ *
+ * The heap is created by calling gran_initialize. Here the granual size
+ * is set to 64 bytes and the alignment to 16 bytes:
+ *
+ * GRAN_HANDLE handle = gran_initialize(g_dmaheap, DMAHEAP_SIZE, 6, 4);
+ *
+ * Then the GRAN_HANDLE can be used to allocate memory (There is no
+ * GRAN_HANDLE if CONFIG_GRAN_SINGLE=y):
+ *
+ * FAR uint8_t *dma_memory = (FAR uint8_t *)gran_alloc(handle, 47);
+ *
+ * The actual memory allocates will be 64 byte (wasting 17 bytes) and
+ * will be aligned at least to (1 << log2align).
+ *
+ * NOTE: The current implementation also restricts the maximum allocation
+ * size to 32 granules. That restriction could be eliminated with some
+ * additional coding effort.
+ *
+ * Input Parameters:
+ * heapstart - Start of the granule allocation heap
+ * heapsize - Size of heap in bytes
+ * log2gran - Log base 2 of the size of one granule. 0->1 byte,
+ * 1->2 bytes, 2->4 bytes, 3-> 8 bytes, etc.
+ * log2align - Log base 2 of required alignment. 0->1 byte,
+ * 1->2 bytes, 2->4 bytes, 3-> 8 bytes, etc. Note that
+ * log2gran must be greater than or equal to log2align
+ * so that all contiguous granules in memory will meet
+ * the minimum alignment requirement. A value of zero
+ * would mean that no alignment is required.
+ *
+ * Returned Value:
+ * On success, a non-NULL handle is returned that may be used with other
+ * granual allocator interfaces.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_GRAN_SINGLE
+EXTERN int gran_initialize(FAR void *heapstart, size_t heapsize,
+ uint8_t log2gran, uint8_t log2align);
+#else
+EXTERN GRAN_HANDLE gran_initialize(FAR void *heapstart, size_t heapsize,
+ uint8_t log2gran, uint8_t log2align);
+#endif
+
+/****************************************************************************
+ * Name: gran_alloc
+ *
+ * Description:
+ * Allocate memory from the granule heap.
+ *
+ * NOTE: The current implementation also restricts the maximum allocation
+ * size to 32 granules. That restriction could be eliminated with some
+ * additional coding effort.
+ *
+ * Input Parameters:
+ * handle - The handle previously returned by gran_initialize
+ * size - The size of the memory region to allocate.
+ *
+ * Returned Value:
+ * On success, either a non-NULL pointer to the allocated memory (if
+ * CONFIG_GRAN_SINGLE) or zero (if !CONFIG_GRAN_SINGLE) is returned.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_GRAN_SINGLE
+EXTERN FAR void *gran_alloc(size_t size);
+#else
+EXTERN FAR void *gran_alloc(GRAN_HANDLE handle, size_t size);
+#endif
+
+/****************************************************************************
+ * Name: gran_free
+ *
+ * Description:
+ * Return memory to the granule heap.
+ *
+ * Input Parameters:
+ * handle - The handle previously returned by gran_initialize
+ * memory - A pointer to memory previoiusly allocated by gran_alloc.
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_GRAN_SINGLE
+EXTERN void gran_free(FAR void *memory, size_t size);
+#else
+EXTERN void gran_free(GRAN_HANDLE handle, FAR void *memory, size_t size);
+#endif
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* CONFIG_GRAN */
+#endif /* __INCLUDE_NUTTX_GRAN_H */
diff --git a/nuttx/include/nuttx/net/enc28j60.h b/nuttx/include/nuttx/net/enc28j60.h
index 2507b1cf6..7d0d7c3e5 100644
--- a/nuttx/include/nuttx/net/enc28j60.h
+++ b/nuttx/include/nuttx/net/enc28j60.h
@@ -1,7 +1,7 @@
/****************************************************************************
* include/nuttx/net/enc28j60.h
*
- * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2010, 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -43,13 +43,15 @@
#include <stdint.h>
#include <stdbool.h>
+#include <nuttx/irq.h>
+
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* ENC28J60 Configuration Settings:
*
- * CONFIG_NET_ENC28J60 - Enabled ENC28J60 support
+ * CONFIG_ENC28J60 - Enabled ENC28J60 support
* CONFIG_ENC28J60_SPIMODE - Controls the SPI mode
* CONFIG_ENC28J60_FREQUENCY - Define to use a different bus frequency
* CONFIG_ENC28J60_NINTERFACES - Specifies the number of physical ENC28J60
@@ -80,6 +82,34 @@ struct enc_stats_s
};
#endif
+/* The ENC28J60 normal provides interrupts to the MCU via a GPIO pin. The
+ * following structure provides an MCU-independent mechanixm for controlling
+ * the ENC28J60 GPIO interrupt.
+ *
+ * The ENC32J60 interrupt is an active low, *level* interrupt. "When an
+ * interrupt occurs, the interrupt flag is set. If the interrupt is enabled
+ * in the EIE register and the INTIE global interrupt enable bit is set, the
+ * INT pin will be driven low"
+ *
+ * "When an enabled interrupt occurs, the interrupt pin will remain low until
+ * all flags which are causing the interrupt are cleared or masked off
+ * (enable bit is cleared) by the host controller." However, the interrupt
+ * will behave like a falling edge interrupt because "After an interrupt
+ * occurs, the host controller [clears] the global enable bit for the
+ * interrupt pin before servicing the interrupt. Clearing the enable bit
+ * will cause the interrupt pin to return to the non-asserted state (high).
+ * Doing so will prevent the host controller from missing a falling edge
+ * should another interrupt occur while the immediate interrupt is being
+ * serviced."
+ */
+
+struct enc_lower_s
+{
+ int (*attach)(FAR const struct enc_lower_s *lower, xcpt_t handler);
+ void (*enable)(FAR const struct enc_lower_s *lower);
+ void (*disable)(FAR const struct enc_lower_s *lower);
+};
+
/****************************************************************************
* Public Data
****************************************************************************/
@@ -104,10 +134,10 @@ extern "C" {
*
* Parameters:
* spi - A reference to the platform's SPI driver for the ENC28J60
+ * lower - The MCU-specific interrupt used to control low-level MCU
+ * functions (i.e., ENC28J60 GPIO interrupts).
* devno - If more than one ENC28J60 is supported, then this is the
* zero based number that identifies the ENC28J60;
- * irq - The fully configured GPIO IRQ that ENC28J60 interrupts will be
- * asserted on. This driver will attach and entable this IRQ.
*
* Returned Value:
* OK on success; Negated errno on failure.
@@ -117,8 +147,9 @@ extern "C" {
****************************************************************************/
struct spi_dev_s; /* see nuttx/spi.h */
-EXTERN int enc_initialize(FAR struct spi_dev_s *spi, unsigned int devno,
- unsigned int irq);
+EXTERN int enc_initialize(FAR struct spi_dev_s *spi,
+ FAR const struct enc_lower_s *lower,
+ unsigned int devno);
/****************************************************************************
* Function: enc_stats
diff --git a/nuttx/include/nuttx/net/uip/uipopt.h b/nuttx/include/nuttx/net/uip/uipopt.h
index 4eff56fe8..9797e0482 100644
--- a/nuttx/include/nuttx/net/uip/uipopt.h
+++ b/nuttx/include/nuttx/net/uip/uipopt.h
@@ -296,7 +296,23 @@
/* The size of the TCP read buffer size */
#ifndef CONFIG_NET_TCP_READAHEAD_BUFSIZE
-# define CONFIG_NET_TCP_READAHEAD_BUFSIZE UIP_TCP_MSS
+# if CONFIG_NET_NTCP_READAHEAD_BUFFERS < 1
+# define CONFIG_NET_TCP_READAHEAD_BUFSIZE 0
+# else
+# define CONFIG_NET_TCP_READAHEAD_BUFSIZE UIP_TCP_MSS
+# endif
+#endif
+
+/* Delay after receive to catch a following packet. No delay should be
+ * required if TCP/IP read-ahead buffering is enabled.
+ */
+
+#ifndef CONFIG_NET_TCP_RECVDELAY
+# if CONFIG_NET_NTCP_READAHEAD_BUFFERS > 0
+# define CONFIG_NET_TCP_RECVDELAY 0
+# else
+# define CONFIG_NET_TCP_RECVDELAY 5
+# endif
#endif
/****************************************************************************
diff --git a/nuttx/include/nuttx/usb/cdc.h b/nuttx/include/nuttx/usb/cdc.h
index 627dd77e3..627dd77e3 100755..100644
--- a/nuttx/include/nuttx/usb/cdc.h
+++ b/nuttx/include/nuttx/usb/cdc.h
diff --git a/nuttx/include/nuttx/usb/usbdev.h b/nuttx/include/nuttx/usb/usbdev.h
index 89813cac9..1270fe13a 100644
--- a/nuttx/include/nuttx/usb/usbdev.h
+++ b/nuttx/include/nuttx/usb/usbdev.h
@@ -85,7 +85,7 @@
/* Allocate/free an I/O buffer. Should not be called from interrupt processing! */
-#ifdef CONFIG_ARCH_USBDEV_DMA
+#ifdef CONFIG_USBDEV_DMA
# define EP_ALLOCBUFFER(ep,nb) (ep)->ops->alloc(ep,nb)
# define EP_FREEBUFFER(ep,buff) (ep)->ops->free(ep,buf)
#else
@@ -234,7 +234,7 @@ struct usbdev_epops_s
/* Allocate and free I/O buffers */
-#ifdef CONFIG_ARCH_USBDEV_DMA
+#ifdef CONFIG_USBDEV_DMA
FAR void *(*allocbuffer)(FAR struct usbdev_ep_s *ep, uint16_t nbytes);
void (*freebuffer)(FAR struct usbdev_ep_s *ep, FAR void *buf);
#endif
@@ -354,6 +354,37 @@ EXTERN int usbdev_register(FAR struct usbdevclass_driver_s *driver);
EXTERN int usbdev_unregister(FAR struct usbdevclass_driver_s *driver);
+/****************************************************************************
+ * Name: usbdev_dma_alloc and usbdev_dma_free
+ *
+ * Description:
+ * The USB class driver allocates packet I/O buffers for data transfer by
+ * calling the driver allocbuffer() and freebuffer() methods. Those
+ * methods are only available if CONFIG_USBDEV_DMA is defined in the
+ * system configuration.
+ *
+ * If CONFIG_USBDEV_DMAMEMORY is also defined in the NuttX configuration,
+ * then the driver implementations of the allocbuffer() and freebuffer()
+ * methods may use board-specific usbdev_dma_alloc() and usbdev_dma_free().
+ * If CONFIG_USBDEV_DMA and CONFIG_USBDEV_DMAMEMORY are both defined,
+ * then the board-specific logic must provide the functions
+ * usbdev_dma_alloc() and usbdev_dma_free() as prototyped below:
+ * usbdev_dma_alloc() will allocate DMA-capable memory of the specified
+ * size; usbdev_dma_free() is the corresponding function that will be
+ * called to free the DMA-capable memory.
+ *
+ * This functions may be simple wrappers around gran_alloc() and
+ * gran_free() (See nuttx/gran.h). Note that the gran_free() function
+ * does require the size of the allocation to be freed; that would need
+ * to be managed in the board-specific logic.
+ *
+ ****************************************************************************/
+
+#if defined(CONFIG_USBDEV_DMA) && defined(CONFIG_USBDEV_DMAMEMORY)
+EXTERN FAR void *usbdev_dma_alloc(size_t size);
+EXTERN void usbdev_dma_free(FAR void *memory);
+#endif
+
#undef EXTERN
#if defined(__cplusplus)
}
diff --git a/nuttx/include/nuttx/vt100.h b/nuttx/include/nuttx/vt100.h
index a0254e88a..d834f48f0 100644
--- a/nuttx/include/nuttx/vt100.h
+++ b/nuttx/include/nuttx/vt100.h
@@ -105,7 +105,7 @@
#define VT100_CURSORPOS(v,h) {ASCII_ESC, '[', (v), ';', (h), 'H'} /* Move cursor to screen location v,h */
#define VT100_HVHOME {ASCII_ESC, '[', 'f'} /* Move cursor to upper left corner */
-#define VT100_HVHOME_ {ASCII_ESC, '[', ;', 'f'} /* Move cursor to upper left corner */
+#define VT100_HVHOME_ {ASCII_ESC, '[', ';', 'f'} /* Move cursor to upper left corner */
#define VT100_HVPOS(v,h) {ASCII_ESC, '[', (v), ';', (h), 'f'} /* Move cursor to screen location v,h */
#define VT100_INDEX {ASCII_ESC, 'D'} /* Move/scroll window up one line */
#define VT100_REVINDEX {ASCII_ESC, 'M'} /* Move/scroll window down one line */
@@ -138,7 +138,7 @@
#define VT100_TERMNOK {ASCII_ESC, '3', 'n'} /* Response: terminal is not OK */
#define VT100_GETCURSOR {ASCII_ESC, '6', 'n'} /* Get cursor position */
-#define VT100_CURSORPOS {ASCII_ESC, (v), ';', (h), 'R'} /* Response: cursor is at v,h */
+#define VT100_CURSORPOSAT {ASCII_ESC, (v), ';', (h), 'R'} /* Response: cursor is at v,h */
#define VT100_IDENT {ASCII_ESC, '[', 'c'} /* Identify what terminal type */
#define VT100_IDENT_ {ASCII_ESC, '[', '0', 'c'} /* Identify what terminal type */
diff --git a/nuttx/include/nuttx/watchdog.h b/nuttx/include/nuttx/watchdog.h
index bcf8b1522..bcf8b1522 100755..100644
--- a/nuttx/include/nuttx/watchdog.h
+++ b/nuttx/include/nuttx/watchdog.h
diff --git a/nuttx/include/nuttx/wqueue.h b/nuttx/include/nuttx/wqueue.h
index dfd424c8d..644585c56 100644
--- a/nuttx/include/nuttx/wqueue.h
+++ b/nuttx/include/nuttx/wqueue.h
@@ -50,6 +50,75 @@
/****************************************************************************
* Pre-Processor Definitions
****************************************************************************/
+/* Configuration ************************************************************/
+/* CONFIG_SCHED_WORKQUEUE. Create a dedicated "worker" thread to
+ * handle delayed processing from interrupt handlers. This feature
+ * is required for some drivers but, if there are not complaints,
+ * can be safely disabled. The worker thread also performs
+ * garbage collection -- completing any delayed memory deallocations
+ * from interrupt handlers. If the worker thread is disabled,
+ * then that clean will be performed by the IDLE thread instead
+ * (which runs at the lowest of priority and may not be appropriate
+ * if memory reclamation is of high priority). If CONFIG_SCHED_WORKQUEUE
+ * is enabled, then the following options can also be used:
+ * CONFIG_SCHED_WORKPRIORITY - The execution priority of the worker
+ * thread. Default: 192
+ * CONFIG_SCHED_WORKPERIOD - How often the worker thread checks for
+ * work in units of microseconds. Default: 50*1000 (50 MS).
+ * CONFIG_SCHED_WORKSTACKSIZE - The stack size allocated for the worker
+ * thread. Default: CONFIG_IDLETHREAD_STACKSIZE.
+ * CONFIG_SIG_SIGWORK - The signal number that will be used to wake-up
+ * the worker thread. Default: 4
+ *
+ * CONFIG_SCHED_LPWORK. If CONFIG_SCHED_WORKQUEUE is defined, then a single
+ * work queue is created by default. If CONFIG_SCHED_LPWORK is also defined
+ * then an additional, lower-priority work queue will also be created. This
+ * lower priority work queue is better suited for more extended processing
+ * (such as file system clean-up operations)
+ * CONFIG_SCHED_LPWORKPRIORITY - The execution priority of the lower priority
+ * worker thread. Default: 50
+ * CONFIG_SCHED_LPWORKPERIOD - How often the lower priority worker thread
+ * checks for work in units of microseconds. Default: 50*1000 (50 MS).
+ * CONFIG_SCHED_LPWORKSTACKSIZE - The stack size allocated for the lower
+ * priority worker thread. Default: CONFIG_IDLETHREAD_STACKSIZE.
+ */
+
+#ifndef CONFIG_SCHED_WORKPRIORITY
+# define CONFIG_SCHED_WORKPRIORITY 192
+#endif
+
+#ifndef CONFIG_SCHED_WORKPERIOD
+# define CONFIG_SCHED_WORKPERIOD (50*1000) /* 50 milliseconds */
+#endif
+
+#ifndef CONFIG_SCHED_WORKSTACKSIZE
+# define CONFIG_SCHED_WORKSTACKSIZE CONFIG_IDLETHREAD_STACKSIZE
+#endif
+
+#ifdef CONFIG_SCHED_LPWORK
+# ifndef CONFIG_SCHED_LPWORKPRIORITY
+# define CONFIG_SCHED_LPWORKPRIORITY 50
+# endif
+
+# ifndef CONFIG_SCHED_LPWORKPERIOD
+# define CONFIG_SCHED_LPWORKPERIOD (50*1000) /* 50 milliseconds */
+# endif
+
+# ifndef CONFIG_SCHED_LPWORKSTACKSIZE
+# define CONFIG_SCHED_LPWORKSTACKSIZE CONFIG_IDLETHREAD_STACKSIZE
+# endif
+#endif
+
+/* Work queue IDs (indices). These are both zero if there is only one work
+ * queue.
+ */
+
+#define HPWORK 0
+#ifdef CONFIG_SCHED_LPWORK
+# define LPWORK 1
+#else
+# define LPWORK HPWORK
+#endif
/****************************************************************************
* Public Types
@@ -86,10 +155,6 @@ extern "C" {
#define EXTERN extern
#endif
-/* The task ID of the worker thread */
-
-EXTERN pid_t g_worker;
-
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
@@ -109,6 +174,7 @@ EXTERN pid_t g_worker;
* and remove it from the work queue.
*
* Input parameters:
+ * qid - The work queue ID
* work - The work structure to queue
* worker - The worker callback to be invoked. The callback will invoked
* on the worker thread of execution.
@@ -122,7 +188,8 @@ EXTERN pid_t g_worker;
*
****************************************************************************/
-EXTERN int work_queue(struct work_s *work, worker_t worker, FAR void *arg, uint32_t delay);
+EXTERN int work_queue(int qid, FAR struct work_s *work, worker_t worker,
+ FAR void *arg, uint32_t delay);
/****************************************************************************
* Name: work_cancel
@@ -133,6 +200,7 @@ EXTERN int work_queue(struct work_s *work, worker_t worker, FAR void *arg, uint3
* again.
*
* Input parameters:
+ * qid - The work queue ID
* work - The previously queue work structure to cancel
*
* Returned Value:
@@ -140,7 +208,7 @@ EXTERN int work_queue(struct work_s *work, worker_t worker, FAR void *arg, uint3
*
****************************************************************************/
-EXTERN int work_cancel(struct work_s *work);
+EXTERN int work_cancel(int qid, FAR struct work_s *work);
/****************************************************************************
* Name: work_signal
@@ -151,14 +219,14 @@ EXTERN int work_cancel(struct work_s *work);
* user to force an immediate re-assessment of pending work.
*
* Input parameters:
- * None
+ * qid - The work queue ID
*
* Returned Value:
* Zero on success, a negated errno on failure
*
****************************************************************************/
-#define work_signal() kill(g_worker, SIGWORK)
+EXTERN int work_signal(int qid);
/****************************************************************************
* Name: work_available
diff --git a/nuttx/include/sys/sendfile.h b/nuttx/include/sys/sendfile.h
new file mode 100644
index 000000000..0f3c05444
--- /dev/null
+++ b/nuttx/include/sys/sendfile.h
@@ -0,0 +1,123 @@
+/****************************************************************************
+ * include/sys/sendfile.h
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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 NuttX 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.
+ *
+ ****************************************************************************/
+
+#ifndef __INCLUDE_SYS_SENDFILE_H
+#define __INCLUDE_SYS_SENDFILE_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+/* Configuration ************************************************************/
+
+#ifndef CONFIG_LIB_SENDFILE_BUFSIZE
+# define CONFIG_LIB_SENDFILE_BUFSIZE 512
+#endif
+
+/****************************************************************************
+ * Public Type Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+/************************************************************************
+ * Name: sendfile
+ *
+ * Description:
+ * sendfile() copies data between one file descriptor and another.
+ * sendfile() basically just wraps a sequence of reads() and writes()
+ * to perform a copy. It serves a purpose in systems where there is
+ * a penalty for copies to between user and kernal space, but really
+ * nothing in NuttX but provide some Linux compatible (and adding
+ * another 'almost standard' interface).
+ *
+ * NOTE: This interface is *not* specified in POSIX.1-2001, or other
+ * standards. The implementation here is very similar to the Linux
+ * sendfile interface. Other UNIX systems implement sendfile() with
+ * different semantics and prototypes. sendfile() should not be used
+ * in portable programs.
+ *
+ * Input Parmeters:
+ * infd - A file (or socket) descriptor opened for reading
+ * outfd - A descriptor opened for writing.
+ * offset - If 'offset' is not NULL, then it points to a variable
+ * holding the file offset from which sendfile() will start
+ * reading data from 'infd'. When sendfile() returns, this
+ * variable will be set to the offset of the byte following
+ * the last byte that was read. If 'offset' is not NULL,
+ * then sendfile() does not modify the current file offset of
+ * 'infd'; otherwise the current file offset is adjusted to
+ * reflect the number of bytes read from 'infd.'
+ *
+ * If 'offset' is NULL, then data will be read from 'infd'
+ * starting at the current file offset, and the file offset
+ * will be updated by the call.
+ * count - The number of bytes to copy between the file descriptors.
+ *
+ * Returned Value:
+ * If the transfer was successful, the number of bytes written to outfd is
+ * returned. On error, -1 is returned, and errno is set appropriately.
+ * There error values are those returned by read() or write() plus:
+ *
+ * EINVAL - Bad input parameters.
+ * ENOMEM - Could not allocated an I/O buffer
+ *
+ ************************************************************************/
+
+EXTERN ssize_t sendfile (int outfd, int infd, FAR off_t *offset, size_t count);
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* __INCLUDE_SYS_SENDFILE_H */