diff options
Diffstat (limited to 'arch/blackfin')
20 files changed, 290 insertions, 702 deletions
| diff --git a/arch/blackfin/cpu/Makefile b/arch/blackfin/cpu/Makefile index 0a72ec5df..1421cb2ca 100644 --- a/arch/blackfin/cpu/Makefile +++ b/arch/blackfin/cpu/Makefile @@ -18,14 +18,12 @@ CEXTRA   := initcode.o  SEXTRA   := start.o  SOBJS    := interrupt.o cache.o  COBJS-y  += cpu.o -COBJS-y  += gpio.o +COBJS-$(CONFIG_ADI_GPIO1) += gpio.o  COBJS-y  += interrupts.o  COBJS-$(CONFIG_JTAG_CONSOLE) += jtag-console.o  COBJS-y  += os_log.o  COBJS-y  += reset.o -COBJS-y  += serial.o  COBJS-y  += traps.o -COBJS-$(CONFIG_HW_WATCHDOG)  += watchdog.o  SRCS     := $(SEXTRA:.o=.S) $(SOBJS:.o=.S) $(COBJS-y:.o=.c)  OBJS     := $(addprefix $(obj),$(COBJS-y) $(SOBJS)) diff --git a/arch/blackfin/cpu/cpu.c b/arch/blackfin/cpu/cpu.c index 0be2e2b83..218f57ed3 100644 --- a/arch/blackfin/cpu/cpu.c +++ b/arch/blackfin/cpu/cpu.c @@ -16,13 +16,39 @@  #include <asm/mach-common/bits/core.h>  #include <asm/mach-common/bits/ebiu.h>  #include <asm/mach-common/bits/trace.h> +#include <asm/serial.h>  #include "cpu.h" -#include "serial.h"  #include "initcode.h"  ulong bfin_poweron_retx; +#if defined(CONFIG_CORE1_RUN) && defined(COREB_L1_CODE_START) +void bfin_core1_start(void) +{ +#ifdef BF561_FAMILY +	/* Enable core 1 */ +	bfin_write_SYSCR(bfin_read_SYSCR() & ~0x0020); +#else +	/* Enable core 1 */ +	bfin_write32(RCU0_SVECT1, COREB_L1_CODE_START); +	bfin_write32(RCU0_CRCTL, 0); + +	bfin_write32(RCU0_CRCTL, 0x2); + +	/* Check if core 1 starts */ +	while (!(bfin_read32(RCU0_CRSTAT) & 0x2)) +		continue; + +	bfin_write32(RCU0_CRCTL, 0); + +	/* flag to notify cces core 1 application */ +	bfin_write32(SDU0_MSG_SET, (1 << 19)); +#endif +} +#endif + +__attribute__ ((__noreturn__))  void cpu_init_f(ulong bootflag, ulong loaded_from_ldr)  {  #ifndef CONFIG_BFIN_BOOTROM_USES_EVT1 @@ -72,6 +98,10 @@ void cpu_init_f(ulong bootflag, ulong loaded_from_ldr)  # endif  #endif +#if defined(CONFIG_CORE1_RUN) && defined(COREB_L1_CODE_START) +	bfin_core1_start(); +#endif +  	serial_early_puts("Board init flash\n");  	board_init_f(bootflag);  } diff --git a/arch/blackfin/cpu/gpio.c b/arch/blackfin/cpu/gpio.c index f684be531..f74a0b7c0 100644 --- a/arch/blackfin/cpu/gpio.c +++ b/arch/blackfin/cpu/gpio.c @@ -1,5 +1,6 @@  /* - * GPIO Abstraction Layer + * ADI GPIO1 Abstraction Layer + * Support BF50x, BF51x, BF52x, BF53x and BF561 only.   *   * Copyright 2006-2010 Analog Devices Inc.   * @@ -55,25 +56,6 @@ static struct gpio_port_t * const gpio_array[] = {  	(struct gpio_port_t *) FIO0_FLAG_D,  	(struct gpio_port_t *) FIO1_FLAG_D,  	(struct gpio_port_t *) FIO2_FLAG_D, -#elif defined(CONFIG_BF54x) -	(struct gpio_port_t *)PORTA_FER, -	(struct gpio_port_t *)PORTB_FER, -	(struct gpio_port_t *)PORTC_FER, -	(struct gpio_port_t *)PORTD_FER, -	(struct gpio_port_t *)PORTE_FER, -	(struct gpio_port_t *)PORTF_FER, -	(struct gpio_port_t *)PORTG_FER, -	(struct gpio_port_t *)PORTH_FER, -	(struct gpio_port_t *)PORTI_FER, -	(struct gpio_port_t *)PORTJ_FER, -#elif defined(CONFIG_BF60x) -	(struct gpio_port_t *)PORTA_FER, -	(struct gpio_port_t *)PORTB_FER, -	(struct gpio_port_t *)PORTC_FER, -	(struct gpio_port_t *)PORTD_FER, -	(struct gpio_port_t *)PORTE_FER, -	(struct gpio_port_t *)PORTF_FER, -	(struct gpio_port_t *)PORTG_FER,  #else  # error no gpio arrays defined  #endif @@ -174,12 +156,6 @@ DECLARE_RESERVED_MAP(peri, gpio_bank(MAX_RESOURCES));  inline int check_gpio(unsigned gpio)  { -#if defined(CONFIG_BF54x) -	if (gpio == GPIO_PB15 || gpio == GPIO_PC14 || gpio == GPIO_PC15 -	    || gpio == GPIO_PH14 || gpio == GPIO_PH15 -	    || gpio == GPIO_PJ14 || gpio == GPIO_PJ15) -		return -EINVAL; -#endif  	if (gpio >= MAX_BLACKFIN_GPIOS)  		return -EINVAL;  	return 0; @@ -218,18 +194,6 @@ static void port_setup(unsigned gpio, unsigned short usage)  	else  		*port_fer[gpio_bank(gpio)] |= gpio_bit(gpio);  	SSYNC(); -#elif defined(CONFIG_BF54x) -	if (usage == GPIO_USAGE) -		gpio_array[gpio_bank(gpio)]->port_fer &= ~gpio_bit(gpio); -	else -		gpio_array[gpio_bank(gpio)]->port_fer |= gpio_bit(gpio); -	SSYNC(); -#elif defined(CONFIG_BF60x) -	if (usage == GPIO_USAGE) -		gpio_array[gpio_bank(gpio)]->port_fer_clear = gpio_bit(gpio); -	else -		gpio_array[gpio_bank(gpio)]->port_fer_set = gpio_bit(gpio); -	SSYNC();  #endif  } @@ -304,30 +268,6 @@ static void portmux_setup(unsigned short per)  		}  	}  } -#elif defined(CONFIG_BF54x) || defined(CONFIG_BF60x) -inline void portmux_setup(unsigned short per) -{ -	u32 pmux; -	u16 ident = P_IDENT(per); -	u16 function = P_FUNCT2MUX(per); - -	pmux = gpio_array[gpio_bank(ident)]->port_mux; - -	pmux &= ~(0x3 << (2 * gpio_sub_n(ident))); -	pmux |= (function & 0x3) << (2 * gpio_sub_n(ident)); - -	gpio_array[gpio_bank(ident)]->port_mux = pmux; -} - -inline u16 get_portmux(unsigned short per) -{ -	u32 pmux; -	u16 ident = P_IDENT(per); - -	pmux = gpio_array[gpio_bank(ident)]->port_mux; - -	return (pmux >> (2 * gpio_sub_n(ident)) & 0x3); -}  #elif defined(CONFIG_BF52x) || defined(CONFIG_BF51x)  inline void portmux_setup(unsigned short per)  { @@ -344,7 +284,6 @@ inline void portmux_setup(unsigned short per)  # define portmux_setup(...)  do { } while (0)  #endif -#if !defined(CONFIG_BF54x) && !defined(CONFIG_BF60x)  /***********************************************************  *  * FUNCTIONS: Blackfin General Purpose Ports Access Functions @@ -491,15 +430,6 @@ GET_GPIO_P(both)  GET_GPIO_P(maska)  GET_GPIO_P(maskb) -#else /* CONFIG_BF54x */ - -unsigned short get_gpio_dir(unsigned gpio) -{ -	return (0x01 & (gpio_array[gpio_bank(gpio)]->dir_clear >> gpio_sub_n(gpio))); -} - -#endif /* CONFIG_BF54x */ -  /***********************************************************  *  * FUNCTIONS:	Blackfin Peripheral Resource Allocation @@ -548,11 +478,7 @@ int peripheral_request(unsigned short per, const char *label)  		 * be requested and used by several drivers  		 */ -#if defined(CONFIG_BF54x) || defined(CONFIG_BF60x) -		if (!((per & P_MAYSHARE) && get_portmux(per) == P_FUNCT2MUX(per))) { -#else  		if (!(per & P_MAYSHARE)) { -#endif  			/*  			 * Allow that the identical pin function can  			 * be requested from the same driver twice @@ -641,7 +567,7 @@ void peripheral_free_list(const unsigned short per[])  * MODIFICATION HISTORY :  **************************************************************/ -int bfin_gpio_request(unsigned gpio, const char *label) +int gpio_request(unsigned gpio, const char *label)  {  	if (check_gpio(gpio) < 0)  		return -EINVAL; @@ -665,11 +591,9 @@ int bfin_gpio_request(unsigned gpio, const char *label)  		       gpio, get_label(gpio));  		return -EBUSY;  	} -#if !defined(CONFIG_BF54x) && !defined(CONFIG_BF60x)  	else {	/* Reset POLAR setting when acquiring a gpio for the first time */  		set_gpio_polar(gpio, 0);  	} -#endif  	reserve(gpio, gpio);  	set_label(gpio, label); @@ -679,27 +603,27 @@ int bfin_gpio_request(unsigned gpio, const char *label)  	return 0;  } -#ifdef CONFIG_BFIN_GPIO_TRACK -void bfin_gpio_free(unsigned gpio) +int gpio_free(unsigned gpio)  {  	if (check_gpio(gpio) < 0) -		return; +		return -1;  	if (unlikely(!is_reserved(gpio, gpio, 0))) {  		gpio_error(gpio); -		return; +		return -1;  	}  	unreserve(gpio, gpio);  	set_label(gpio, "free"); + +	return 0;  } -#endif -#ifdef BFIN_SPECIAL_GPIO_BANKS +#ifdef ADI_SPECIAL_GPIO_BANKS  DECLARE_RESERVED_MAP(special_gpio, gpio_bank(MAX_RESOURCES)); -int bfin_special_gpio_request(unsigned gpio, const char *label) +int special_gpio_request(unsigned gpio, const char *label)  {  	/*  	 * Allow that the identical GPIO can @@ -731,7 +655,7 @@ int bfin_special_gpio_request(unsigned gpio, const char *label)  	return 0;  } -void bfin_special_gpio_free(unsigned gpio) +void special_gpio_free(unsigned gpio)  {  	if (unlikely(!is_reserved(special_gpio, gpio, 0))) {  		gpio_error(gpio); @@ -744,21 +668,13 @@ void bfin_special_gpio_free(unsigned gpio)  }  #endif -static inline void __bfin_gpio_direction_input(unsigned gpio) +static inline void __gpio_direction_input(unsigned gpio)  { -#if defined(CONFIG_BF54x) || defined(CONFIG_BF60x) -	gpio_array[gpio_bank(gpio)]->dir_clear = gpio_bit(gpio); -#else  	gpio_array[gpio_bank(gpio)]->dir &= ~gpio_bit(gpio); -#endif -#if defined(CONFIG_BF60x) -	gpio_array[gpio_bank(gpio)]->inen_set = gpio_bit(gpio); -#else  	gpio_array[gpio_bank(gpio)]->inen |= gpio_bit(gpio); -#endif  } -int bfin_gpio_direction_input(unsigned gpio) +int gpio_direction_input(unsigned gpio)  {  	unsigned long flags; @@ -768,31 +684,24 @@ int bfin_gpio_direction_input(unsigned gpio)  	}  	local_irq_save(flags); -	__bfin_gpio_direction_input(gpio); +	__gpio_direction_input(gpio);  	AWA_DUMMY_READ(inen);  	local_irq_restore(flags);  	return 0;  } -void bfin_gpio_toggle_value(unsigned gpio) -{ -#ifdef CONFIG_BF54x -	gpio_set_value(gpio, !gpio_get_value(gpio)); -#else -	gpio_array[gpio_bank(gpio)]->toggle = gpio_bit(gpio); -#endif -} - -void bfin_gpio_set_value(unsigned gpio, int arg) +int gpio_set_value(unsigned gpio, int arg)  {  	if (arg)  		gpio_array[gpio_bank(gpio)]->data_set = gpio_bit(gpio);  	else  		gpio_array[gpio_bank(gpio)]->data_clear = gpio_bit(gpio); + +	return 0;  } -int bfin_gpio_direction_output(unsigned gpio, int value) +int gpio_direction_output(unsigned gpio, int value)  {  	unsigned long flags; @@ -803,17 +712,9 @@ int bfin_gpio_direction_output(unsigned gpio, int value)  	local_irq_save(flags); -#if defined(CONFIG_BF60x) -	gpio_array[gpio_bank(gpio)]->inen_clear = gpio_bit(gpio); -#else  	gpio_array[gpio_bank(gpio)]->inen &= ~gpio_bit(gpio); -#endif  	gpio_set_value(gpio, value); -#if defined(CONFIG_BF54x) || defined(CONFIG_BF60x) -	gpio_array[gpio_bank(gpio)]->dir_set = gpio_bit(gpio); -#else  	gpio_array[gpio_bank(gpio)]->dir |= gpio_bit(gpio); -#endif  	AWA_DUMMY_READ(dir);  	local_irq_restore(flags); @@ -821,11 +722,8 @@ int bfin_gpio_direction_output(unsigned gpio, int value)  	return 0;  } -int bfin_gpio_get_value(unsigned gpio) +int gpio_get_value(unsigned gpio)  { -#if defined(CONFIG_BF54x) || defined(CONFIG_BF60x) -	return (1 & (gpio_array[gpio_bank(gpio)]->data >> gpio_sub_n(gpio))); -#else  	unsigned long flags;  	if (unlikely(get_gpio_edge(gpio))) { @@ -838,7 +736,6 @@ int bfin_gpio_get_value(unsigned gpio)  		return ret;  	} else  		return get_gpio_data(gpio); -#endif  }  /* If we are booting from SPI and our board lacks a strong enough pull up, @@ -860,8 +757,7 @@ void bfin_reset_boot_spi_cs(unsigned short pin)  	udelay(1);  } -#ifdef CONFIG_BFIN_GPIO_TRACK -void bfin_gpio_labels(void) +void gpio_labels(void)  {  	int c, gpio; @@ -877,4 +773,3 @@ void bfin_gpio_labels(void)  			continue;  	}  } -#endif diff --git a/arch/blackfin/cpu/initcode.c b/arch/blackfin/cpu/initcode.c index 1a066806d..ffaf1017d 100644 --- a/arch/blackfin/cpu/initcode.c +++ b/arch/blackfin/cpu/initcode.c @@ -13,12 +13,12 @@  #include <config.h>  #include <asm/blackfin.h> +#include <asm/mach-common/bits/watchdog.h>  #include <asm/mach-common/bits/bootrom.h>  #include <asm/mach-common/bits/core.h> +#include <asm/serial.h> -#define BUG() while (1) { asm volatile("emuexcpt;"); } - -#include "serial.h" +#define BUG() while (1) asm volatile("emuexcpt;");  #ifndef __ADSPBF60x__  #include <asm/mach-common/bits/ebiu.h> @@ -193,17 +193,12 @@ static inline void serial_init(void)  	}  #endif +#if CONFIG_BFIN_BOOT_MODE != BFIN_BOOT_BYPASS  	if (BFIN_DEBUG_EARLY_SERIAL) { -		int enabled = serial_early_enabled(uart_base); -  		serial_early_init(uart_base); - -		/* If the UART is off, that means we need to program -		 * the baud rate ourselves initially. -		 */ -		if (!enabled) -			serial_early_set_baud(uart_base, CONFIG_BAUDRATE); +		serial_early_set_baud(uart_base, CONFIG_BAUDRATE);  	} +#endif  }  __attribute__((always_inline)) @@ -262,7 +257,8 @@ program_nmi_handler(void)  		"%1 = RETS;" /* Load addr of NMI handler */  		"RETS = %0;" /* Restore RETS */  		"[%2] = %1;" /* Write NMI handler */ -		: "=r"(tmp1), "=r"(tmp2) : "ab"(EVT2) +		: "=d"(tmp1), "=d"(tmp2) +		: "ab"(EVT2)  	);  } @@ -462,19 +458,29 @@ program_early_devices(ADI_BOOT_DATA *bs, uint *sdivB, uint *divB, uint *vcoB)  	if (CONFIG_BFIN_BOOT_MODE != BFIN_BOOT_BYPASS) {  		serial_putc('e');  #ifdef __ADSPBF60x__ +		/* Reset system event controller */  		bfin_write_SEC_GCTL(0x2); +		bfin_write_SEC_CCTL(0x2);  		SSYNC(); + +		/* Enable fault event input and system reset action in fault +		 * controller. Route watchdog timeout event to fault interface. +		 */  		bfin_write_SEC_FCTL(0xc1); +		/* Enable watchdog interrupt source */  		bfin_write_SEC_SCTL(2, bfin_read_SEC_SCTL(2) | 0x6); - -		bfin_write_SEC_CCTL(0x2);  		SSYNC(); + +		/* Enable system event controller */  		bfin_write_SEC_GCTL(0x1);  		bfin_write_SEC_CCTL(0x1); +		SSYNC();  #endif +		bfin_write_WDOG_CTL(WDDIS); +		SSYNC();  		bfin_write_WDOG_CNT(MSEC_TO_SCLK(CONFIG_HW_WATCHDOG_TIMEOUT_INITCODE));  #if CONFIG_BFIN_BOOT_MODE != BFIN_BOOT_UART -		bfin_write_WDOG_CTL(0); +		bfin_write_WDOG_CTL(WDEN);  #endif  		serial_putc('f');  	} @@ -713,37 +719,32 @@ program_clocks(ADI_BOOT_DATA *bs, bool put_into_srfs)  __attribute__((always_inline)) static inline void  update_serial_clocks(ADI_BOOT_DATA *bs, uint sdivB, uint divB, uint vcoB)  { -	serial_putc('a'); -  	/* Since we've changed the SCLK above, we may need to update  	 * the UART divisors (UART baud rates are based on SCLK).  	 * Do the division by hand as there are no native instructions  	 * for dividing which means we'd generate a libgcc reference.  	 */ -	if (CONFIG_BFIN_BOOT_MODE == BFIN_BOOT_UART) { -		unsigned int sdivR, vcoR; -		int dividend = sdivB * divB * vcoR; -		int divisor = vcoB * sdivR; -		unsigned int quotient; +	unsigned int sdivR, vcoR; +	unsigned int dividend; +	unsigned int divisor; +	unsigned int quotient; -		serial_putc('b'); +	serial_putc('a');  #ifdef __ADSPBF60x__ -		sdivR = bfin_read_CGU_DIV(); -		sdivR = ((sdivR >> 8) & 0x1f) * ((sdivR >> 5) & 0x7); -		vcoR = (bfin_read_CGU_CTL() >> 8) & 0x7f; +	sdivR = bfin_read_CGU_DIV(); +	sdivR = ((sdivR >> 8) & 0x1f) * ((sdivR >> 5) & 0x7); +	vcoR = (bfin_read_CGU_CTL() >> 8) & 0x7f;  #else -		sdivR = bfin_read_PLL_DIV() & 0xf; -		vcoR = (bfin_read_PLL_CTL() >> 9) & 0x3f; +	sdivR = bfin_read_PLL_DIV() & 0xf; +	vcoR = (bfin_read_PLL_CTL() >> 9) & 0x3f;  #endif -		for (quotient = 0; dividend > 0; ++quotient) -			dividend -= divisor; -		serial_early_put_div(quotient - ANOMALY_05000230); -		serial_putc('c'); -	} - -	serial_putc('d'); +	dividend = sdivB * divB * vcoR; +	divisor = vcoB * sdivR; +	quotient = early_division(dividend, divisor); +	serial_early_put_div(quotient - ANOMALY_05000230); +	serial_putc('c');  }  __attribute__((always_inline)) static inline void diff --git a/arch/blackfin/cpu/serial.c b/arch/blackfin/cpu/serial.c deleted file mode 100644 index 9847e9f2c..000000000 --- a/arch/blackfin/cpu/serial.c +++ /dev/null @@ -1,369 +0,0 @@ -/* - * U-boot - serial.c Blackfin Serial Driver - * - * Copyright (c) 2005-2008 Analog Devices Inc. - * - * Copyright (c) 2003	Bas Vermeulen <bas@buyways.nl>, - *			BuyWays B.V. (www.buyways.nl) - * - * Based heavily on: - * blkfinserial.c: Serial driver for BlackFin DSP internal USRTs. - * Copyright(c) 2003	Metrowerks	<mwaddel@metrowerks.com> - * Copyright(c)	2001	Tony Z. Kou	<tonyko@arcturusnetworks.com> - * Copyright(c)	2001-2002 Arcturus Networks Inc. <www.arcturusnetworks.com> - * - * Based on code from 68328 version serial driver imlpementation which was: - * Copyright (C) 1995       David S. Miller    <davem@caip.rutgers.edu> - * Copyright (C) 1998       Kenneth Albanowski <kjahds@kjahds.com> - * Copyright (C) 1998, 1999 D. Jeff Dionne     <jeff@uclinux.org> - * Copyright (C) 1999       Vladimir Gurevich  <vgurevic@cisco.com> - * - * (C) Copyright 2000-2004 - * Wolfgang Denk, DENX Software Engineering, wd@denx.de. - * - * Licensed under the GPL-2 or later. - */ - -/* Anomaly notes: - *  05000086 - we don't support autobaud - *  05000099 - we only use DR bit, so losing others is not a problem - *  05000100 - we don't use the UART_IIR register - *  05000215 - we poll the uart (no dma/interrupts) - *  05000225 - no workaround possible, but this shouldnt cause errors ... - *  05000230 - we tweak the baud rate calculation slightly - *  05000231 - we always use 1 stop bit - *  05000309 - we always enable the uart before we modify it in anyway - *  05000350 - we always enable the uart regardless of boot mode - *  05000363 - we don't support break signals, so don't generate one - */ - -#include <common.h> -#include <post.h> -#include <watchdog.h> -#include <serial.h> -#include <linux/compiler.h> -#include <asm/blackfin.h> - -DECLARE_GLOBAL_DATA_PTR; - -#ifdef CONFIG_UART_CONSOLE - -#include "serial.h" - -#ifdef CONFIG_DEBUG_SERIAL -static uart_lsr_t cached_lsr[256]; -static uart_lsr_t cached_rbr[256]; -static size_t cache_count; - -/* The LSR is read-to-clear on some parts, so we have to make sure status - * bits aren't inadvertently lost when doing various tests.  This also - * works around anomaly 05000099 at the same time by keeping a cumulative - * tally of all the status bits. - */ -static uart_lsr_t uart_lsr_save; -static uart_lsr_t uart_lsr_read(uint32_t uart_base) -{ -	uart_lsr_t lsr = _lsr_read(pUART); -	uart_lsr_save |= (lsr & (OE|PE|FE|BI)); -	return lsr | uart_lsr_save; -} -/* Just do the clear for everyone since it can't hurt. */ -static void uart_lsr_clear(uint32_t uart_base) -{ -	uart_lsr_save = 0; -	_lsr_write(pUART, -1); -} -#else -/* When debugging is disabled, we only care about the DR bit, so if other - * bits get set/cleared, we don't really care since we don't read them - * anyways (and thus anomaly 05000099 is irrelevant). - */ -static inline uart_lsr_t uart_lsr_read(uint32_t uart_base) -{ -	return _lsr_read(pUART); -} -static void uart_lsr_clear(uint32_t uart_base) -{ -	_lsr_write(pUART, -1); -} -#endif - -static void uart_putc(uint32_t uart_base, const char c) -{ -	/* send a \r for compatibility */ -	if (c == '\n') -		serial_putc('\r'); - -	WATCHDOG_RESET(); - -	/* wait for the hardware fifo to clear up */ -	while (!(uart_lsr_read(uart_base) & THRE)) -		continue; - -	/* queue the character for transmission */ -	bfin_write(&pUART->thr, c); -	SSYNC(); - -	WATCHDOG_RESET(); -} - -static int uart_tstc(uint32_t uart_base) -{ -	WATCHDOG_RESET(); -	return (uart_lsr_read(uart_base) & DR) ? 1 : 0; -} - -static int uart_getc(uint32_t uart_base) -{ -	uint16_t uart_rbr_val; - -	/* wait for data ! */ -	while (!uart_tstc(uart_base)) -		continue; - -	/* grab the new byte */ -	uart_rbr_val = bfin_read(&pUART->rbr); - -#ifdef CONFIG_DEBUG_SERIAL -	/* grab & clear the LSR */ -	uart_lsr_t uart_lsr_val = uart_lsr_read(uart_base); - -	cached_lsr[cache_count] = uart_lsr_val; -	cached_rbr[cache_count] = uart_rbr_val; -	cache_count = (cache_count + 1) % ARRAY_SIZE(cached_lsr); - -	if (uart_lsr_val & (OE|PE|FE|BI)) { -		printf("\n[SERIAL ERROR]\n"); -		do { -			--cache_count; -			printf("\t%3zu: RBR=0x%02x LSR=0x%02x\n", cache_count, -				cached_rbr[cache_count], cached_lsr[cache_count]); -		} while (cache_count > 0); -		return -1; -	} -#endif -	uart_lsr_clear(uart_base); - -	return uart_rbr_val; -} - -#if CONFIG_POST & CONFIG_SYS_POST_UART -# define LOOP(x) x -#else -# define LOOP(x) -#endif - -#if BFIN_UART_HW_VER < 4 - -LOOP( -static void uart_loop(uint32_t uart_base, int state) -{ -	u16 mcr; - -	/* Drain the TX fifo first so bytes don't come back */ -	while (!(uart_lsr_read(uart_base) & TEMT)) -		continue; - -	mcr = bfin_read(&pUART->mcr); -	if (state) -		mcr |= LOOP_ENA | MRTS; -	else -		mcr &= ~(LOOP_ENA | MRTS); -	bfin_write(&pUART->mcr, mcr); -} -) - -#else - -LOOP( -static void uart_loop(uint32_t uart_base, int state) -{ -	u32 control; - -	/* Drain the TX fifo first so bytes don't come back */ -	while (!(uart_lsr_read(uart_base) & TEMT)) -		continue; - -	control = bfin_read(&pUART->control); -	if (state) -		control |= LOOP_ENA | MRTS; -	else -		control &= ~(LOOP_ENA | MRTS); -	bfin_write(&pUART->control, control); -} -) - -#endif - -#ifdef CONFIG_SYS_BFIN_UART - -static void uart_puts(uint32_t uart_base, const char *s) -{ -	while (*s) -		uart_putc(uart_base, *s++); -} - -#define DECL_BFIN_UART(n) \ -static int uart##n##_init(void) \ -{ \ -	const unsigned short pins[] = { _P_UART(n, RX), _P_UART(n, TX), 0, }; \ -	peripheral_request_list(pins, "bfin-uart"); \ -	uart_init(MMR_UART(n)); \ -	serial_early_set_baud(MMR_UART(n), gd->baudrate); \ -	uart_lsr_clear(MMR_UART(n)); \ -	return 0; \ -} \ -\ -static int uart##n##_uninit(void) \ -{ \ -	return serial_early_uninit(MMR_UART(n)); \ -} \ -\ -static void uart##n##_setbrg(void) \ -{ \ -	serial_early_set_baud(MMR_UART(n), gd->baudrate); \ -} \ -\ -static int uart##n##_getc(void) \ -{ \ -	return uart_getc(MMR_UART(n)); \ -} \ -\ -static int uart##n##_tstc(void) \ -{ \ -	return uart_tstc(MMR_UART(n)); \ -} \ -\ -static void uart##n##_putc(const char c) \ -{ \ -	uart_putc(MMR_UART(n), c); \ -} \ -\ -static void uart##n##_puts(const char *s) \ -{ \ -	uart_puts(MMR_UART(n), s); \ -} \ -\ -LOOP( \ -static void uart##n##_loop(int state) \ -{ \ -	uart_loop(MMR_UART(n), state); \ -} \ -) \ -\ -struct serial_device bfin_serial##n##_device = { \ -	.name   = "bfin_uart"#n, \ -	.start  = uart##n##_init, \ -	.stop   = uart##n##_uninit, \ -	.setbrg = uart##n##_setbrg, \ -	.getc   = uart##n##_getc, \ -	.tstc   = uart##n##_tstc, \ -	.putc   = uart##n##_putc, \ -	.puts   = uart##n##_puts, \ -	LOOP(.loop = uart##n##_loop) \ -}; - -#ifdef UART0_RBR -DECL_BFIN_UART(0) -#endif -#ifdef UART1_RBR -DECL_BFIN_UART(1) -#endif -#ifdef UART2_RBR -DECL_BFIN_UART(2) -#endif -#ifdef UART3_RBR -DECL_BFIN_UART(3) -#endif - -__weak struct serial_device *default_serial_console(void) -{ -#if CONFIG_UART_CONSOLE == 0 -	return &bfin_serial0_device; -#elif CONFIG_UART_CONSOLE == 1 -	return &bfin_serial1_device; -#elif CONFIG_UART_CONSOLE == 2 -	return &bfin_serial2_device; -#elif CONFIG_UART_CONSOLE == 3 -	return &bfin_serial3_device; -#endif -} - -void bfin_serial_initialize(void) -{ -#ifdef UART0_RBR -	serial_register(&bfin_serial0_device); -#endif -#ifdef UART1_RBR -	serial_register(&bfin_serial1_device); -#endif -#ifdef UART2_RBR -	serial_register(&bfin_serial2_device); -#endif -#ifdef UART3_RBR -	serial_register(&bfin_serial3_device); -#endif -} - -#else - -/* Symbol for our assembly to call. */ -void serial_set_baud(uint32_t baud) -{ -	serial_early_set_baud(UART_BASE, baud); -} - -/* Symbol for common u-boot code to call. - * Setup the baudrate (brg: baudrate generator). - */ -void serial_setbrg(void) -{ -	serial_set_baud(gd->baudrate); -} - -/* Symbol for our assembly to call. */ -void serial_initialize(void) -{ -	serial_early_init(UART_BASE); -} - -/* Symbol for common u-boot code to call. */ -int serial_init(void) -{ -	serial_initialize(); -	serial_setbrg(); -	uart_lsr_clear(UART_BASE); -	return 0; -} - -int serial_tstc(void) -{ -	return uart_tstc(UART_BASE); -} - -int serial_getc(void) -{ -	return uart_getc(UART_BASE); -} - -void serial_putc(const char c) -{ -	uart_putc(UART_BASE, c); -} - -void serial_puts(const char *s) -{ -	while (*s) -		serial_putc(*s++); -} - -LOOP( -void serial_loop(int state) -{ -	uart_loop(UART_BASE, state); -} -) - -#endif - -#endif diff --git a/arch/blackfin/cpu/start.S b/arch/blackfin/cpu/start.S index 7155fc858..da084a87c 100644 --- a/arch/blackfin/cpu/start.S +++ b/arch/blackfin/cpu/start.S @@ -32,10 +32,10 @@  #include <config.h>  #include <asm/blackfin.h> +#include <asm/mach-common/bits/watchdog.h>  #include <asm/mach-common/bits/core.h>  #include <asm/mach-common/bits/pll.h> - -#include "serial.h" +#include <asm/serial.h>  /* It may seem odd that we make calls to functions even though we haven't   * relocated ourselves yet out of {flash,ram,wherever}.  This is OK because @@ -65,20 +65,29 @@ ENTRY(_start)  	p5.h = HI(COREMMR_BASE);  #ifdef CONFIG_HW_WATCHDOG -#ifndef __ADSPBF60x__ -# ifndef CONFIG_HW_WATCHDOG_TIMEOUT_START -#  define CONFIG_HW_WATCHDOG_TIMEOUT_START 5000 -# endif -	/* Program the watchdog with an initial timeout of ~5 seconds. +	/* Program the watchdog with default timeout of ~5 seconds.  	 * That should be long enough to bootstrap ourselves up and  	 * then the common u-boot code can take over.  	 */ +	r1 = WDDIS; +# ifdef __ADSPBF60x__ +	[p4 + (WDOG_CTL - SYSMMR_BASE)] = r1; +# else +	W[p4 + (WDOG_CTL - SYSMMR_BASE)] = r1; +# endif +	SSYNC;  	r0 = 0; -	r0.h = HI(MSEC_TO_SCLK(CONFIG_HW_WATCHDOG_TIMEOUT_START)); +	r0.h = HI(MSEC_TO_SCLK(CONFIG_WATCHDOG_TIMEOUT_MSECS));  	[p4 + (WDOG_CNT - SYSMMR_BASE)] = r0; +	SSYNC; +	r1 = WDEN;  	/* fire up the watchdog - R0.L above needs to be 0x0000 */ -	W[p4 + (WDOG_CTL - SYSMMR_BASE)] = r0; -#endif +# ifdef __ADSPBF60x__ +	[p4 + (WDOG_CTL - SYSMMR_BASE)] = r1; +# else +	W[p4 + (WDOG_CTL - SYSMMR_BASE)] = r1; +# endif +	SSYNC;  #endif  	/* Turn on the serial for debugging the init process */ diff --git a/arch/blackfin/cpu/watchdog.c b/arch/blackfin/cpu/watchdog.c deleted file mode 100644 index 1886bda0a..000000000 --- a/arch/blackfin/cpu/watchdog.c +++ /dev/null @@ -1,23 +0,0 @@ -/* - * watchdog.c - driver for Blackfin on-chip watchdog - * - * Copyright (c) 2007-2009 Analog Devices Inc. - * - * Licensed under the GPL-2 or later. - */ - -#include <common.h> -#include <watchdog.h> -#include <asm/blackfin.h> - -void hw_watchdog_reset(void) -{ -	bfin_write_WDOG_STAT(0); -} - -void hw_watchdog_init(void) -{ -	bfin_write_WDOG_CNT(5 * get_sclk());	/* 5 second timeout */ -	hw_watchdog_reset(); -	bfin_write_WDOG_CTL(0x0); -} diff --git a/arch/blackfin/include/asm/clock.h b/arch/blackfin/include/asm/clock.h new file mode 100644 index 000000000..f1fcd4049 --- /dev/null +++ b/arch/blackfin/include/asm/clock.h @@ -0,0 +1,78 @@ + +/* + * Copyright (C) 2012 Analog Devices Inc. + * Licensed under the GPL-2 or later. + */ + +#ifndef __CLOCK_H__ +#define __CLOCK_H__ + +#include <asm/blackfin.h> +#ifdef PLL_CTL +#include <asm/mach-common/bits/pll.h> +# define pll_is_bypassed() (bfin_read_PLL_CTL() & BYPASS) +#else +#include <asm/mach-common/bits/cgu.h> +# define pll_is_bypassed() (bfin_read_CGU_STAT() & PLLBP) +# define bfin_read_PLL_CTL() bfin_read_CGU_CTL() +# define bfin_read_PLL_DIV() bfin_read_CGU_DIV() +# define SSEL SYSSEL +# define SSEL_P SYSSEL_P +#endif + +__attribute__((always_inline)) +static inline uint32_t early_division(uint32_t dividend, uint32_t divisor) +{ +	uint32_t quotient; +	uint32_t i, j; + +	for (quotient = 1, i = 1; dividend > divisor; ++i) { +		j = divisor << i; +		if (j > dividend || (j & 0x80000000)) { +			--i; +			quotient += (1 << i); +			dividend -= (divisor << i); +			i = 0; +		} +	} + +	return quotient; +} + +__attribute__((always_inline)) +static inline uint32_t early_get_uart_clk(void) +{ +	uint32_t msel, pll_ctl, vco; +	uint32_t div, ssel, sclk, uclk; + +	pll_ctl = bfin_read_PLL_CTL(); +	msel = (pll_ctl & MSEL) >> MSEL_P; +	if (msel == 0) +		msel = (MSEL >> MSEL_P) + 1; + +	vco = (CONFIG_CLKIN_HZ >> (pll_ctl & DF)) * msel; +	sclk = vco; +	if (!pll_is_bypassed()) { +		div = bfin_read_PLL_DIV(); +		ssel = (div & SSEL) >> SSEL_P; +#if CONFIG_BFIN_BOOT_MODE == BFIN_BOOT_BYPASS +		sclk = vco/ssel; +#else +		sclk = early_division(vco, ssel); +#endif +	} +	uclk = sclk; +#ifdef CGU_DIV +	ssel = (div & S0SEL) >> S0SEL_P; +	uclk = early_division(sclk, ssel); +#endif +	return uclk; +} + +#ifdef CGU_DIV +# define get_uart_clk get_sclk0 +#else +# define get_uart_clk get_sclk +#endif + +#endif diff --git a/arch/blackfin/include/asm/dma.h b/arch/blackfin/include/asm/dma.h index ef1db6e99..8a7c07933 100644 --- a/arch/blackfin/include/asm/dma.h +++ b/arch/blackfin/include/asm/dma.h @@ -17,21 +17,21 @@  struct dmasg_large {  	void *next_desc_addr; -	unsigned long start_addr; -	unsigned short cfg; -	unsigned short x_count; -	short x_modify; -	unsigned short y_count; -	short y_modify; +	u32 start_addr; +	u16 cfg; +	u16 x_count; +	s16 x_modify; +	u16 y_count; +	s16 y_modify;  } __attribute__((packed));  struct dmasg { -	unsigned long start_addr; -	unsigned short cfg; -	unsigned short x_count; -	short x_modify; -	unsigned short y_count; -	short y_modify; +	u32 start_addr; +	u16 cfg; +	u16 x_count; +	s16 x_modify; +	u16 y_count; +	s16 y_modify;  } __attribute__((packed));  struct dma_register { diff --git a/arch/blackfin/include/asm/gpio.h b/arch/blackfin/include/asm/gpio.h index 05131b5e8..58a619110 100644 --- a/arch/blackfin/include/asm/gpio.h +++ b/arch/blackfin/include/asm/gpio.h @@ -7,6 +7,8 @@  #ifndef __ARCH_BLACKFIN_GPIO_H__  #define __ARCH_BLACKFIN_GPIO_H__ +#include <asm-generic/gpio.h> +  #define gpio_bank(x)	((x) >> 4)  #define gpio_bit(x)	(1<<((x) & 0xF))  #define gpio_sub_n(x)	((x) & 0xF) @@ -65,10 +67,11 @@  #define PERIPHERAL_USAGE 1  #define GPIO_USAGE 0 +#define MAX_GPIOS MAX_BLACKFIN_GPIOS  #ifndef __ASSEMBLY__ -#if !defined(CONFIG_BF54x) && !defined(CONFIG_BF60x) +#ifdef CONFIG_ADI_GPIO1  void set_gpio_dir(unsigned, unsigned short);  void set_gpio_inen(unsigned, unsigned short);  void set_gpio_polar(unsigned, unsigned short); @@ -140,61 +143,16 @@ struct gpio_port_t {  };  #endif -#ifdef CONFIG_BFIN_GPIO_TRACK -void bfin_gpio_labels(void); -void bfin_gpio_free(unsigned gpio); -#else -#define bfin_gpio_labels() -#define bfin_gpio_free(gpio) -#define bfin_gpio_request(gpio, label) bfin_gpio_request(gpio) -#define bfin_special_gpio_request(gpio, label) bfin_special_gpio_request(gpio) -#endif - -#ifdef BFIN_SPECIAL_GPIO_BANKS -void bfin_special_gpio_free(unsigned gpio); -int bfin_special_gpio_request(unsigned gpio, const char *label); +#ifdef ADI_SPECIAL_GPIO_BANKS +void special_gpio_free(unsigned gpio); +int special_gpio_request(unsigned gpio, const char *label);  #endif -int bfin_gpio_request(unsigned gpio, const char *label); -int bfin_gpio_direction_input(unsigned gpio); -int bfin_gpio_direction_output(unsigned gpio, int value); -int bfin_gpio_get_value(unsigned gpio); -void bfin_gpio_set_value(unsigned gpio, int value); -void bfin_gpio_toggle_value(unsigned gpio); - -static inline int gpio_request(unsigned gpio, const char *label) -{ -	return bfin_gpio_request(gpio, label); -} - -static inline void gpio_free(unsigned gpio) -{ -	return bfin_gpio_free(gpio); -} - -static inline int gpio_direction_input(unsigned gpio) -{ -	return bfin_gpio_direction_input(gpio); -} - -static inline int gpio_direction_output(unsigned gpio, int value) -{ -	return bfin_gpio_direction_output(gpio, value); -} - -static inline int gpio_get_value(unsigned gpio) -{ -	return bfin_gpio_get_value(gpio); -} - -static inline void gpio_set_value(unsigned gpio, int value) -{ -	return bfin_gpio_set_value(gpio, value); -} +void gpio_labels(void);  static inline int gpio_is_valid(int number)  { -	return number >= 0 && number < MAX_BLACKFIN_GPIOS; +	return number >= 0 && number < MAX_GPIOS;  }  #include <linux/ctype.h> @@ -248,7 +206,7 @@ static inline int name_to_gpio(const char *name)  }  #define name_to_gpio(n) name_to_gpio(n) -#define gpio_status() bfin_gpio_labels() +#define gpio_status() gpio_labels()  #endif /* __ASSEMBLY__ */ diff --git a/arch/blackfin/include/asm/mach-bf561/BF561_def.h b/arch/blackfin/include/asm/mach-bf561/BF561_def.h index a7ff5a3fe..8fd552f2a 100644 --- a/arch/blackfin/include/asm/mach-bf561/BF561_def.h +++ b/arch/blackfin/include/asm/mach-bf561/BF561_def.h @@ -714,4 +714,6 @@  #define L1_INST_SRAM_SIZE (0xFFA03FFF - 0xFFA00000 + 1)  #define L1_INST_SRAM_END (L1_INST_SRAM + L1_INST_SRAM_SIZE) +#define COREB_L1_CODE_START       0xFF600000 +  #endif /* __BFIN_DEF_ADSP_BF561_proc__ */ diff --git a/arch/blackfin/include/asm/mach-bf609/BF609_def.h b/arch/blackfin/include/asm/mach-bf609/BF609_def.h index 8c1dcd006..02b81d3fd 100644 --- a/arch/blackfin/include/asm/mach-bf609/BF609_def.h +++ b/arch/blackfin/include/asm/mach-bf609/BF609_def.h @@ -128,6 +128,9 @@  #define EMAC0_MACCFG      0xFFC20000 /* EMAC0 MAC Configuration Register */  #define EMAC1_MACCFG      0xFFC22000 /* EMAC1 MAC Configuration Register */ +#define SPI0_REGBASE      0xFFC40400 /* SPI0 Base Address */ +#define SPI1_REGBASE      0xFFC40500 /* SPI1 Base Address */ +  #define DMA10_DSCPTR_NXT  0xFFC05000 /* DMA10 Pointer to Next Initial Desc */  #define DMA10_ADDRSTART   0xFFC05004 /* DMA10 Start Address of Current Buf */  #define DMA10_CFG         0xFFC05008 /* DMA10 Configuration Register */ @@ -244,4 +247,6 @@  #define L1_INST_SRAM_SIZE 0x8000  #define L1_INST_SRAM_END (L1_INST_SRAM + L1_INST_SRAM_SIZE) +#define COREB_L1_CODE_START       0xFF600000 +  #endif /* __BFIN_DEF_ADSP_BF609_proc__ */ diff --git a/arch/blackfin/include/asm/portmux.h b/arch/blackfin/include/asm/portmux.h index 300ef44fd..003694b51 100644 --- a/arch/blackfin/include/asm/portmux.h +++ b/arch/blackfin/include/asm/portmux.h @@ -17,11 +17,6 @@  #define P_MAYSHARE	0x2000  #define P_DONTCARE	0x1000 -#ifndef CONFIG_BFIN_GPIO_TRACK -#define peripheral_request(per, label) peripheral_request(per) -#define peripheral_request_list(per, label) peripheral_request_list(per) -#endif -  #ifndef __ASSEMBLY__  int peripheral_request(unsigned short per, const char *label); diff --git a/arch/blackfin/cpu/serial.h b/arch/blackfin/include/asm/serial.h index 920033966..87a337d1b 100644 --- a/arch/blackfin/cpu/serial.h +++ b/arch/blackfin/include/asm/serial.h @@ -78,19 +78,31 @@ static inline void serial_early_puts(const char *s)  #else  .macro serial_early_init -#ifdef CONFIG_DEBUG_EARLY_SERIAL -	call _serial_initialize; +#if defined(CONFIG_DEBUG_EARLY_SERIAL) && !defined(CONFIG_UART_MEM) +	call __serial_early_init;  #endif  .endm  .macro serial_early_set_baud -#ifdef CONFIG_DEBUG_EARLY_SERIAL +#if defined(CONFIG_DEBUG_EARLY_SERIAL) && !defined(CONFIG_UART_MEM)  	R0.L = LO(CONFIG_BAUDRATE);  	R0.H = HI(CONFIG_BAUDRATE); -	call _serial_set_baud; +	call __serial_early_set_baud;  #endif  .endm +#if CONFIG_BFIN_BOOT_MODE == BFIN_BOOT_BYPASS +#define update_serial_early_string_addr \ +	R1.L = _start; \ +	R1.H = _start; \ +	R0 = R0 - R1; \ +	R1.L = 0; \ +	R1.H = 0x2000; \ +	R0 = R0 + R1; +#else +#define update_serial_early_string_addr +#endif +  /* Since we embed the string right into our .text section, we need   * to find its address.  We do this by getting our PC and adding 2   * bytes (which is the length of the jump instruction).  Then we @@ -108,7 +120,8 @@ static inline void serial_early_puts(const char *s)  	.previous; \  	R0.L = 7b; \  	R0.H = 7b; \ -	call _serial_puts; +	update_serial_early_string_addr \ +	call _uart_early_puts;  #else  # define serial_early_puts(str)  #endif diff --git a/arch/blackfin/cpu/serial1.h b/arch/blackfin/include/asm/serial1.h index a20175bc7..467d3817f 100644 --- a/arch/blackfin/cpu/serial1.h +++ b/arch/blackfin/include/asm/serial1.h @@ -15,6 +15,8 @@  #ifndef __ASSEMBLY__ +#include <asm/clock.h> +  #define MMR_UART(n) _PASTE_UART(n, UART, DLL)  #ifdef UART_DLL  # define UART0_DLL UART_DLL @@ -230,19 +232,6 @@ static inline void serial_early_do_portmux(void)  }  __attribute__((always_inline)) -static inline uint32_t uart_sclk(void) -{ -#if defined(BFIN_IN_INITCODE) || defined(CONFIG_DEBUG_EARLY_SERIAL) -	/* We cannot use get_sclk() early on as it uses -	 * caches in external memory -	 */ -	return CONFIG_CLKIN_HZ * CONFIG_VCO_MULT / CONFIG_SCLK_DIV; -#else -	return get_sclk(); -#endif -} - -__attribute__((always_inline))  static inline int uart_init(uint32_t uart_base)  {  	/* always enable UART -- avoids anomalies 05000309 and 05000350 */ @@ -275,21 +264,8 @@ static inline int serial_early_uninit(uint32_t uart_base)  }  __attribute__((always_inline)) -static inline int serial_early_enabled(uint32_t uart_base) +static inline void serial_set_divisor(uint32_t uart_base, uint16_t divisor)  { -	return bfin_read(&pUART->gctl) & UCEN; -} - -__attribute__((always_inline)) -static inline void serial_early_set_baud(uint32_t uart_base, uint32_t baud) -{ -	/* Translate from baud into divisor in terms of SCLK.  The -	 * weird multiplication is to make sure we over sample just -	 * a little rather than under sample the incoming signals. -	 */ -	uint16_t divisor = (uart_sclk() + (baud * 8)) / (baud * 16) - -			ANOMALY_05000230; -  	/* Set DLAB in LCR to Access DLL and DLH */  	ACCESS_LATCH();  	SSYNC(); @@ -305,6 +281,24 @@ static inline void serial_early_set_baud(uint32_t uart_base, uint32_t baud)  }  __attribute__((always_inline)) +static inline void serial_early_set_baud(uint32_t uart_base, uint32_t baud) +{ +	/* Translate from baud into divisor in terms of SCLK.  The +	 * weird multiplication is to make sure we over sample just +	 * a little rather than under sample the incoming signals. +	 */ +#if CONFIG_BFIN_BOOT_MODE == BFIN_BOOT_BYPASS +	uint16_t divisor = (early_get_uart_clk() + baud * 8) / (baud * 16) +			- ANOMALY_05000230; +#else +	uint16_t divisor = early_division(early_get_uart_clk() + (baud * 8), +			baud * 16) - ANOMALY_05000230; +#endif + +	serial_set_divisor(uart_base, divisor); +} + +__attribute__((always_inline))  static inline void serial_early_put_div(uint16_t divisor)  {  	uint32_t uart_base = UART_BASE; diff --git a/arch/blackfin/cpu/serial4.h b/arch/blackfin/include/asm/serial4.h index 887845c18..65483960b 100644 --- a/arch/blackfin/cpu/serial4.h +++ b/arch/blackfin/include/asm/serial4.h @@ -15,6 +15,8 @@  #ifndef __ASSEMBLY__ +#include <asm/clock.h> +  #define MMR_UART(n) _PASTE_UART(n, UART, REVID)  #define UART_BASE MMR_UART(CONFIG_UART_CONSOLE) @@ -84,20 +86,6 @@ static inline void serial_early_do_portmux(void)  }  __attribute__((always_inline)) -static inline uint32_t uart_sclk(void) -{ -#if defined(BFIN_IN_INITCODE) || defined(CONFIG_DEBUG_EARLY_SERIAL) -	/* We cannot use get_sclk() early on as it uses caches in -	 * external memory -	 */ -	return CONFIG_CLKIN_HZ * CONFIG_VCO_MULT / CONFIG_SCLK_DIV / -		CONFIG_SCLK0_DIV; -#else -	return get_sclk0(); -#endif -} - -__attribute__((always_inline))  static inline int uart_init(uint32_t uart_base)  {  	/* always enable UART to 8-bit mode */ @@ -127,19 +115,20 @@ static inline int serial_early_uninit(uint32_t uart_base)  }  __attribute__((always_inline)) -static inline int serial_early_enabled(uint32_t uart_base) +static inline void serial_set_divisor(uint32_t uart_base, uint16_t divisor)  { -	return bfin_read(&pUART->control) & UEN; +	/* Program the divisor to get the baud rate we want */ +	bfin_write(&pUART->clock, divisor); +	SSYNC();  }  __attribute__((always_inline))  static inline void serial_early_set_baud(uint32_t uart_base, uint32_t baud)  { -	uint32_t divisor = uart_sclk() / (baud * 16); +	uint16_t divisor = early_division(early_get_uart_clk(), baud * 16);  	/* Program the divisor to get the baud rate we want */ -	bfin_write(&pUART->clock, divisor); -	SSYNC(); +	serial_set_divisor(uart_base, divisor);  }  __attribute__((always_inline)) diff --git a/arch/blackfin/include/asm/soft_switch.h b/arch/blackfin/include/asm/soft_switch.h new file mode 100644 index 000000000..ff8e44d8b --- /dev/null +++ b/arch/blackfin/include/asm/soft_switch.h @@ -0,0 +1,18 @@ +/* + * U-boot - main board file + * + * Copyright (c) 2008-2012 Analog Devices Inc. + * + * Licensed under the GPL-2 or later. + */ + +#ifndef __SOFT_SWITCH_H__ +#define __SOFT_SWITCH_H__ + +#define IO_PORT_A              0 +#define IO_PORT_B              1 +#define IO_PORT_INPUT          0 +#define IO_PORT_OUTPUT         1 + +int config_switch_bit(int num, int port, int bit, int dir, uchar value); +#endif diff --git a/arch/blackfin/lib/board.c b/arch/blackfin/lib/board.c index ccea3b9fb..f1d55470e 100644 --- a/arch/blackfin/lib/board.c +++ b/arch/blackfin/lib/board.c @@ -231,6 +231,8 @@ static int global_board_data_init(void)  	bd->bi_sclk = get_sclk();  	bd->bi_memstart = CONFIG_SYS_SDRAM_BASE;  	bd->bi_memsize = CONFIG_SYS_MAX_RAM_SIZE; +	bd->bi_baudrate = (gd->baudrate > 0) +		? simple_strtoul(gd->baudrate, NULL, 10) : CONFIG_BAUDRATE;  	return 0;  } @@ -277,9 +279,9 @@ void board_init_f(ulong bootflag)  	dcache_enable();  #endif -#ifdef CONFIG_WATCHDOG +#ifdef CONFIG_HW_WATCHDOG  	serial_early_puts("Setting up external watchdog\n"); -	watchdog_init(); +	hw_watchdog_init();  #endif  #ifdef DEBUG diff --git a/arch/blackfin/lib/clocks.c b/arch/blackfin/lib/clocks.c index d852f5ebe..97795e11a 100644 --- a/arch/blackfin/lib/clocks.c +++ b/arch/blackfin/lib/clocks.c @@ -7,17 +7,7 @@   */  #include <common.h> -#include <asm/blackfin.h> - -#ifdef PLL_CTL -# include <asm/mach-common/bits/pll.h> -# define pll_is_bypassed() (bfin_read_PLL_STAT() & DF) -#else -# include <asm/mach-common/bits/cgu.h> -# define pll_is_bypassed() (bfin_read_CGU_STAT() & PLLBP) -# define bfin_read_PLL_CTL() bfin_read_CGU_CTL() -# define bfin_read_PLL_DIV() bfin_read_CGU_DIV() -#endif +#include <asm/clock.h>  /* Get the voltage input multiplier */  u_long get_vco(void) diff --git a/arch/blackfin/lib/string.c b/arch/blackfin/lib/string.c index 44d8c6d90..5b7ac0b91 100644 --- a/arch/blackfin/lib/string.c +++ b/arch/blackfin/lib/string.c @@ -128,10 +128,12 @@ static void dma_calc_size(unsigned long ldst, unsigned long lsrc, size_t count,  	unsigned long limit;  #ifdef MSIZE -	limit = 6; +	/* The max memory DMA memory transfer size is 32 bytes. */ +	limit = 5;  	*dshift = MSIZE_P;  #else -	limit = 3; +	/* The max memory DMA memory transfer size is 4 bytes. */ +	limit = 2;  	*dshift = WDSIZE_P;  #endif @@ -170,7 +172,8 @@ void dma_memcpy_nocache(void *dst, const void *src, size_t count)  	mod = 1 << bpos;  #ifdef PSIZE -	dsize |= min(3, bpos) << PSIZE_P; +	/* The max memory DMA peripheral transfer size is 4 bytes. */ +	dsize |= min(2, bpos) << PSIZE_P;  #endif  	/* Copy sram functions from sdram to sram */ |