summaryrefslogtreecommitdiff
path: root/nuttx/configs
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-10-31 18:35:06 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-10-31 18:35:06 +0000
commita843c2be5cd076663201fd86109d031c4f425645 (patch)
tree655d384bf0e061b5cbf08711e7d2def019143f5c /nuttx/configs
parent7badb15542ccc6e5426af8f5ae9a4c9c7469fec9 (diff)
downloadpx4-nuttx-a843c2be5cd076663201fd86109d031c4f425645.tar.gz
px4-nuttx-a843c2be5cd076663201fd86109d031c4f425645.tar.bz2
px4-nuttx-a843c2be5cd076663201fd86109d031c4f425645.zip
Add logic to initialize clocks
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@1108 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/configs')
-rw-r--r--nuttx/configs/olimex-strp711/include/board.h71
-rw-r--r--nuttx/configs/olimex-strp711/ostest/defconfig48
2 files changed, 115 insertions, 4 deletions
diff --git a/nuttx/configs/olimex-strp711/include/board.h b/nuttx/configs/olimex-strp711/include/board.h
index 48ce054cd..d0471c971 100644
--- a/nuttx/configs/olimex-strp711/include/board.h
+++ b/nuttx/configs/olimex-strp711/include/board.h
@@ -32,6 +32,35 @@
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
+/****************************************************************************
+ * Features:
+ *
+ * - MCU: STR711FR2T6 16/32 bit ARM7TDMIā„¢ with 256K Bytes Program Flash,
+ * 64K Bytes RAM, USB 2.0, RTC, 12 bit ADC, 4x UARTs, 2x I2C,2x SPI,
+ * 5x 32bit TIMERS, 2x PWM, 2x CCR, WDT, up to 50MHz operation
+ * - Standard JTAG connector with ARM 2x10 pin layout for programming/debugging
+ * with ARM-JTAG
+ * - USB connector
+ * - Two channel RS232 interface and drivers
+ * - SD/MMC card connector
+ * - Two buttons
+ * - Trimpot connected to ADC
+ * - Two status LEDs
+ * - Buzzer
+ * - UEXT - 10 pin extension connector for Olimex addon peripherials like MP3,
+ * RF2.4Ghz, RFID etc. modules
+ * - 2x SPI connectors
+ * - I2C connector
+ * - On board voltage regulator 3.3V with up to 800mA current
+ * - Single power supply: 6V AC or DC required, USB port can power the board
+ * - Power supply LED
+ * - Power supply filtering capacitor
+ * - RESET circuit
+ * - RESET button
+ * - 4 Mhz crystal oscillator
+ * - 32768 Hz crystal and RTC
+ *
+ ****************************************************************************/
#ifndef _CONFIGS_OLIMEX_STRP711_BOARD_H
#define _CONFIGS_OLIMEX_STRP711_BOARD_H
@@ -43,6 +72,7 @@
#ifndef __ASSEMBLY__
# include <sys/types.h>
#endif
+#include "chip.h"
/****************************************************************************
* Definitions
@@ -50,9 +80,46 @@
/* Clocking *****************************************************************/
-/* RTC Oscillator Frequency value = 32,768 Hz */
+/* Main Oscillator Frequency = 4MHz */
+
+#define STR71X_RCCU_MAIN_OSC (4000000)
+
+/* RTC Oscillator Frequency = 32,768 Hz */
+
+#define STR71X_RCCU_RTC_OSC (32768)
+
+/* HCLK driving PLL2 */
+
+#define STR71X_PCU_HCLK_OSC (4000000) /* ? */
+
+/* PLL1 Setup:
+ *
+ * PLL1 input clock: CLK2 = Main OSC = 4MHz
+ * PLL1 output clock: PLL1OUT = 16 * CLK2 / 2 = 32MHz
+ * PLL1 output: CLK3 = PLL1OUT = 32MHz (hard coded selection)
+ * RCLK = CLK3 = 32MHz (hard coded selection)
+ * APB1 peripheral clock: PCLK1 = RCLK = 32MHz
+ * APB2 peripheral clock: PCLK2 = RCLK = 32MHz
+ * Main system clock: MCLK = RCLK = 32MHz
+ */
+
+#undef STR71X_PLL1IN_DIV2 /* Don't divide main OSC by two */
+#define STR71X_PLL1OUT_MUL STR71X_RCCUPLL1CR_MUL16 /* PLL1OUT = 16 * CLK2 */
+#define STR71X_PLL1OUT_DIV STR71X_RCCUPLL1CR_DIV2 /* PLL1OUT = CLK2 / 2 */
+#define STR71X_APB1_DIV STR71X_PCUPDIVR_APB1DIV1 /* PCLK1 = RCLK */
+#define STR71X_APB2_DIV STR71X_PCUPDIVR_APB1DIV1 /* PCLK2 = RCLK */
+#define STR71X_MCLK_DIV STR71X_PCUMDIVR_DIV1 /* MCLK = RCLK */
+
+/* PLL2 Setup -- only needed for HDLC or USB
+ *
+ * USB input: USB clock
+ * HCLK = 4MHz?
+ * USB clock = 12 * HCLK / 1 = 48 MHz
+ */
-#define STR71X_RCCU_RTC_OSC (32768)
+#undef STR71X_USBIN_PLL2 /* USB input is USB clock */
+#define STR71X_PLL2OUT_MUL STR71X_PCUPPL2CR_MUL12 /* PLL2OUT = 12 * HCLK */
+#define STR71X_PLL2OUT_DIV STR71X_PCUPPL2CR_DIV1 /* PLL2OUT = HCLK / 1 */
/* LED definitions **********************************************************/
diff --git a/nuttx/configs/olimex-strp711/ostest/defconfig b/nuttx/configs/olimex-strp711/ostest/defconfig
index e662dc0f9..70ef9aab9 100644
--- a/nuttx/configs/olimex-strp711/ostest/defconfig
+++ b/nuttx/configs/olimex-strp711/ostest/defconfig
@@ -72,18 +72,48 @@ CONFIG_ARCH_STACKDUMP=y
#
# STR71x specific boot/build settings
#
+# CONFIG_STR71X_I2C0, CONFIG_STR71X_I2C1, CONFIG_STR71X_UART0, CONFIG_STR71X_UART1,
+# CONFIG_STR71X_UART2, CONFIG_STR71X_UART3, CONFIG_STR71X_USB, CONFIG_STR71X_CAN,
+# CONFIG_STR71X_BSPI0, CONFIG_STR71X_BSPI1, CONFIG_STR71X_HDLC, CONFIG_STR71X_XTI,
+# CONFIG_STR71X_GPIO0, CONFIG_STR71X_GPIO1, CONFIG_STR71X_GPIO2, CONFIG_STR71X_ADC12,
+# CONFIG_STR71X_CKOUT, CONFIG_STR71X_TIM1, CONFIG_STR71X_TIM2, CONFIG_STR71X_TIM3, and
+# CONFIG_STR71X_RTC
+# Select peripherals to initialize (Timer0 and EIC are always initialized)
# CONFIG_STR71X_BANK0, CONFIG_STR71X_BANK1, CONFIG_STR71X_BANK2, and CONFIG_STR71X_BANK3
# Enable initialize of external memory banks 0-3.
-# CONFIG_STR71X_BANK0_SIZE, CONFIG_STR71X_BANK1_SIZE, CONFIG_STR71X_BANK2_SIZE, and CONFIG_STR71X_BANK3_SIZE
+# CONFIG_STR71X_BANK0_SIZE, CONFIG_STR71X_BANK1_SIZE, CONFIG_STR71X_BANK2_SIZE, and
+# CONFIG_STR71X_BANK3_SIZE
# If a particular external memory bank is configured, then its width must be provided.
# 8 and 16 (bits) are the only valid options.
-# CONFIG_STR71X_BANK0_WAITSTATES, CONFIG_STR71X_BANK1_WAITSTATES, CONFIG_STR71X_BANK2_WAITSTATES, and CONFIG_STR71X_BANK3_WAITSTATES
+# CONFIG_STR71X_BANK0_WAITSTATES, CONFIG_STR71X_BANK1_WAITSTATES,
+# CONFIG_STR71X_BANK2_WAITSTATES, and CONFIG_STR71X_BANK3_WAITSTATES
# If a particular external memory bank is configured, then the number of waistates
# for the bank must also be provided. Valid options are {0, .., 15}
# CONFIG_STR71X_BIGEXTMEM
# The default is to provide 20 bits of address for all external memory regions. If
# any memory region is larger than 1Mb, then this option should be selected. In this
# case, 24 bits of addressing will be used
+CONFIG_STR71X_I2C0=n
+CONFIG_STR71X_I2C1=n
+CONFIG_STR71X_UART0=y
+CONFIG_STR71X_UART1=y
+CONFIG_STR71X_UART2=n
+CONFIG_STR71X_UART3=n
+CONFIG_STR71X_USB=n
+CONFIG_STR71X_CAN=n
+CONFIG_STR71X_BSPI0=n
+CONFIG_STR71X_BSPI1=n
+CONFIG_STR71X_HDLC=n
+CONFIG_STR71X_XTI=n
+CONFIG_STR71X_GPIO0=y
+CONFIG_STR71X_GPIO1=n
+CONFIG_STR71X_GPIO2=n
+CONFIG_STR71X_ADC12=n
+CONFIG_STR71X_CKOUT=n
+CONFIG_STR71X_TIM1=n
+CONFIG_STR71X_TIM2=n
+CONFIG_STR71X_TIM3=n
+CONFIG_STR71X_RTC=n
CONFIG_STR71X_BANK0=n
CONFIG_STR71X_BANK0_SIZE=16
CONFIG_STR71X_BANK0_WAITSTATES=0
@@ -114,18 +144,32 @@ CONFIG_STR71X_BIGEXTMEM=n
#
CONFIG_UART0_SERIAL_CONSOLE=y
CONFIG_UART1_SERIAL_CONSOLE=n
+CONFIG_UART2_SERIAL_CONSOLE=n
+CONFIG_UART3_SERIAL_CONSOLE=n
CONFIG_UART0_TXBUFSIZE=256
CONFIG_UART1_TXBUFSIZE=256
+CONFIG_UART2_TXBUFSIZE=256
+CONFIG_UART3_TXBUFSIZE=256
CONFIG_UART0_RXBUFSIZE=256
CONFIG_UART1_RXBUFSIZE=256
+CONFIG_UART2_RXBUFSIZE=256
+CONFIG_UART3_RXBUFSIZE=256
CONFIG_UART0_BAUD=38400
CONFIG_UART1_BAUD=38400
+CONFIG_UART2_BAUD=38400
+CONFIG_UART3_BAUD=38400
CONFIG_UART0_BITS=8
CONFIG_UART1_BITS=8
+CONFIG_UART2_BITS=8
+CONFIG_UART3_BITS=8
CONFIG_UART0_PARITY=0
CONFIG_UART1_PARITY=0
+CONFIG_UART2_PARITY=0
+CONFIG_UART3_PARITY=0
CONFIG_UART0_2STOP=0
CONFIG_UART1_2STOP=0
+CONFIG_UART2_2STOP=0
+CONFIG_UART3_2STOP=0
#
# General build options