summaryrefslogtreecommitdiff
path: root/nuttx/arch/avr/src
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-07-01 22:23:54 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-07-01 22:23:54 +0000
commitcdd11552fc1366a0280fe01bfef875344a967b1c (patch)
tree2b71ce05f5afc630b8d7f56719c3691c28400353 /nuttx/arch/avr/src
parent00b2545e9e3cc760255aa7b4fc953ad5ab97ba62 (diff)
downloadpx4-nuttx-cdd11552fc1366a0280fe01bfef875344a967b1c.tar.gz
px4-nuttx-cdd11552fc1366a0280fe01bfef875344a967b1c.tar.bz2
px4-nuttx-cdd11552fc1366a0280fe01bfef875344a967b1c.zip
Add termios header files; add files missed in last commit
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3739 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/arch/avr/src')
-rw-r--r--nuttx/arch/avr/src/avr/up_romgetc.c106
1 files changed, 106 insertions, 0 deletions
diff --git a/nuttx/arch/avr/src/avr/up_romgetc.c b/nuttx/arch/avr/src/avr/up_romgetc.c
new file mode 100644
index 000000000..7d46b1792
--- /dev/null
+++ b/nuttx/arch/avr/src/avr/up_romgetc.c
@@ -0,0 +1,106 @@
+/****************************************************************************
+ * arch/avr/src/avr/up_romgetc.c
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <nuttx/arch.h>
+#include <avr/pgmspace.h>
+
+#ifdef CONFIG_ARCH_ROMGETC
+
+/****************************************************************************
+ * Private Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_romgetc
+ *
+ * Description:
+ * In Harvard architectures, data accesses and instruction accesses occur
+ * on different busses, perhaps concurrently. All data accesses are
+ * performed on the data bus unless special machine instructions are
+ * used to read data from the instruction address space. Also, in the
+ * typical MCU, the available SRAM data memory is much smaller that the
+ * non-volatile FLASH instruction memory. So if the application requires
+ * many constant strings, the only practical solution may be to store
+ * those constant strings in FLASH memory where they can only be accessed
+ * using architecture-specific machine instructions.
+ *
+ * A similar case is where strings are retained in "external" memory such
+ * as EEPROM or serial FLASH. This case is similar only in that again
+ * special operations are required to obtain the string data; it cannot
+ * be accessed directly from a string pointer.
+ *
+ * If CONFIG_ARCH_ROMGETC is defined, then the architecture logic must
+ * export the function up_romgetc(). up_romgetc() will simply read one
+ * byte of data from the instruction space.
+ *
+ * If CONFIG_ARCH_ROMGETC, certain C stdio functions are effected: (1)
+ * All format strings in printf, fprintf, sprintf, etc. are assumed to
+ * lie in FLASH (string arguments for %s are still assumed to reside in
+ * SRAM). And (2), the string argument to puts and fputs is assumed to
+ * reside in FLASH. Clearly, these assumptions may have to modified for
+ * the particular needs of your environment. There is no "one-size-fits-all"
+ * solution for this problem.
+ *
+ * Additional AVR Assumptions:
+ *
+ * - This version of up_romgetc obtains string data from FLASH memory.
+ * - Since the passed pointer is 16-bits, the strings must lie in the first
+ * 64Kb of FLASH.
+ *
+ ****************************************************************************/
+
+char up_romgetc(FAR const char *ptr)
+{
+ return pgm_read_byte_near(ptr);
+}
+#endif