summaryrefslogtreecommitdiff
path: root/nuttx/configs/sam3u-ek
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2013-06-02 13:04:40 -0600
committerGregory Nutt <gnutt@nuttx.org>2013-06-02 13:04:40 -0600
commit9c0f7e4217cf195b2f83175b0014e273fbc805da (patch)
tree46f769b6188d65d2f3471b9fe7bdae2676162f56 /nuttx/configs/sam3u-ek
parent872bef7d41462d36b81ddc8de82a2cde18eaf096 (diff)
downloadpx4-nuttx-9c0f7e4217cf195b2f83175b0014e273fbc805da.tar.gz
px4-nuttx-9c0f7e4217cf195b2f83175b0014e273fbc805da.tar.bz2
px4-nuttx-9c0f7e4217cf195b2f83175b0014e273fbc805da.zip
Eliminated sam3u_internal.h. Use separate header files instead. More renaming from sam3u_ to sam_ to make room in the namespce for the sam4l_
Diffstat (limited to 'nuttx/configs/sam3u-ek')
-rw-r--r--nuttx/configs/sam3u-ek/README.txt6
-rw-r--r--nuttx/configs/sam3u-ek/include/board.h11
-rw-r--r--nuttx/configs/sam3u-ek/src/sam3u-ek.h (renamed from nuttx/configs/sam3u-ek/src/sam3uek_internal.h)45
-rw-r--r--nuttx/configs/sam3u-ek/src/up_boot.c25
-rw-r--r--nuttx/configs/sam3u-ek/src/up_buttons.c16
-rw-r--r--nuttx/configs/sam3u-ek/src/up_lcd.c360
-rw-r--r--nuttx/configs/sam3u-ek/src/up_leds.c12
-rw-r--r--nuttx/configs/sam3u-ek/src/up_mmcsd.c27
-rw-r--r--nuttx/configs/sam3u-ek/src/up_nsh.c7
-rw-r--r--nuttx/configs/sam3u-ek/src/up_spi.c39
-rw-r--r--nuttx/configs/sam3u-ek/src/up_touchscreen.c18
-rw-r--r--nuttx/configs/sam3u-ek/src/up_usbdev.c20
-rw-r--r--nuttx/configs/sam3u-ek/src/up_usbmsc.c6
13 files changed, 298 insertions, 294 deletions
diff --git a/nuttx/configs/sam3u-ek/README.txt b/nuttx/configs/sam3u-ek/README.txt
index 9907c7bd1..212229d97 100644
--- a/nuttx/configs/sam3u-ek/README.txt
+++ b/nuttx/configs/sam3u-ek/README.txt
@@ -114,7 +114,7 @@ IDEs
on the command line.
Startup files will probably cause you some headaches. The NuttX startup file
- is arch/arm/src/sam3u/sam3u_vectors.S. You may need to build NuttX
+ is arch/arm/src/sam3u/sam_vectors.S. You may need to build NuttX
one time from the Cygwin command line in order to obtain the pre-built
startup object needed by RIDE.
@@ -261,12 +261,14 @@ SAM3U-EK-specific Configuration Options
CONFIG_ARCH_CHIP_name - For use in C code to identify the exact
chip:
+ CONFIG_ARCH_CHIP_SAM34
+ CONFIG_ARCH_CHIP_SAM3U
CONFIG_ARCH_CHIP_AT91SAM3U4
CONFIG_ARCH_BOARD - Identifies the configs subdirectory and
hence, the board that supports the particular chip or SoC.
- CONFIG_ARCH_BOARD=sam3u_ek (for the SAM3U-EK development board)
+ CONFIG_ARCH_BOARD=sam3u-ek (for the SAM3U-EK development board)
CONFIG_ARCH_BOARD_name - For use in C code
diff --git a/nuttx/configs/sam3u-ek/include/board.h b/nuttx/configs/sam3u-ek/include/board.h
index dd9c893fd..213a6f4e4 100644
--- a/nuttx/configs/sam3u-ek/include/board.h
+++ b/nuttx/configs/sam3u-ek/include/board.h
@@ -42,7 +42,6 @@
************************************************************************************/
#include <nuttx/config.h>
-#include "sam3u_internal.h"
#ifndef __ASSEMBLY__
# include <stdint.h>
@@ -144,7 +143,7 @@ extern "C" {
* Public Function Prototypes
************************************************************************************/
/************************************************************************************
- * Name: sam3u_boardinitialize
+ * Name: sam_boardinitialize
*
* Description:
* All SAM3U architectures must provide the following entry point. This entry point
@@ -153,7 +152,7 @@ extern "C" {
*
************************************************************************************/
-EXTERN void sam3u_boardinitialize(void);
+void sam_boardinitialize(void);
/************************************************************************************
* Name: up_buttoninit
@@ -166,7 +165,7 @@ EXTERN void sam3u_boardinitialize(void);
************************************************************************************/
#ifdef CONFIG_ARCH_BUTTONS
-EXTERN void up_buttoninit(void);
+void up_buttoninit(void);
/************************************************************************************
* Name: up_buttons
@@ -179,7 +178,7 @@ EXTERN void up_buttoninit(void);
*
************************************************************************************/
-EXTERN uint8_t up_buttons(void);
+uint8_t up_buttons(void);
/************************************************************************************
* Name: up_irqbutton
@@ -193,7 +192,7 @@ EXTERN uint8_t up_buttons(void);
************************************************************************************/
#ifdef CONFIG_GPIOA_IRQ
-EXTERN xcpt_t up_irqbutton(int id, xcpt_t irqhandler);
+xcpt_t up_irqbutton(int id, xcpt_t irqhandler);
#endif
#endif /* CONFIG_ARCH_BUTTONS */
diff --git a/nuttx/configs/sam3u-ek/src/sam3uek_internal.h b/nuttx/configs/sam3u-ek/src/sam3u-ek.h
index d81fbd7cc..21e0e2649 100644
--- a/nuttx/configs/sam3u-ek/src/sam3uek_internal.h
+++ b/nuttx/configs/sam3u-ek/src/sam3u-ek.h
@@ -1,6 +1,5 @@
/************************************************************************************
- * configs/sam3uek_eval/src/sam3uek_internal.h
- * arch/arm/src/board/sam3uek_internal.n
+ * configs/sam3uek_eval/src/sam3u-ek.h
*
* Copyright (C) 2009-2011, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
@@ -34,8 +33,8 @@
*
************************************************************************************/
-#ifndef __CONFIGS_SAM3U_EK_SRC_SAM3UEK_INTERNAL_H
-#define __CONFIGS_SAM3U_EK_SRC_SAM3UEK_INTERNAL_H
+#ifndef __CONFIGS_SAM3U_EK_SRC_SAM3U_EK_H
+#define __CONFIGS_SAM3U_EK_SRC_SAM3U_EK_H
/************************************************************************************
* Included Files
@@ -49,6 +48,8 @@
#include <arch/irq.h>
#include <nuttx/irq.h>
+#include "chip/sam_pinmap.h"
+
/************************************************************************************
* Definitions
************************************************************************************/
@@ -191,27 +192,27 @@
************************************************************************************/
/************************************************************************************
- * Name: sam3u_spiinitialize
+ * Name: sam_spiinitialize
*
* Description:
* Called to configure SPI chip select GPIO pins for the SAM3U-EK board.
*
************************************************************************************/
-extern void weak_function sam3u_spiinitialize(void);
+extern void weak_function sam_spiinitialize(void);
/************************************************************************************
- * Name: sam3u_usbinitialize
+ * Name: sam_usbinitialize
*
* Description:
* Called to setup USB-related GPIO pins for the SAM3U-EK board.
*
************************************************************************************/
-extern void weak_function sam3u_usbinitialize(void);
+extern void weak_function sam_usbinitialize(void);
/****************************************************************************
- * Name: sam3u_hsmciinit
+ * Name: sam_hsmciinit
*
* Description:
* Initialize HSMCI support
@@ -219,13 +220,21 @@ extern void weak_function sam3u_usbinitialize(void);
****************************************************************************/
#ifdef CONFIG_SAM34_HSMCI
-extern int weak_function sam3u_hsmciinit(void);
+extern int weak_function sam_hsmciinit(void);
#else
-# define sam3u_hsmciinit()
+# define sam_hsmciinit()
+#endif
+
+/****************************************************************************
+ * Name: up_ledinit
+ ****************************************************************************/
+
+#ifdef CONFIG_ARCH_LEDS
+void up_ledinit(void);
#endif
/****************************************************************************
- * Name: sam3u_cardinserted
+ * Name: sam_cardinserted
*
* Description:
* Check if a card is inserted into the selected HSMCI slot
@@ -233,13 +242,13 @@ extern int weak_function sam3u_hsmciinit(void);
****************************************************************************/
#ifdef CONFIG_SAM34_HSMCI
-extern bool sam3u_cardinserted(unsigned char slot);
+extern bool sam_cardinserted(unsigned char slot);
#else
-# define sam3u_cardinserted(slot) (false)
+# define sam_cardinserted(slot) (false)
#endif
/****************************************************************************
- * Name: sam3u_writeprotected
+ * Name: sam_writeprotected
*
* Description:
* Check if a card is inserted into the selected HSMCI slot
@@ -247,11 +256,11 @@ extern bool sam3u_cardinserted(unsigned char slot);
****************************************************************************/
#ifdef CONFIG_SAM34_HSMCI
-extern bool sam3u_writeprotected(unsigned char slot);
+extern bool sam_writeprotected(unsigned char slot);
#else
-# define sam3u_writeprotected(slot) (false)
+# define sam_writeprotected(slot) (false)
#endif
#endif /* __ASSEMBLY__ */
-#endif /* __CONFIGS_SAM3U_EK_SRC_SAM3UEK_INTERNAL_H */
+#endif /* __CONFIGS_SAM3U_EK_SRC_SAM3U_EK_H */
diff --git a/nuttx/configs/sam3u-ek/src/up_boot.c b/nuttx/configs/sam3u-ek/src/up_boot.c
index 11bb80f07..c7367fe02 100644
--- a/nuttx/configs/sam3u-ek/src/up_boot.c
+++ b/nuttx/configs/sam3u-ek/src/up_boot.c
@@ -1,6 +1,5 @@
/************************************************************************************
* configs/sam3u-ek/src/up_boot.c
- * arch/arm/src/board/up_boot.c
*
* Copyright (C) 2009-2011, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
@@ -45,7 +44,7 @@
#include <arch/board/board.h>
#include "up_arch.h"
-#include "sam3uek_internal.h"
+#include "sam3u-ek.h"
/************************************************************************************
* Definitions
@@ -60,7 +59,7 @@
************************************************************************************/
/************************************************************************************
- * Name: sam3u_boardinitialize
+ * Name: sam_boardinitialize
*
* Description:
* All SAM3U architectures must provide the following entry point. This entry point
@@ -69,28 +68,28 @@
*
************************************************************************************/
-void sam3u_boardinitialize(void)
+void sam_boardinitialize(void)
{
/* Configure SPI chip selects if 1) SPI is not disabled, and 2) the weak function
- * sam3u_spiinitialize() has been brought into the link.
+ * sam_spiinitialize() has been brought into the link.
*/
#ifdef CONFIG_SAM34_SPI
- if (sam3u_spiinitialize)
+ if (sam_spiinitialize)
{
- sam3u_spiinitialize();
+ sam_spiinitialize();
}
#endif
/* Initialize USB if 1) USBDEV is selected, 2) the USB controller is not
- * disabled, and 3) the weak function sam3u_usbinitialize() has been brought
+ * disabled, and 3) the weak function sam_usbinitialize() has been brought
* into the build.
*/
#if defined(CONFIG_USBDEV) && defined(CONFIG_SAM34_USB)
- if (sam3u_usbinitialize)
+ if (sam_usbinitialize)
{
- sam3u_usbinitialize();
+ sam_usbinitialize();
}
#endif
@@ -101,13 +100,13 @@ void sam3u_boardinitialize(void)
#endif
/* Setup SD card-related PIOs if 1) HSMCI is selected and 2) the weak
- * function sam3u_hsmciinit() has been brought into the build.
+ * function sam_hsmciinit() has been brought into the build.
*/
#ifdef CONFIG_SAM34_HSMCI
- if (sam3u_hsmciinit)
+ if (sam_hsmciinit)
{
- sam3u_hsmciinit();
+ sam_hsmciinit();
}
#endif
}
diff --git a/nuttx/configs/sam3u-ek/src/up_buttons.c b/nuttx/configs/sam3u-ek/src/up_buttons.c
index a4b8e0fd7..f638fcb31 100644
--- a/nuttx/configs/sam3u-ek/src/up_buttons.c
+++ b/nuttx/configs/sam3u-ek/src/up_buttons.c
@@ -46,8 +46,8 @@
#include <arch/irq.h>
#include <arch/board/board.h>
-#include "sam3u_internal.h"
-#include "sam3uek_internal.h"
+#include "sam_gpio.h"
+#include "sam3u-ek.h"
#ifdef CONFIG_ARCH_BUTTONS
@@ -93,9 +93,9 @@ static xcpt_t up_irqbuttonx(int irq, xcpt_t irqhandler, xcpt_t *store)
/* Configure the interrupt */
- sam3u_gpioirq(irq);
+ sam_gpioirq(irq);
(void)irq_attach(irq, irqhandler);
- sam3u_gpioirqenable(irq);
+ sam_gpioirqenable(irq);
irqrestore(flags);
/* Return the old button handler (so that it can be restored) */
@@ -121,8 +121,8 @@ static xcpt_t up_irqbuttonx(int irq, xcpt_t irqhandler, xcpt_t *store)
void up_buttoninit(void)
{
- (void)sam3u_configgpio(GPIO_BUTTON1);
- (void)sam3u_configgpio(GPIO_BUTTON2);
+ (void)sam_configgpio(GPIO_BUTTON1);
+ (void)sam_configgpio(GPIO_BUTTON2);
}
/************************************************************************************
@@ -140,8 +140,8 @@ uint8_t up_buttons(void)
{
uint8_t retval;
- retval = sam3u_gpioread(GPIO_BUTTON1) ? 0 : GPIO_BUTTON1;
- retval |= sam3u_gpioread(GPIO_BUTTON2) ? 0 : GPIO_BUTTON2;
+ retval = sam_gpioread(GPIO_BUTTON1) ? 0 : GPIO_BUTTON1;
+ retval |= sam_gpioread(GPIO_BUTTON2) ? 0 : GPIO_BUTTON2;
return retval;
}
diff --git a/nuttx/configs/sam3u-ek/src/up_lcd.c b/nuttx/configs/sam3u-ek/src/up_lcd.c
index fded845a4..2190fb15e 100644
--- a/nuttx/configs/sam3u-ek/src/up_lcd.c
+++ b/nuttx/configs/sam3u-ek/src/up_lcd.c
@@ -125,10 +125,10 @@
#include <arch/irq.h>
#include "up_arch.h"
+#include "sam_gpio.h"
#include "chip/sam_pmc.h"
#include "chip/sam_smc.h"
-#include "sam3u_internal.h"
-#include "sam3uek_internal.h"
+#include "sam3u-ek.h"
/**************************************************************************************
* Pre-processor Definitions
@@ -288,7 +288,7 @@
/* This structure describes the state of this driver */
-struct sam3u_dev_s
+struct sam_dev_s
{
/* Publically visible device structure */
@@ -305,36 +305,36 @@ struct sam3u_dev_s
/* Low-level HX834x Register access */
-static void sam3u_putreg(uint16_t reg, uint16_t data);
-static uint16_t sam3u_getreg(uint16_t reg);
+static void sam_putreg(uint16_t reg, uint16_t data);
+static uint16_t sam_getreg(uint16_t reg);
/* Misc. LCD Helper Functions */
-static void sam3u_setcursor(fb_coord_t row, fb_coord_t col);
-static inline void sam3u_wrsetup(void);
-static inline void sam3u_wrram(uint16_t color);
-static inline uint16_t sam3u_rdram(void);
-static void sam3u_lcdon(void);
-static void sam3u_lcdoff(void);
+static void sam_setcursor(fb_coord_t row, fb_coord_t col);
+static inline void sam_wrsetup(void);
+static inline void sam_wrram(uint16_t color);
+static inline uint16_t sam_rdram(void);
+static void sam_lcdon(void);
+static void sam_lcdoff(void);
#ifdef CONFIG_DEBUG_GRAPHICS
-static void sam3u_dumpreg(uint8_t startreg, uint8_t endreg);
+static void sam_dumpreg(uint8_t startreg, uint8_t endreg);
#else
-# define sam3u_dumpreg(startreg,endreg)
+# define sam_dumpreg(startreg,endreg)
#endif
/* LCD Data Transfer Methods */
-static int sam3u_putrun(fb_coord_t row, fb_coord_t col, FAR const uint8_t *buffer,
+static int sam_putrun(fb_coord_t row, fb_coord_t col, FAR const uint8_t *buffer,
size_t npixels);
-static int sam3u_getrun(fb_coord_t row, fb_coord_t col, FAR uint8_t *buffer,
+static int sam_getrun(fb_coord_t row, fb_coord_t col, FAR uint8_t *buffer,
size_t npixels);
/* LCD Configuration */
-static int sam3u_getvideoinfo(FAR struct lcd_dev_s *dev,
+static int sam_getvideoinfo(FAR struct lcd_dev_s *dev,
FAR struct fb_videoinfo_s *vinfo);
-static int sam3u_getplaneinfo(FAR struct lcd_dev_s *dev, unsigned int planeno,
+static int sam_getplaneinfo(FAR struct lcd_dev_s *dev, unsigned int planeno,
FAR struct lcd_planeinfo_s *pinfo);
/* LCD RGB Mapping */
@@ -351,10 +351,10 @@ static int sam3u_getplaneinfo(FAR struct lcd_dev_s *dev, unsigned int planeno,
/* LCD Specific Controls */
-static int sam3u_getpower(struct lcd_dev_s *dev);
-static int sam3u_setpower(struct lcd_dev_s *dev, int power);
-static int sam3u_getcontrast(struct lcd_dev_s *dev);
-static int sam3u_setcontrast(struct lcd_dev_s *dev, unsigned int contrast);
+static int sam_getpower(struct lcd_dev_s *dev);
+static int sam_setpower(struct lcd_dev_s *dev, int power);
+static int sam_getcontrast(struct lcd_dev_s *dev);
+static int sam_setcontrast(struct lcd_dev_s *dev, unsigned int contrast);
/**************************************************************************************
* Private Data
@@ -387,32 +387,32 @@ static const struct fb_videoinfo_s g_videoinfo =
static const struct lcd_planeinfo_s g_planeinfo =
{
- .putrun = sam3u_putrun, /* Put a run into LCD memory */
- .getrun = sam3u_getrun, /* Get a run from LCD memory */
+ .putrun = sam_putrun, /* Put a run into LCD memory */
+ .getrun = sam_getrun, /* Get a run from LCD memory */
.buffer = (uint8_t*)g_runbuffer, /* Run scratch buffer */
.bpp = SAM3UEK_BPP, /* Bits-per-pixel */
};
/* This is the standard, NuttX LCD driver object */
-static struct sam3u_dev_s g_lcddev_s =
+static struct sam_dev_s g_lcddev_s =
{
.dev =
{
/* LCD Configuration */
- .getvideoinfo = sam3u_getvideoinfo,
- .getplaneinfo = sam3u_getplaneinfo,
+ .getvideoinfo = sam_getvideoinfo,
+ .getplaneinfo = sam_getplaneinfo,
/* LCD RGB Mapping -- Not supported */
/* Cursor Controls -- Not supported */
/* LCD Specific Controls */
- .getpower = sam3u_getpower,
- .setpower = sam3u_setpower,
- .getcontrast = sam3u_getcontrast,
- .setcontrast = sam3u_setcontrast,
+ .getpower = sam_getpower,
+ .setpower = sam_setpower,
+ .getcontrast = sam_getcontrast,
+ .setcontrast = sam_setcontrast,
},
};
@@ -421,14 +421,14 @@ static struct sam3u_dev_s g_lcddev_s =
**************************************************************************************/
/**************************************************************************************
- * Name: sam3u_putreg
+ * Name: sam_putreg
*
* Description:
* Write to a HX834x register
*
**************************************************************************************/
-static void sam3u_putreg(uint16_t reg, uint16_t data)
+static void sam_putreg(uint16_t reg, uint16_t data)
{
regdbg("base: %08x RS: %04x data: %04x\n", LCD_BASE, LCD_BASE + HX843X_LCD_RS, data);
putreg16(reg, LCD_BASE);
@@ -436,14 +436,14 @@ static void sam3u_putreg(uint16_t reg, uint16_t data)
}
/**************************************************************************************
- * Name: sam3u_getreg
+ * Name: sam_getreg
*
* Description:
* Read from a HX834x register
*
**************************************************************************************/
-static uint16_t sam3u_getreg(uint16_t reg)
+static uint16_t sam_getreg(uint16_t reg)
{
uint16_t data;
putreg16(reg, LCD_BASE);
@@ -453,14 +453,14 @@ static uint16_t sam3u_getreg(uint16_t reg)
}
/**************************************************************************************
- * Name: sam3u_setcursor
+ * Name: sam_setcursor
*
* Description:
* Set the LCD cursor position.
*
**************************************************************************************/
-static void sam3u_setcursor(fb_coord_t row, fb_coord_t col)
+static void sam_setcursor(fb_coord_t row, fb_coord_t col)
{
uint8_t x1;
uint8_t x2;
@@ -477,90 +477,90 @@ static void sam3u_setcursor(fb_coord_t row, fb_coord_t col)
/* Then set the cursor position */
- sam3u_putreg(HX8347_R02H, x2); /* column high */
- sam3u_putreg(HX8347_R03H, x1); /* column low */
- sam3u_putreg(HX8347_R06H, y2); /* row high */
- sam3u_putreg(HX8347_R07H, y1); /* row low */
+ sam_putreg(HX8347_R02H, x2); /* column high */
+ sam_putreg(HX8347_R03H, x1); /* column low */
+ sam_putreg(HX8347_R06H, y2); /* row high */
+ sam_putreg(HX8347_R07H, y1); /* row low */
}
/**************************************************************************************
- * Name: sam3u_wrsetup
+ * Name: sam_wrsetup
*
* Description:
* Set up for a GRAM write operation.
*
**************************************************************************************/
-static inline void sam3u_wrsetup(void)
+static inline void sam_wrsetup(void)
{
putreg16(HX8347_R22H, LCD_BASE);
}
/**************************************************************************************
- * Name: sam3u_wrram
+ * Name: sam_wrram
*
* Description:
* Write to the 16-bit GRAM register
*
**************************************************************************************/
-static inline void sam3u_wrram(uint16_t color)
+static inline void sam_wrram(uint16_t color)
{
putreg16(color, LCD_BASE + HX843X_LCD_RS);
}
/**************************************************************************************
- * Name: sam3u_rdram
+ * Name: sam_rdram
*
* Description:
* Read from the 16-bit GRAM register
*
**************************************************************************************/
-static inline uint16_t sam3u_rdram(void)
+static inline uint16_t sam_rdram(void)
{
return getreg16(LCD_BASE + HX843X_LCD_RS);
}
/**************************************************************************************
- * Name: sam3u_lcdon
+ * Name: sam_lcdon
*
* Description:
* Turn the LCD on
*
**************************************************************************************/
-static void sam3u_lcdon(void)
+static void sam_lcdon(void)
{
/* Display ON Setting */
gvdbg("ON\n");
- sam3u_putreg(HX8347_R90H, 0x7f); /* SAP=0111 1111 */
- sam3u_putreg(HX8347_R26H, 0x04); /* GON=0 DTE=0 D=01 */
+ sam_putreg(HX8347_R90H, 0x7f); /* SAP=0111 1111 */
+ sam_putreg(HX8347_R26H, 0x04); /* GON=0 DTE=0 D=01 */
up_mdelay(100);
- sam3u_putreg(HX8347_R26H, 0x24); /* GON=1 DTE=0 D=01 */
- sam3u_putreg(HX8347_R26H, 0x2c); /* GON=1 DTE=0 D=11 */
+ sam_putreg(HX8347_R26H, 0x24); /* GON=1 DTE=0 D=01 */
+ sam_putreg(HX8347_R26H, 0x2c); /* GON=1 DTE=0 D=11 */
up_mdelay(100);
- sam3u_putreg(HX8347_R26H, 0x3c); /* GON=1 DTE=1 D=11 */
+ sam_putreg(HX8347_R26H, 0x3c); /* GON=1 DTE=1 D=11 */
}
/**************************************************************************************
- * Name: sam3u_lcdoff
+ * Name: sam_lcdoff
*
* Description:
* Turn the LCD off
*
**************************************************************************************/
-static void sam3u_lcdoff(void)
+static void sam_lcdoff(void)
{
gvdbg("OFF\n");
- sam3u_putreg(HX8347_R90H, 0x00); /* SAP=0000 0000 */
- sam3u_putreg(HX8347_R26H, 0x00); /* GON=0 DTE=0 D=00 */
+ sam_putreg(HX8347_R90H, 0x00); /* SAP=0000 0000 */
+ sam_putreg(HX8347_R26H, 0x00); /* GON=0 DTE=0 D=00 */
}
/**************************************************************************************
- * Name: sam3u_dumpreg
+ * Name: sam_dumpreg
*
* Description:
* Dump a range of LCD registers.
@@ -568,21 +568,21 @@ static void sam3u_lcdoff(void)
**************************************************************************************/
#ifdef CONFIG_DEBUG_GRAPHICS
-static void sam3u_dumpreg(uint8_t startreg, uint8_t endreg)
+static void sam_dumpreg(uint8_t startreg, uint8_t endreg)
{
uint16_t value;
uint8_t addr;
for (addr = startreg; addr <= endreg; addr++)
{
- value = sam3u_getreg(addr);
+ value = sam_getreg(addr);
gdbg(" %02x: %04x\n", addr, value);
}
}
#endif
/**************************************************************************************
- * Name: sam3u_putrun
+ * Name: sam_putrun
*
* Description:
* This method can be used to write a partial raster line to the LCD:
@@ -595,8 +595,8 @@ static void sam3u_dumpreg(uint8_t startreg, uint8_t endreg)
*
**************************************************************************************/
-static int sam3u_putrun(fb_coord_t row, fb_coord_t col, FAR const uint8_t *buffer,
- size_t npixels)
+static int sam_putrun(fb_coord_t row, fb_coord_t col, FAR const uint8_t *buffer,
+ size_t npixels)
{
uint16_t *run = (uint16_t*)buffer;
unsigned int i;
@@ -609,8 +609,8 @@ static int sam3u_putrun(fb_coord_t row, fb_coord_t col, FAR const uint8_t *buffe
#ifdef CONFIG_LCD_PORTRAIT
/* Set up to write the run. */
- sam3u_setcursor(row, col);
- sam3u_wrsetup();
+ sam_setcursor(row, col);
+ sam_wrsetup();
/* Write the run to GRAM. */
@@ -618,7 +618,7 @@ static int sam3u_putrun(fb_coord_t row, fb_coord_t col, FAR const uint8_t *buffe
{
/* Write the pixel pixel to GRAM */
- sam3u_wrram(*run++);
+ sam_wrram(*run++);
}
#else
/* Write the run to GRAM. Because rows and colums are swapped, we need to reset
@@ -636,19 +636,19 @@ static int sam3u_putrun(fb_coord_t row, fb_coord_t col, FAR const uint8_t *buffe
* col: 0-319 maps to y: 319-0
*/
- sam3u_setcursor(col--, row);
- sam3u_wrsetup();
+ sam_setcursor(col--, row);
+ sam_wrsetup();
/* Write the pixel pixel to GRAM */
- sam3u_wrram(*run++);
+ sam_wrram(*run++);
}
#endif
return OK;
}
/**************************************************************************************
- * Name: sam3u_getrun
+ * Name: sam_getrun
*
* Description:
* This method can be used to read a partial raster line from the LCD:
@@ -661,8 +661,8 @@ static int sam3u_putrun(fb_coord_t row, fb_coord_t col, FAR const uint8_t *buffe
*
**************************************************************************************/
-static int sam3u_getrun(fb_coord_t row, fb_coord_t col, FAR uint8_t *buffer,
- size_t npixels)
+static int sam_getrun(fb_coord_t row, fb_coord_t col, FAR uint8_t *buffer,
+ size_t npixels)
{
uint16_t *run = (uint16_t*)buffer;
unsigned int i;
@@ -675,7 +675,7 @@ static int sam3u_getrun(fb_coord_t row, fb_coord_t col, FAR uint8_t *buffer,
#ifdef CONFIG_LCD_PORTRAIT
/* Set up to read the run */
- sam3u_setcursor(row, col);
+ sam_setcursor(row, col);
/* Read the run from GRAM. */
@@ -683,7 +683,7 @@ static int sam3u_getrun(fb_coord_t row, fb_coord_t col, FAR uint8_t *buffer,
{
/* Read the next pixel */
- *run++ = sam3u_rdram();
+ *run++ = sam_rdram();
}
#else
/* Read the run from GRAM Because rows and colums are swapped, we need to reset
@@ -701,23 +701,23 @@ static int sam3u_getrun(fb_coord_t row, fb_coord_t col, FAR uint8_t *buffer,
* col: 0-319 maps to y: 319-0
*/
- sam3u_setcursor(col--, row);
- *run++ = sam3u_rdram();
+ sam_setcursor(col--, row);
+ *run++ = sam_rdram();
}
#endif
return OK;
}
/**************************************************************************************
- * Name: sam3u_getvideoinfo
+ * Name: sam_getvideoinfo
*
* Description:
* Get information about the LCD video controller configuration.
*
**************************************************************************************/
-static int sam3u_getvideoinfo(FAR struct lcd_dev_s *dev,
- FAR struct fb_videoinfo_s *vinfo)
+static int sam_getvideoinfo(FAR struct lcd_dev_s *dev,
+ FAR struct fb_videoinfo_s *vinfo)
{
DEBUGASSERT(dev && vinfo);
gvdbg("fmt: %d xres: %d yres: %d nplanes: %d\n",
@@ -727,15 +727,15 @@ static int sam3u_getvideoinfo(FAR struct lcd_dev_s *dev,
}
/**************************************************************************************
- * Name: sam3u_getplaneinfo
+ * Name: sam_getplaneinfo
*
* Description:
* Get information about the configuration of each LCD color plane.
*
**************************************************************************************/
-static int sam3u_getplaneinfo(FAR struct lcd_dev_s *dev, unsigned int planeno,
- FAR struct lcd_planeinfo_s *pinfo)
+static int sam_getplaneinfo(FAR struct lcd_dev_s *dev, unsigned int planeno,
+ FAR struct lcd_planeinfo_s *pinfo)
{
DEBUGASSERT(dev && pinfo && planeno == 0);
gvdbg("planeno: %d bpp: %d\n", planeno, g_planeinfo.bpp);
@@ -744,7 +744,7 @@ static int sam3u_getplaneinfo(FAR struct lcd_dev_s *dev, unsigned int planeno,
}
/**************************************************************************************
- * Name: sam3u_getpower
+ * Name: sam_getpower
*
* Description:
* Get the LCD panel power status (0: full off - CONFIG_LCD_MAXPOWER: full on. On
@@ -752,16 +752,16 @@ static int sam3u_getplaneinfo(FAR struct lcd_dev_s *dev, unsigned int planeno,
*
**************************************************************************************/
-static int sam3u_getpower(struct lcd_dev_s *dev)
+static int sam_getpower(struct lcd_dev_s *dev)
{
- struct sam3u_dev_s *priv = (struct sam3u_dev_s *)dev;
+ struct sam_dev_s *priv = (struct sam_dev_s *)dev;
DEBUGASSERT(dev);
gvdbg("power: %d\n", priv->power);
return priv->power;
}
/**************************************************************************************
- * Name: sam3u_setpower
+ * Name: sam_setpower
*
* Description:
* Enable/disable LCD panel power (0: full off - CONFIG_LCD_MAXPOWERL: full on). On
@@ -775,9 +775,9 @@ static int sam3u_getpower(struct lcd_dev_s *dev)
*
**************************************************************************************/
-static int sam3u_setpower(struct lcd_dev_s *dev, int power)
+static int sam_setpower(struct lcd_dev_s *dev, int power)
{
- struct sam3u_dev_s *priv = (struct sam3u_dev_s *)dev;
+ struct sam_dev_s *priv = (struct sam_dev_s *)dev;
unsigned int i;
gvdbg("power: %d\n", power);
@@ -785,7 +785,7 @@ static int sam3u_setpower(struct lcd_dev_s *dev, int power)
/* Switch off backlight */
- sam3u_gpiowrite(GPIO_LCD_BKL, false);
+ sam_gpiowrite(GPIO_LCD_BKL, false);
/* For for at least 500uS to drain the charge pump */
@@ -795,12 +795,12 @@ static int sam3u_setpower(struct lcd_dev_s *dev, int power)
for (i = 0; i < power; i++)
{
- sam3u_gpiowrite(GPIO_LCD_BKL, false);
- sam3u_gpiowrite(GPIO_LCD_BKL, false);
- sam3u_gpiowrite(GPIO_LCD_BKL, false);
- sam3u_gpiowrite(GPIO_LCD_BKL, true);
- sam3u_gpiowrite(GPIO_LCD_BKL, true);
- sam3u_gpiowrite(GPIO_LCD_BKL, true);
+ sam_gpiowrite(GPIO_LCD_BKL, false);
+ sam_gpiowrite(GPIO_LCD_BKL, false);
+ sam_gpiowrite(GPIO_LCD_BKL, false);
+ sam_gpiowrite(GPIO_LCD_BKL, true);
+ sam_gpiowrite(GPIO_LCD_BKL, true);
+ sam_gpiowrite(GPIO_LCD_BKL, true);
}
/* This delay seems to be required... perhaps because of the big current jump? */
@@ -815,28 +815,28 @@ static int sam3u_setpower(struct lcd_dev_s *dev, int power)
}
/**************************************************************************************
- * Name: sam3u_getcontrast
+ * Name: sam_getcontrast
*
* Description:
* Get the current contrast setting (0-CONFIG_LCD_MAXCONTRAST).
*
**************************************************************************************/
-static int sam3u_getcontrast(struct lcd_dev_s *dev)
+static int sam_getcontrast(struct lcd_dev_s *dev)
{
gvdbg("Not implemented\n");
return -ENOSYS;
}
/**************************************************************************************
- * Name: sam3u_getcontrast
+ * Name: sam_getcontrast
*
* Description:
* Set LCD panel contrast (0-CONFIG_LCD_MAXCONTRAST).
*
**************************************************************************************/
-static int sam3u_setcontrast(struct lcd_dev_s *dev, unsigned int contrast)
+static int sam_setcontrast(struct lcd_dev_s *dev, unsigned int contrast)
{
gvdbg("contrast: %d\n", contrast);
return -ENOSYS;
@@ -868,36 +868,36 @@ int up_lcdinitialize(void)
/* Enable LCD EXTCS2 pins */
- sam3u_configgpio(GPIO_LCD_NCS2);
- sam3u_configgpio(GPIO_LCD_RS);
- sam3u_configgpio(GPIO_LCD_NWE);
- sam3u_configgpio(GPIO_LCD_NRD);
-
- sam3u_configgpio(GPIO_LCD_D0);
- sam3u_configgpio(GPIO_LCD_D1);
- sam3u_configgpio(GPIO_LCD_D2);
- sam3u_configgpio(GPIO_LCD_D3);
- sam3u_configgpio(GPIO_LCD_D4);
- sam3u_configgpio(GPIO_LCD_D5);
- sam3u_configgpio(GPIO_LCD_D6);
- sam3u_configgpio(GPIO_LCD_D7);
- sam3u_configgpio(GPIO_LCD_D8);
- sam3u_configgpio(GPIO_LCD_D9);
- sam3u_configgpio(GPIO_LCD_D10);
- sam3u_configgpio(GPIO_LCD_D11);
- sam3u_configgpio(GPIO_LCD_D12);
- sam3u_configgpio(GPIO_LCD_D13);
- sam3u_configgpio(GPIO_LCD_D14);
- sam3u_configgpio(GPIO_LCD_D15);
+ sam_configgpio(GPIO_LCD_NCS2);
+ sam_configgpio(GPIO_LCD_RS);
+ sam_configgpio(GPIO_LCD_NWE);
+ sam_configgpio(GPIO_LCD_NRD);
+
+ sam_configgpio(GPIO_LCD_D0);
+ sam_configgpio(GPIO_LCD_D1);
+ sam_configgpio(GPIO_LCD_D2);
+ sam_configgpio(GPIO_LCD_D3);
+ sam_configgpio(GPIO_LCD_D4);
+ sam_configgpio(GPIO_LCD_D5);
+ sam_configgpio(GPIO_LCD_D6);
+ sam_configgpio(GPIO_LCD_D7);
+ sam_configgpio(GPIO_LCD_D8);
+ sam_configgpio(GPIO_LCD_D9);
+ sam_configgpio(GPIO_LCD_D10);
+ sam_configgpio(GPIO_LCD_D11);
+ sam_configgpio(GPIO_LCD_D12);
+ sam_configgpio(GPIO_LCD_D13);
+ sam_configgpio(GPIO_LCD_D14);
+ sam_configgpio(GPIO_LCD_D15);
#ifdef CONFIG_LCD_REGDEBUG
- sam3u_dumpgpio(GPIO_PORT_PIOB, "PORTB");
- sam3u_dumpgpio(GPIO_PORT_PIOC, "PORTC");
+ sam_dumpgpio(GPIO_PORT_PIOB, "PORTB");
+ sam_dumpgpio(GPIO_PORT_PIOC, "PORTC");
#endif
/* Configure LCD Backlight Pin */
- sam3u_configgpio(GPIO_LCD_D15);
+ sam_configgpio(GPIO_LCD_D15);
/* Enable SMC peripheral clock */
@@ -932,7 +932,7 @@ int up_lcdinitialize(void)
/* Check HX8347 Chip ID */
#ifdef CONFIG_DEBUG_GRAPHICS
- hxregval = sam3u_getreg(HX8347_R67H);
+ hxregval = sam_getreg(HX8347_R67H);
gvdbg("Chip ID: %04x\n", hxregval);
if (hxregval != HX8347_CHIPID)
{
@@ -945,86 +945,86 @@ int up_lcdinitialize(void)
/* Start internal OSC */
- sam3u_putreg(HX8347_R19H, 0x49); /* OSCADJ=10 0000 OSD_EN=1 60Hz */
- sam3u_putreg(HX8347_R93H, 0x0C); /* RADJ=1100 */
+ sam_putreg(HX8347_R19H, 0x49); /* OSCADJ=10 0000 OSD_EN=1 60Hz */
+ sam_putreg(HX8347_R93H, 0x0C); /* RADJ=1100 */
/* Power on flow */
- sam3u_putreg(HX8347_R44H, 0x4D); /* VCM=100 1101 */
- sam3u_putreg(HX8347_R45H, 0x11); /* VDV=1 0001 */
- sam3u_putreg(HX8347_R20H, 0x40); /* BT=0100 */
- sam3u_putreg(HX8347_R1DH, 0x07); /* VC1=111 */
- sam3u_putreg(HX8347_R1EH, 0x00); /* VC3=000 */
- sam3u_putreg(HX8347_R1FH, 0x04); /* VRH=0100 */
- sam3u_putreg(HX8347_R1CH, 0x04); /* AP=100 */
- sam3u_putreg(HX8347_R1BH, 0x10); /* GASENB=0 PON=1 DK=0 XDK=0 DDVDH_TRI=0 STB=0 */
+ sam_putreg(HX8347_R44H, 0x4D); /* VCM=100 1101 */
+ sam_putreg(HX8347_R45H, 0x11); /* VDV=1 0001 */
+ sam_putreg(HX8347_R20H, 0x40); /* BT=0100 */
+ sam_putreg(HX8347_R1DH, 0x07); /* VC1=111 */
+ sam_putreg(HX8347_R1EH, 0x00); /* VC3=000 */
+ sam_putreg(HX8347_R1FH, 0x04); /* VRH=0100 */
+ sam_putreg(HX8347_R1CH, 0x04); /* AP=100 */
+ sam_putreg(HX8347_R1BH, 0x10); /* GASENB=0 PON=1 DK=0 XDK=0 DDVDH_TRI=0 STB=0 */
up_mdelay(50);
- sam3u_putreg(HX8347_R43H, 0x80); /* Set VCOMG=1 */
+ sam_putreg(HX8347_R43H, 0x80); /* Set VCOMG=1 */
up_mdelay(50);
/* Gamma for CMO 2.8 */
- sam3u_putreg(HX8347_R46H, 0x95);
- sam3u_putreg(HX8347_R47H, 0x51);
- sam3u_putreg(HX8347_R48H, 0x00);
- sam3u_putreg(HX8347_R49H, 0x36);
- sam3u_putreg(HX8347_R4AH, 0x11);
- sam3u_putreg(HX8347_R4BH, 0x66);
- sam3u_putreg(HX8347_R4CH, 0x14);
- sam3u_putreg(HX8347_R4DH, 0x77);
- sam3u_putreg(HX8347_R4EH, 0x13);
- sam3u_putreg(HX8347_R4FH, 0x4c);
- sam3u_putreg(HX8347_R50H, 0x46);
- sam3u_putreg(HX8347_R51H, 0x46);
+ sam_putreg(HX8347_R46H, 0x95);
+ sam_putreg(HX8347_R47H, 0x51);
+ sam_putreg(HX8347_R48H, 0x00);
+ sam_putreg(HX8347_R49H, 0x36);
+ sam_putreg(HX8347_R4AH, 0x11);
+ sam_putreg(HX8347_R4BH, 0x66);
+ sam_putreg(HX8347_R4CH, 0x14);
+ sam_putreg(HX8347_R4DH, 0x77);
+ sam_putreg(HX8347_R4EH, 0x13);
+ sam_putreg(HX8347_R4FH, 0x4c);
+ sam_putreg(HX8347_R50H, 0x46);
+ sam_putreg(HX8347_R51H, 0x46);
/* 240x320 window setting */
- sam3u_putreg(HX8347_R02H, 0x00); /* Column address start2 */
- sam3u_putreg(HX8347_R03H, 0x00); /* Column address start1 */
- sam3u_putreg(HX8347_R04H, 0x00); /* Column address end2 */
- sam3u_putreg(HX8347_R05H, 0xef); /* Column address end1 */
- sam3u_putreg(HX8347_R06H, 0x00); /* Row address start2 */
- sam3u_putreg(HX8347_R07H, 0x00); /* Row address start1 */
- sam3u_putreg(HX8347_R08H, 0x01); /* Row address end2 */
- sam3u_putreg(HX8347_R09H, 0x3f); /* Row address end1 */
+ sam_putreg(HX8347_R02H, 0x00); /* Column address start2 */
+ sam_putreg(HX8347_R03H, 0x00); /* Column address start1 */
+ sam_putreg(HX8347_R04H, 0x00); /* Column address end2 */
+ sam_putreg(HX8347_R05H, 0xef); /* Column address end1 */
+ sam_putreg(HX8347_R06H, 0x00); /* Row address start2 */
+ sam_putreg(HX8347_R07H, 0x00); /* Row address start1 */
+ sam_putreg(HX8347_R08H, 0x01); /* Row address end2 */
+ sam_putreg(HX8347_R09H, 0x3f); /* Row address end1 */
/* Display Setting */
- sam3u_putreg(HX8347_R01H, 0x06); /* IDMON=0 INVON=1 NORON=1 PTLON=0 */
- sam3u_putreg(HX8347_R16H, 0xc8); /* MY=1 MX=1 MV=0 BGR=1 */
- sam3u_putreg(HX8347_R23H, 0x95); /* N_DC=1001 0101 */
- sam3u_putreg(HX8347_R24H, 0x95); /* P_DC=1001 0101 */
- sam3u_putreg(HX8347_R25H, 0xff); /* I_DC=1111 1111 */
- sam3u_putreg(HX8347_R27H, 0x06); /* N_BP=0000 0110 */
- sam3u_putreg(HX8347_R28H, 0x06); /* N_FP=0000 0110 */
- sam3u_putreg(HX8347_R29H, 0x06); /* P_BP=0000 0110 */
- sam3u_putreg(HX8347_R2AH, 0x06); /* P_FP=0000 0110 */
- sam3u_putreg(HX8347_R2CH, 0x06); /* I_BP=0000 0110 */
- sam3u_putreg(HX8347_R2DH, 0x06); /* I_FP=0000 0110 */
- sam3u_putreg(HX8347_R3AH, 0x01); /* N_RTN=0000 N_NW=001 */
- sam3u_putreg(HX8347_R3BH, 0x01); /* P_RTN=0000 P_NW=001 */
- sam3u_putreg(HX8347_R3CH, 0xf0); /* I_RTN=1111 I_NW=000 */
- sam3u_putreg(HX8347_R3DH, 0x00); /* DIV=00 */
- sam3u_putreg(HX8347_R3EH, 0x38); /* SON=38h */
- sam3u_putreg(HX8347_R40H, 0x0f); /* GDON=0Fh */
- sam3u_putreg(HX8347_R41H, 0xf0); /* GDOF=F0h */
+ sam_putreg(HX8347_R01H, 0x06); /* IDMON=0 INVON=1 NORON=1 PTLON=0 */
+ sam_putreg(HX8347_R16H, 0xc8); /* MY=1 MX=1 MV=0 BGR=1 */
+ sam_putreg(HX8347_R23H, 0x95); /* N_DC=1001 0101 */
+ sam_putreg(HX8347_R24H, 0x95); /* P_DC=1001 0101 */
+ sam_putreg(HX8347_R25H, 0xff); /* I_DC=1111 1111 */
+ sam_putreg(HX8347_R27H, 0x06); /* N_BP=0000 0110 */
+ sam_putreg(HX8347_R28H, 0x06); /* N_FP=0000 0110 */
+ sam_putreg(HX8347_R29H, 0x06); /* P_BP=0000 0110 */
+ sam_putreg(HX8347_R2AH, 0x06); /* P_FP=0000 0110 */
+ sam_putreg(HX8347_R2CH, 0x06); /* I_BP=0000 0110 */
+ sam_putreg(HX8347_R2DH, 0x06); /* I_FP=0000 0110 */
+ sam_putreg(HX8347_R3AH, 0x01); /* N_RTN=0000 N_NW=001 */
+ sam_putreg(HX8347_R3BH, 0x01); /* P_RTN=0000 P_NW=001 */
+ sam_putreg(HX8347_R3CH, 0xf0); /* I_RTN=1111 I_NW=000 */
+ sam_putreg(HX8347_R3DH, 0x00); /* DIV=00 */
+ sam_putreg(HX8347_R3EH, 0x38); /* SON=38h */
+ sam_putreg(HX8347_R40H, 0x0f); /* GDON=0Fh */
+ sam_putreg(HX8347_R41H, 0xf0); /* GDOF=F0h */
/* Set LCD backlight to FULL off */
- sam3u_setpower(&g_lcddev_s.dev, LCD_FULL_OFF);
+ sam_setpower(&g_lcddev_s.dev, LCD_FULL_OFF);
/* Fill the display memory with the color BLACK */
- sam3u_setcursor(0, 0);
- sam3u_wrsetup();
+ sam_setcursor(0, 0);
+ sam_wrsetup();
for (i = 0; i < (SAM3UEK_XRES * SAM3UEK_YRES); i++)
{
- sam3u_wrram(RGB16_BLACK);
+ sam_wrram(RGB16_BLACK);
}
/* Turn the LCD on (but with the backlight off) */
- sam3u_lcdon();
+ sam_lcdon();
return OK;
}
@@ -1055,11 +1055,11 @@ void up_lcduninitialize(void)
{
/* Turn the LCD off */
- sam3u_lcdoff();
+ sam_lcdoff();
/* Set LCD backlight to FULL off */
- sam3u_setpower(&g_lcddev_s.dev, LCD_FULL_OFF);
+ sam_setpower(&g_lcddev_s.dev, LCD_FULL_OFF);
/* Disable SMC peripheral clock */
diff --git a/nuttx/configs/sam3u-ek/src/up_leds.c b/nuttx/configs/sam3u-ek/src/up_leds.c
index 0b02ae20f..1c6c4aeb7 100644
--- a/nuttx/configs/sam3u-ek/src/up_leds.c
+++ b/nuttx/configs/sam3u-ek/src/up_leds.c
@@ -49,8 +49,8 @@
#include "chip.h"
#include "up_arch.h"
#include "up_internal.h"
-#include "sam3u_internal.h"
-#include "sam3uek_internal.h"
+#include "sam_gpio.h"
+#include "sam3u-ek.h"
#ifdef CONFIG_ARCH_LEDS
@@ -144,7 +144,7 @@ static void up_setled(uint16_t pinset, uint8_t state)
return;
}
- sam3u_gpiowrite(pinset, polarity);
+ sam_gpiowrite(pinset, polarity);
}
/****************************************************************************
@@ -168,9 +168,9 @@ static void up_setleds(uint8_t state)
void up_ledinit(void)
{
- (void)sam3u_configgpio(GPIO_LED0);
- (void)sam3u_configgpio(GPIO_LED1);
- (void)sam3u_configgpio(GPIO_LED2);
+ (void)sam_configgpio(GPIO_LED0);
+ (void)sam_configgpio(GPIO_LED1);
+ (void)sam_configgpio(GPIO_LED2);
}
/****************************************************************************
diff --git a/nuttx/configs/sam3u-ek/src/up_mmcsd.c b/nuttx/configs/sam3u-ek/src/up_mmcsd.c
index 0ea8b9207..92934752f 100644
--- a/nuttx/configs/sam3u-ek/src/up_mmcsd.c
+++ b/nuttx/configs/sam3u-ek/src/up_mmcsd.c
@@ -1,6 +1,5 @@
/************************************************************************************
* configs/sam3u-ek/src/up_mmcsd.c
- * arch/arm/src/board/up_mmcsd.c
*
* Copyright (C) 2010, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
@@ -43,8 +42,8 @@
#include <stdbool.h>
#include <debug.h>
-#include "sam3u_internal.h"
-#include "sam3uek_internal.h"
+#include "sam_gpio.h"
+#include "sam3u-ek.h"
#ifdef CONFIG_SAM34_HSMCI
@@ -55,7 +54,7 @@
/* This needs to be extended. The card detect GPIO must be configured as an interrupt.
* when the interrupt indicating that a card has been inserted or removed is received,
* this function must call sio_mediachange() to handle that event. See
- * arch/arm/src/sam3u/sam3u_internal.h for more information.
+ * arch/arm/src/sam3u/sam_hsmci.h for more information.
*/
#ifdef GPIO_MCI_CD
@@ -71,7 +70,7 @@
************************************************************************************/
/************************************************************************************
- * Name: sam3u_hsmciinit
+ * Name: sam_hsmciinit
*
* Description:
* Initialize HSMCI support. This function is called very early in board
@@ -79,31 +78,31 @@
*
************************************************************************************/
-int sam3u_hsmciinit(void)
+int sam_hsmciinit(void)
{
#ifdef GPIO_MCI_CD
- sam3u_configgpio(GPIO_MCI_CD);
+ sam_configgpio(GPIO_MCI_CD);
#endif
#ifdef GPIO_MCI_WP
- sam3u_configgpio(GPIO_MCI_WP);
+ sam_configgpio(GPIO_MCI_WP);
#endif
return OK;
}
/************************************************************************************
- * Name: sam3u_cardinserted
+ * Name: sam_cardinserted
*
* Description:
* Check if a card is inserted into the selected HSMCI slot
*
************************************************************************************/
-bool sam3u_cardinserted(unsigned char slot)
+bool sam_cardinserted(unsigned char slot)
{
if (slot == 0)
{
#ifdef GPIO_MCI_CD
- bool inserted = sam3u_gpioread(GPIO_MCI_CD);
+ bool inserted = sam_gpioread(GPIO_MCI_CD);
fvdbg("inserted: %s\n", inserted ? "NO" : "YES");
return !inserted;
#else
@@ -114,19 +113,19 @@ bool sam3u_cardinserted(unsigned char slot)
}
/************************************************************************************
- * Name: sam3u_writeprotected
+ * Name: sam_writeprotected
*
* Description:
* Check if a card is inserted into the selected HSMCI slot
*
************************************************************************************/
-bool sam3u_writeprotected(unsigned char slot)
+bool sam_writeprotected(unsigned char slot)
{
if (slot == 0)
{
#ifdef GPIO_MCI_WP
- bool protected = sam3u_gpioread(GPIO_MCI_WP);
+ bool protected = sam_gpioread(GPIO_MCI_WP);
fvdbg("protected: %s\n", inserted ? "YES" : "NO");
return protected;
#else
diff --git a/nuttx/configs/sam3u-ek/src/up_nsh.c b/nuttx/configs/sam3u-ek/src/up_nsh.c
index 436704929..dfa296117 100644
--- a/nuttx/configs/sam3u-ek/src/up_nsh.c
+++ b/nuttx/configs/sam3u-ek/src/up_nsh.c
@@ -1,6 +1,5 @@
/****************************************************************************
* config/sam3u-ek/src/up_nsh.c
- * arch/arm/src/board/up_nsh.c
*
* Copyright (C) 2010, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
@@ -48,8 +47,8 @@
#include <nuttx/sdio.h>
#include <nuttx/mmcsd.h>
-#include "sam3u_internal.h"
-#include "sam3uek_internal.h"
+#include "sam_hsmci.h"
+#include "sam3u-ek.h"
#ifdef CONFIG_SAM34_HSMCI
@@ -152,7 +151,7 @@ int nsh_archinitialize(void)
/* Then inform the HSMCI driver if there is or is not a card in the slot. */
- sdio_mediachange(sdio, sam3u_cardinserted(0));
+ sdio_mediachange(sdio, sam_cardinserted(0));
#endif
return OK;
}
diff --git a/nuttx/configs/sam3u-ek/src/up_spi.c b/nuttx/configs/sam3u-ek/src/up_spi.c
index a4b1881bc..b14029f5d 100644
--- a/nuttx/configs/sam3u-ek/src/up_spi.c
+++ b/nuttx/configs/sam3u-ek/src/up_spi.c
@@ -1,6 +1,5 @@
/************************************************************************************
* configs/sam3u-ek/src/up_spi.c
- * arch/arm/src/board/up_spi.c
*
* Copyright (C) 2009, 2011, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
@@ -50,8 +49,9 @@
#include "up_arch.h"
#include "chip.h"
-#include "sam3u_internal.h"
-#include "sam3uek_internal.h"
+#include "sam_gpio.h"
+#include "sam_spi.h"
+#include "sam3u-ek.h"
#ifdef CONFIG_SAM34_SPI
@@ -86,14 +86,14 @@
************************************************************************************/
/************************************************************************************
- * Name: sam3u_spiinitialize
+ * Name: sam_spiinitialize
*
* Description:
* Called to configure SPI chip select GPIO pins for the SAM3U10E-EVAL board.
*
************************************************************************************/
-void weak_function sam3u_spiinitialize(void)
+void weak_function sam_spiinitialize(void)
{
/* The ZigBee module connects used NPCS0. However, there is not yet any
* ZigBee support.
@@ -102,36 +102,35 @@ void weak_function sam3u_spiinitialize(void)
/* The touchscreen connects using NPCS2 (PC14). */
#if defined(CONFIG_INPUT) && defined(CONFIG_INPUT_ADS7843E)
- sam3u_configgpio(GPIO_TSC_NPCS2);
+ sam_configgpio(GPIO_TSC_NPCS2);
#endif
}
/****************************************************************************
- * Name: sam3u_spicsnumber, sam3u_spiselect, sam3u_spistatus, and
- * sam3u_spicmddata
+ * Name: sam_spicsnumber, sam_spiselect, sam_spistatus, and sam_spicmddata
*
* Description:
* These external functions must be provided by board-specific logic. They
* include:
*
- * o sam3u_spicsnumbe and sam3u_spiselect which are helper functions to
+ * o sam_spicsnumber and sam_spiselect which are helper functions to
* manage the board-specific aspects of the unique SAM3U chip select
* architecture.
- * o sam3u_spistatus and sam3u_spicmddata: Implementations of the status
+ * o sam_spistatus and sam_spicmddata: Implementations of the status
* and cmddata methods of the SPI interface defined by struct spi_ops_
* (see include/nuttx/spi.h). All other methods including
* up_spiinitialize()) are provided by common SAM3U logic.
*
* To use this common SPI logic on your board:
*
- * 1. Provide logic in sam3u_boardinitialize() to configure SPI chip select
+ * 1. Provide logic in sam_boardinitialize() to configure SPI chip select
* pins.
- * 2. Provide sam3u_spicsnumber(), sam3u_spiselect() and sam3u_spistatus()
+ * 2. Provide sam_spicsnumber(), sam_spiselect() and sam_spistatus()
* functions in your board-specific logic. These functions will perform
* chip selection and status operations using GPIOs in the way your board
* is configured.
* 2. If CONFIG_SPI_CMDDATA is defined in the NuttX configuration, provide
- * sam3u_spicmddata() functions in your board-specific logic. This
+ * sam_spicmddata() functions in your board-specific logic. This
* function will perform cmd/data selection operations using GPIOs in
* the way your board is configured.
* 3. Add a call to up_spiinitialize() in your low level application
@@ -144,7 +143,7 @@ void weak_function sam3u_spiinitialize(void)
****************************************************************************/
/****************************************************************************
- * Name: sam3u_spicsnumber
+ * Name: sam_spicsnumber
*
* Description:
* The SAM3U has 4 CS registers for controlling device features. This
@@ -161,7 +160,7 @@ void weak_function sam3u_spiinitialize(void)
*
****************************************************************************/
-int sam3u_spicsnumber(enum spi_dev_e devid)
+int sam_spicsnumber(enum spi_dev_e devid)
{
int cs = -EINVAL;
@@ -179,7 +178,7 @@ int sam3u_spicsnumber(enum spi_dev_e devid)
}
/****************************************************************************
- * Name: sam3u_spiselect
+ * Name: sam_spiselect
*
* Description:
* PIO chip select pins may be programmed by the board specific logic in
@@ -203,7 +202,7 @@ int sam3u_spicsnumber(enum spi_dev_e devid)
*
****************************************************************************/
-void sam3u_spiselect(enum spi_dev_e devid, bool selected)
+void sam_spiselect(enum spi_dev_e devid, bool selected)
{
/* The touchscreen chip select is implemented as a GPIO OUTPUT that must
* be controlled by this function. This is because the ADS7843E driver
@@ -216,13 +215,13 @@ void sam3u_spiselect(enum spi_dev_e devid, bool selected)
#if defined(CONFIG_INPUT) && defined(CONFIG_INPUT_ADS7843E)
if (devid == SPIDEV_TOUCHSCREEN)
{
- sam3u_gpiowrite(GPIO_TSC_NPCS2, !selected);
+ sam_gpiowrite(GPIO_TSC_NPCS2, !selected);
}
#endif
}
/****************************************************************************
- * Name: sam3u_spistatus
+ * Name: sam_spistatus
*
* Description:
* Return status information associated with the SPI device.
@@ -235,7 +234,7 @@ void sam3u_spiselect(enum spi_dev_e devid, bool selected)
*
****************************************************************************/
-uint8_t sam3u_spistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
+uint8_t sam_spistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
{
return 0;
}
diff --git a/nuttx/configs/sam3u-ek/src/up_touchscreen.c b/nuttx/configs/sam3u-ek/src/up_touchscreen.c
index 3157f7160..71b12f571 100644
--- a/nuttx/configs/sam3u-ek/src/up_touchscreen.c
+++ b/nuttx/configs/sam3u-ek/src/up_touchscreen.c
@@ -50,8 +50,8 @@
#include <nuttx/input/touchscreen.h>
#include <nuttx/input/ads7843e.h>
-#include "sam3u_internal.h"
-#include "sam3uek_internal.h"
+#include "sam_gpio.h"
+#include "sam3u-ek.h"
/****************************************************************************
* Pre-Processor Definitions
@@ -165,11 +165,11 @@ static void tsc_enable(FAR struct ads7843e_config_s *state, bool enable)
ivdbg("IRQ:%d enable:%d\n", SAM_TCS_IRQ, enable);
if (enable)
{
- sam3u_gpioirqenable(SAM_TCS_IRQ);
+ sam_gpioirqenable(SAM_TCS_IRQ);
}
else
{
- sam3u_gpioirqdisable(SAM_TCS_IRQ);
+ sam_gpioirqdisable(SAM_TCS_IRQ);
}
}
@@ -186,7 +186,7 @@ static bool tsc_busy(FAR struct ads7843e_config_s *state)
/* REVISIT: This might need to be inverted */
- bool busy = sam3u_gpioread(GPIO_TCS_BUSY);
+ bool busy = sam_gpioread(GPIO_TCS_BUSY);
#if defined(CONFIG_DEBUG_INPUT) && defined(CONFIG_DEBUG_VERBOSE)
if (busy != last)
{
@@ -201,7 +201,7 @@ static bool tsc_pendown(FAR struct ads7843e_config_s *state)
{
/* REVISIT: This might need to be inverted */
- bool pendown = sam3u_gpioread(GPIO_TCS_IRQ);
+ bool pendown = sam_gpioread(GPIO_TCS_IRQ);
ivdbg("pendown:%d\n", pendown);
return pendown;
}
@@ -238,12 +238,12 @@ int arch_tcinitialize(int minor)
/* Configure and enable the ADS7843E interrupt pin as an input */
- (void)sam3u_configgpio(GPIO_TCS_BUSY);
- (void)sam3u_configgpio(GPIO_TCS_IRQ);
+ (void)sam_configgpio(GPIO_TCS_BUSY);
+ (void)sam_configgpio(GPIO_TCS_IRQ);
/* Configure the PIO interrupt */
- sam3u_gpioirq(GPIO_TCS_IRQ);
+ sam_gpioirq(GPIO_TCS_IRQ);
/* Get an instance of the SPI interface */
diff --git a/nuttx/configs/sam3u-ek/src/up_usbdev.c b/nuttx/configs/sam3u-ek/src/up_usbdev.c
index 0fc4a61ec..b67ea88eb 100644
--- a/nuttx/configs/sam3u-ek/src/up_usbdev.c
+++ b/nuttx/configs/sam3u-ek/src/up_usbdev.c
@@ -1,6 +1,5 @@
/************************************************************************************
* configs/sam3u-ek/src/up_usbdev.c
- * arch/arm/src/board/up_usbdev.c
*
* Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
@@ -49,8 +48,7 @@
#include <nuttx/usb/usbdev_trace.h>
#include "up_arch.h"
-#include "sam3u_internal.h"
-#include "sam3uek_internal.h"
+#include "sam3u-ek.h"
/************************************************************************************
* Definitions
@@ -65,46 +63,46 @@
************************************************************************************/
/************************************************************************************
- * Name: sam3u_usbinitialize
+ * Name: sam_usbinitialize
*
* Description:
* Called to setup USB-related GPIO pins for the SAM3U-EK board.
*
************************************************************************************/
-void sam3u_usbinitialize(void)
+void sam_usbinitialize(void)
{
}
/************************************************************************************
- * Name: sam3u_usbpullup
+ * Name: sam_usbpullup
*
* Description:
* If USB is supported and the board supports a pullup via GPIO (for USB software
- * connect and disconnect), then the board software must provide sam3u_pullup.
+ * connect and disconnect), then the board software must provide sam_pullup.
* See include/nuttx/usb/usbdev.h for additional description of this method.
* Alternatively, if no pull-up GPIO the following EXTERN can be redefined to be
* NULL.
*
************************************************************************************/
-int sam3u_usbpullup(FAR struct usbdev_s *dev, bool enable)
+int sam_usbpullup(FAR struct usbdev_s *dev, bool enable)
{
return 0;
}
/************************************************************************************
- * Name: sam3u_usbsuspend
+ * Name: sam_usbsuspend
*
* Description:
- * Board logic must provide the sam3u_usbsuspend logic if the USBDEV driver is
+ * Board logic must provide the sam_usbsuspend logic if the USBDEV driver is
* used. This function is called whenever the USB enters or leaves suspend mode.
* This is an opportunity for the board logic to shutdown clocks, power, etc.
* while the USB is suspended.
*
************************************************************************************/
-void sam3u_usbsuspend(FAR struct usbdev_s *dev, bool resume)
+void sam_usbsuspend(FAR struct usbdev_s *dev, bool resume)
{
ulldbg("resume: %d\n", resume);
}
diff --git a/nuttx/configs/sam3u-ek/src/up_usbmsc.c b/nuttx/configs/sam3u-ek/src/up_usbmsc.c
index 2bba22901..d14a8f29e 100644
--- a/nuttx/configs/sam3u-ek/src/up_usbmsc.c
+++ b/nuttx/configs/sam3u-ek/src/up_usbmsc.c
@@ -48,9 +48,9 @@
#include <nuttx/sdio.h>
#include <nuttx/mmcsd.h>
-#include "sam3u_internal.h"
+#include "sam_hsmci.h"
-#ifdef CONFIG_SAM34_SDIO
+#ifdef CONFIG_SAM34_HSMCI
/****************************************************************************
* Pre-Processor Definitions
@@ -149,4 +149,4 @@ int usbmsc_archinitialize(void)
return OK;
}
-#endif /* CONFIG_SAM34_SDIO */
+#endif /* CONFIG_SAM34_HSMCI */