summaryrefslogtreecommitdiff
path: root/nuttx/configs/pic32mx7mmb/src
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/configs/pic32mx7mmb/src')
-rw-r--r--nuttx/configs/pic32mx7mmb/src/Makefile2
-rw-r--r--nuttx/configs/pic32mx7mmb/src/pic32mx7mmb_internal.h26
-rw-r--r--nuttx/configs/pic32mx7mmb/src/up_boot.c7
-rw-r--r--nuttx/configs/pic32mx7mmb/src/up_lcd.c81
-rw-r--r--nuttx/configs/pic32mx7mmb/src/up_leds.c14
5 files changed, 121 insertions, 9 deletions
diff --git a/nuttx/configs/pic32mx7mmb/src/Makefile b/nuttx/configs/pic32mx7mmb/src/Makefile
index f632086b5..5543f8a43 100644
--- a/nuttx/configs/pic32mx7mmb/src/Makefile
+++ b/nuttx/configs/pic32mx7mmb/src/Makefile
@@ -38,7 +38,7 @@
CFLAGS += -I$(TOPDIR)/sched
ASRCS =
-CSRCS = up_boot.c up_leds.c up_spi.c
+CSRCS = up_boot.c up_lcd.c up_leds.c up_spi.c
ifeq ($(CONFIG_PIC32MX_USBDEV),y)
CSRCS += up_usbdev.c
diff --git a/nuttx/configs/pic32mx7mmb/src/pic32mx7mmb_internal.h b/nuttx/configs/pic32mx7mmb/src/pic32mx7mmb_internal.h
index dceb3c070..db523b67f 100644
--- a/nuttx/configs/pic32mx7mmb/src/pic32mx7mmb_internal.h
+++ b/nuttx/configs/pic32mx7mmb/src/pic32mx7mmb_internal.h
@@ -55,8 +55,12 @@
* RA0 LED0 Pulled-up, low value illuminates
* RA1 LED1 Pulled-up, low value illuminates
* RD9 LED2 Pulled-up, low value illuminates
- * --- LED4 Not controllable by software, indicates MMC/SD activity
+ * RA9 LED4 Not available for general use*, indicates MMC/SD activity
* --- LED5 Not controllable by software, indicates power-on
+ *
+ * * RA9 is also the SD chip select. It will illuminate whenever the SD card
+ * is selected. If SD is not used, then LED4 could also be used as a user-
+ * controlled LED.
*/
/* The Mikroelektronika PIC32MX7 MMB has a joystick:
@@ -71,6 +75,14 @@
* RA10 JOY-CP Joystick CP, HDR1 pin 25 Pulled up, low value when closed
*/
+/* LCD
+ *
+ * ------ -------- ------------------------- --------------------------------
+ * GPIO SIGNAL BOARD CONNECTION NOTES
+ * ------ -------- ------------------------- --------------------------------
+ * RD2 LCD-BLED Backlight Light Low value turns off
+ */
+
/****************************************************************************
* Public Types
****************************************************************************/
@@ -116,6 +128,18 @@ EXTERN void weak_function pic32mx_spiinitialize(void);
EXTERN void pic32mx_ledinit(void);
#endif
+/****************************************************************************
+ * Name: pic32mx_lcdinitialize
+ *
+ * Description:
+ * Initialize the LCD. This function should be called early in the boot
+ * sequence -- even if the LCD is not enabled. In that case we should
+ * at a minimum at least disable the LCD backlight.
+ *
+ ****************************************************************************/
+
+EXTERN void pic32mx_lcdinitialize(void);
+
#undef EXTERN
#ifdef __cplusplus
}
diff --git a/nuttx/configs/pic32mx7mmb/src/up_boot.c b/nuttx/configs/pic32mx7mmb/src/up_boot.c
index 6c6004871..426a70761 100644
--- a/nuttx/configs/pic32mx7mmb/src/up_boot.c
+++ b/nuttx/configs/pic32mx7mmb/src/up_boot.c
@@ -86,6 +86,13 @@ void pic32mx_boardinitialize(void)
}
#endif
+/* Initialize the LCD. The LCD initialization function should be called early in the
+ * boot sequence -- even if the LCD is not enabled. In that case we should
+ * at a minimum at least disable the LCD backlight.
+ */
+
+ pic32mx_lcdinitialize();
+
/* Configure on-board LEDs if LED support has been selected. */
#ifdef CONFIG_ARCH_LEDS
diff --git a/nuttx/configs/pic32mx7mmb/src/up_lcd.c b/nuttx/configs/pic32mx7mmb/src/up_lcd.c
new file mode 100644
index 000000000..26e4e7002
--- /dev/null
+++ b/nuttx/configs/pic32mx7mmb/src/up_lcd.c
@@ -0,0 +1,81 @@
+/****************************************************************************
+ * configs/pic32mx7mmb/src/up_lcd.c
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <debug.h>
+
+#include "pic32mx-internal.h"
+#include "pic32mx7mmb_internal.h"
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+/* LCD
+ *
+ * ------ -------- ------------------------- --------------------------------
+ * GPIO SIGNAL BOARD CONNECTION NOTES
+ * ------ -------- ------------------------- --------------------------------
+ * RD2 LCD-BLED Backlight Light Low value turns off
+ */
+
+#define GPIO_BLED (GPIO_OUTPUT|GPIO_VALUE_ZERO|GPIO_PORTD|GPIO_PIN2)
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: pic32mx_lcdinitialize
+ *
+ * Description:
+ * Initialize the LCD. This function should be called early in the boot
+ * sequendce -- Even if the LCD is not enabled. In that case we should
+ * at a minimum at least disable the LCD backlight.
+ *
+ ****************************************************************************/
+
+void pic32mx_lcdinitialize(void)
+{
+ /* Just configure the backlight control as an output and turn off the
+ * backlight for now.
+ */
+
+ pic32mx_configgpio(GPIO_BLED);
+}
diff --git a/nuttx/configs/pic32mx7mmb/src/up_leds.c b/nuttx/configs/pic32mx7mmb/src/up_leds.c
index 56e00f2ae..187935280 100644
--- a/nuttx/configs/pic32mx7mmb/src/up_leds.c
+++ b/nuttx/configs/pic32mx7mmb/src/up_leds.c
@@ -46,12 +46,7 @@
#include <arch/board/board.h>
-#include "chip.h"
-#include "up_arch.h"
-#include "up_internal.h"
-
#include "pic32mx-internal.h"
-#include "pic32mx-ioport.h"
#include "pic32mx7mmb_internal.h"
/****************************************************************************
@@ -67,11 +62,15 @@
* RA0 LED0 Pulled-up, low value illuminates
* RA1 LED1 Pulled-up, low value illuminates
* RD9 LED2 Pulled-up, low value illuminates
- * --- LED4 Not controllable by software, indicates MMC/SD activity
+ * RA9 LED4 Not available for general use*, indicates MMC/SD activity
* --- LED5 Not controllable by software, indicates power-on
*
- * If CONFIG_ARCH_LEDS is defined, then NuttX will control these LEDs as follows:
+ * * RA9 is also the SD chip select. It will illuminate whenever the SD card
+ * is selected. If SD is not used, then LED4 could also be used as a user-
+ * controlled LED.
*
+ * If CONFIG_ARCH_LEDS is defined, then NuttX will control these LEDs as
+ * follows:
* ON OFF
* ------------------------- ---- ---- ---- ---- ---- ----
* LED0 LED1 LED2 LED0 LED1 LED2
@@ -89,6 +88,7 @@
#define GPIO_LED_0 (GPIO_OUTPUT|GPIO_VALUE_ONE|GPIO_PORTA|GPIO_PIN0)
#define GPIO_LED_1 (GPIO_OUTPUT|GPIO_VALUE_ONE|GPIO_PORTA|GPIO_PIN1)
#define GPIO_LED_2 (GPIO_OUTPUT|GPIO_VALUE_ONE|GPIO_PORTD|GPIO_PIN9)
+#define GPIO_LED_4 (GPIO_OUTPUT|GPIO_VALUE_ONE|GPIO_PORTA|GPIO_PIN9)
/* LED Management Definitions ***********************************************/