aboutsummaryrefslogtreecommitdiff
path: root/nuttx/include
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-09-17 18:35:37 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-09-17 18:35:37 +0000
commit298194339295d116ec5c47b06fce377c8424b8e0 (patch)
tree1701d3d2c3f6c456a04442336d5fa406bf553b55 /nuttx/include
parent57623d42ebb04f0a0b9e6eb7c0847a3ece2aa0ff (diff)
downloadpx4-firmware-298194339295d116ec5c47b06fce377c8424b8e0.tar.gz
px4-firmware-298194339295d116ec5c47b06fce377c8424b8e0.tar.bz2
px4-firmware-298194339295d116ec5c47b06fce377c8424b8e0.zip
Resync new repository with old repo r5166
git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5154 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/include')
-rw-r--r--nuttx/include/nuttx/analog/adc.h3
-rw-r--r--nuttx/include/nuttx/compiler.h24
-rw-r--r--nuttx/include/nuttx/gran.h9
-rw-r--r--nuttx/include/nuttx/i2c.h26
-rw-r--r--nuttx/include/nuttx/mtd.h13
-rw-r--r--nuttx/include/nuttx/net/enc28j60.h16
6 files changed, 79 insertions, 12 deletions
diff --git a/nuttx/include/nuttx/analog/adc.h b/nuttx/include/nuttx/analog/adc.h
index 873f5d9da..f654bff05 100644
--- a/nuttx/include/nuttx/analog/adc.h
+++ b/nuttx/include/nuttx/analog/adc.h
@@ -47,6 +47,7 @@
************************************************************************************/
#include <nuttx/config.h>
+#include <nuttx/compiler.h>
#include <sys/types.h>
#include <stdint.h>
@@ -78,7 +79,7 @@ struct adc_msg_s
{
uint8_t am_channel; /* The 8-bit ADC Channel */
int32_t am_data; /* ADC convert result (4 bytes) */
-} __attribute__((__packed__));
+} packed_struct;
struct adc_fifo_s
{
diff --git a/nuttx/include/nuttx/compiler.h b/nuttx/include/nuttx/compiler.h
index 733d58eec..1e0af4382 100644
--- a/nuttx/include/nuttx/compiler.h
+++ b/nuttx/include/nuttx/compiler.h
@@ -1,7 +1,7 @@
/****************************************************************************
* include/nuttx/compiler.h
*
- * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009, 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -92,6 +92,14 @@
# define reentrant_function
# define naked_function
+/* The inline_function attribute informs GCC that the function should always
+ * be inlined, regardless of the level of optimization. The noinline_function
+ * indicates that the function should never be inlined.
+ */
+
+# define inline_function __attribute__ ((always_inline))
+# define noinline_function __attribute__ ((noinline))
+
/* GCC has does not use storage classes to qualify addressing */
# define FAR
@@ -224,10 +232,15 @@
# define noreturn_function
# define packed_struct
-/* SDCC does support "naked" function s*/
+/* SDCC does support "naked" functions */
# define naked_function __naked
+/* SDCC does not support forced inlining. */
+
+# define inline_function
+# define noinline_function
+
/* The reentrant attribute informs SDCC that the function
* must be reentrant. In this case, SDCC will store input
* arguments on the stack to support reentrancy.
@@ -320,11 +333,13 @@
# define weak_function
# define weak_const_function
-/* The Zilog compiler does not support the noreturn, packed, or naked attributes */
+/* The Zilog compiler does not support the noreturn, packed, naked attributes */
# define noreturn_function
# define packed_struct
# define naked_function
+# define inline_function
+# define noinline_function
/* The Zilog compiler does not support the reentrant attribute */
@@ -406,7 +421,8 @@
# define packed_struct
# define reentrant_function
# define naked_function
-
+# define inline_function
+# define noinline_function
# define FAR
# define NEAR
diff --git a/nuttx/include/nuttx/gran.h b/nuttx/include/nuttx/gran.h
index 5390618a3..5e980dd9c 100644
--- a/nuttx/include/nuttx/gran.h
+++ b/nuttx/include/nuttx/gran.h
@@ -92,11 +92,10 @@ extern "C" {
* 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 alignment
- * quantization waste. Additional memory waste can occur form 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.
+ * 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
diff --git a/nuttx/include/nuttx/i2c.h b/nuttx/include/nuttx/i2c.h
index b2238b1cf..23356ecd3 100644
--- a/nuttx/include/nuttx/i2c.h
+++ b/nuttx/include/nuttx/i2c.h
@@ -1,7 +1,7 @@
/****************************************************************************
* include/nuttx/i2c.h
*
- * Copyright(C) 2009-2011 Gregory Nutt. All rights reserved.
+ * Copyright(C) 2009-2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -47,6 +47,16 @@
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
+/* If a dynamic timeout is selected, then a non-negative, non-zero micro-
+ * seconds per byte vale must be provided as well.
+ */
+
+#ifdef CONFIG_STM32_I2C_DYNTIMEO
+# if CONFIG_STM32_I2C_DYNTIMEO_USECPERBYTE < 1
+# warning "Ignoring CONFIG_STM32_I2C_DYNTIMEO because of CONFIG_STM32_I2C_DYNTIMEO_USECPERBYTE"
+# undef CONFIG_STM32_I2C_DYNTIMEO
+# endif
+#endif
/* I2C address calculation. Convert 7- and 10-bit address to 8-bit and
* 16-bit read/write address
@@ -323,7 +333,19 @@ EXTERN FAR struct i2c_dev_s *up_i2cinitialize(int port);
*
****************************************************************************/
-EXTERN int up_i2cuninitialize(FAR struct i2c_dev_s * dev);
+EXTERN int up_i2cuninitialize(FAR struct i2c_dev_s *dev);
+
+/************************************************************************************
+ * Name: up_i2creset
+ *
+ * Description:
+ * Reset an I2C bus
+ *
+ ************************************************************************************/
+
+#ifdef CONFIG_I2C_RESET
+EXTERN int up_i2creset(FAR struct i2c_dev_s *dev);
+#endif
#undef EXTERN
#if defined(__cplusplus)
diff --git a/nuttx/include/nuttx/mtd.h b/nuttx/include/nuttx/mtd.h
index 5b955a45f..44582c412 100644
--- a/nuttx/include/nuttx/mtd.h
+++ b/nuttx/include/nuttx/mtd.h
@@ -220,6 +220,19 @@ EXTERN FAR struct mtd_dev_s *at24c_initialize(FAR struct i2c_dev_s *dev);
EXTERN FAR struct mtd_dev_s *sst25_initialize(FAR struct spi_dev_s *dev);
+
+/****************************************************************************
+ * Name: w25_initialize
+ *
+ * Description:
+ * Create an initialized MTD device instance. MTD devices are not registered
+ * in the file system, but are created as instances that can be bound to
+ * other functions (such as a block or character driver front end).
+ *
+ ****************************************************************************/
+
+EXTERN FAR struct mtd_dev_s *w25_initialize(FAR struct spi_dev_s *dev);
+
#undef EXTERN
#ifdef __cplusplus
}
diff --git a/nuttx/include/nuttx/net/enc28j60.h b/nuttx/include/nuttx/net/enc28j60.h
index 2e39d88ac..7d0d7c3e5 100644
--- a/nuttx/include/nuttx/net/enc28j60.h
+++ b/nuttx/include/nuttx/net/enc28j60.h
@@ -85,6 +85,22 @@ struct enc_stats_s
/* 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