diff --git a/bsps/m68k/csb360/README.md b/bsps/m68k/csb360/README.md deleted file mode 100644 index b1d161e894..0000000000 --- a/bsps/m68k/csb360/README.md +++ /dev/null @@ -1,54 +0,0 @@ -CSB360 -====== -Copyright (C) 2004 by Cogent Computer Systems -Author: Jay Monkman - - -``` -BSP NAME: csb360 -BOARD: Cogent CSB360 -BUS: none -CPU FAMILY: Motorola ColdFire MCF5272 -COPROCESSORS: none -MODE: not applicable -DEBUG MONITOR: none (Hardware provides BDM) -``` - - -PERIPHERALS ------------ -``` -TIMERS: - RESOLUTION: -SERIAL PORTS: -REAL-TIME CLOCK: -NVRAM: -DMA: -VIDEO: -SCSI: -NETWORKING: -I2C BUS: -``` - - -DRIVER INFORMATION ------------------- -``` -CLOCK DRIVER: -IOSUPP DRIVER: -SHMSUPP: -TIMER DRIVER: -I2C DRIVER: -``` - - -STDIO ------ -``` -PORT: -ELECTRICAL: -BAUD: -BITS PER CHARACTER: -PARITY: -STOP BITS: -``` diff --git a/bsps/m68k/csb360/config/csb360.cfg b/bsps/m68k/csb360/config/csb360.cfg deleted file mode 100644 index 8694aacec7..0000000000 --- a/bsps/m68k/csb360/config/csb360.cfg +++ /dev/null @@ -1,19 +0,0 @@ -# -# Config file for a Cogent CSB360 -# -# Author: Jay Monkman -# - -RTEMS_CPU=m68k - -include $(RTEMS_ROOT)/make/custom/default.cfg - -# This contains the compiler options necessary to select the CPU model -# and (hopefully) optimize for it. -CPU_CFLAGS = -mcpu=5272 - -# optimize flag: typically -O2 -CFLAGS_OPTIMIZE_V = -O2 -g -fomit-frame-pointer -CFLAGS_OPTIMIZE_V += -ffunction-sections -fdata-sections - -LDFLAGS = -Wl,--gc-sections diff --git a/bsps/m68k/csb360/console/console-io.c b/bsps/m68k/csb360/console/console-io.c deleted file mode 100644 index 1cd11b8697..0000000000 --- a/bsps/m68k/csb360/console/console-io.c +++ /dev/null @@ -1,116 +0,0 @@ -/* SPDX-License-Identifier: BSD-2-Clause */ - -/* - * This file contains the hardware specific portions of the TTY driver - * for the serial ports on the mcf5272 - */ - -/* - * COPYRIGHT (c) 1989-2000. - * On-Line Applications Research Corporation (OAR). - * - * 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. - * - * 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. - */ - -#include -#include -#include -#include - -volatile int g_cnt = 0; - -/* - * console_initialize_hardware - * - * This routine initializes the console hardware. - * - */ - -void console_initialize_hardware(void) -{ -} - - -/* - * console_outbyte_polled - * - * This routine transmits a character using polling. - */ - -void console_outbyte_polled( - int port, - char ch -) -{ - uart_regs_t *uart; - int i; - if (port == 0) { - uart = g_uart0_regs; - } else { - uart = g_uart1_regs; - } - - /* wait for the fifo to make room */ -/* while ((uart->usr & MCF5272_USR_TXRDY) == 0) { */ - while ((uart->ucsr & MCF5272_USR_TXRDY) == 0) { - continue; - } - - uart->udata = ch; - for (i = 0; i < 1000; i++) g_cnt++; -} - -/* - * console_inbyte_nonblocking - * - * This routine polls for a character. - */ - -int console_inbyte_nonblocking( - int port -) -{ - uart_regs_t *uart; - unsigned char c; - - if (port == 0) { - uart = g_uart0_regs; - } else { - uart = g_uart1_regs; - } - -/* if (uart->usr & MCF5272_USR_RXRDY) { */ - if (uart->ucsr & MCF5272_USR_RXRDY) { - c = (char)uart->udata; - return c; - } else { - return -1; - } -} - -#include - -static void mcf5272_output_char(char c) { console_outbyte_polled( 0, c ); } - -BSP_output_char_function_type BSP_output_char = mcf5272_output_char; -BSP_polling_getchar_function_type BSP_poll_char = NULL; - diff --git a/bsps/m68k/csb360/dev/ckinit.c b/bsps/m68k/csb360/dev/ckinit.c deleted file mode 100644 index ef0e891cf2..0000000000 --- a/bsps/m68k/csb360/dev/ckinit.c +++ /dev/null @@ -1,118 +0,0 @@ -/* - * Clock Driver for MCF5272 CPU - * - * This driver initailizes timer1 on the MCF5272 as the - * main system clock - */ - -/* - * Copyright 2004 Cogent Computer Systems - * Author: Jay Monkman - * - * Based on MCF5206 clock driver by - * Victor V. Vengerov - * - * Based on work: - * David Fiddes, D.J@fiddes.surfaid.org - * http://www.calm.hw.ac.uk/davidf/coldfire/ - * - * COPYRIGHT (c) 1989-1998. - * On-Line Applications Research Corporation (OAR). - * - * The license and distribution terms for this file may be - * found in the file LICENSE in this distribution or at - * http://www.rtems.org/license/LICENSE. - */ - -#include -#include -#include -#include -#include - -/* - * Clock_driver_ticks is a monotonically increasing counter of the - * number of clock ticks since the driver was initialized. - */ -volatile uint32_t Clock_driver_ticks; - -rtems_isr (*rtems_clock_hook)(rtems_vector_number) = NULL; - -static rtems_isr -Clock_isr (rtems_vector_number vector) -{ - /* Clear pending interrupt... */ - g_timer_regs->ter1 = MCF5272_TER_REF | MCF5272_TER_CAP; - - /* Announce the clock tick */ - Clock_driver_ticks++; - rtems_clock_tick(); - if (rtems_clock_hook != NULL) { - rtems_clock_hook(vector); - } -} - -static void -Clock_exit(void) -{ - uint32_t icr; - - /* disable all timer1 interrupts */ - icr = g_intctrl_regs->icr1; - icr = icr & ~(MCF5272_ICR1_TMR1_MASK | MCF5272_ICR1_TMR1_PI); - icr |= (MCF5272_ICR1_TMR1_IPL(0) | MCF5272_ICR1_TMR1_PI); - g_intctrl_regs->icr1 = icr; - - /* reset timer1 */ - g_timer_regs->tmr1 = MCF5272_TMR_CLK_STOP; - - /* clear pending */ - g_timer_regs->ter1 = MCF5272_TER_REF | MCF5272_TER_CAP; -} - -static void -Install_clock(rtems_isr_entry clock_isr) -{ - uint32_t icr; - - Clock_driver_ticks = 0; - - /* Register the interrupt handler */ - set_vector(clock_isr, BSP_INTVEC_TMR1, 1); - - /* Reset timer 1 */ - g_timer_regs->tmr1 = MCF5272_TMR_RST; - g_timer_regs->tmr1 = MCF5272_TMR_CLK_STOP; - g_timer_regs->tmr1 = MCF5272_TMR_RST; - g_timer_regs->tcn1 = 0; /* reset counter */ - g_timer_regs->ter1 = MCF5272_TER_REF | MCF5272_TER_CAP; - - /* Set Timer 1 prescaler so that it counts in microseconds */ - g_timer_regs->tmr1 = ( - ((((BSP_SYSTEM_FREQUENCY / 1000000) - 1) << MCF5272_TMR_PS_SHIFT) | - MCF5272_TMR_CE_DISABLE | - MCF5272_TMR_ORI | - MCF5272_TMR_FRR | - MCF5272_TMR_CLK_MSTR | - MCF5272_TMR_RST)); - - /* Set the timer timeout value from the BSP config */ - g_timer_regs->trr1 = rtems_configuration_get_microseconds_per_tick() - 1; - - /* Feed system frequency to the timer */ - g_timer_regs->tmr1 |= MCF5272_TMR_CLK_MSTR; - - /* Configure timer1 interrupts */ - icr = g_intctrl_regs->icr1; - icr = icr & ~(MCF5272_ICR1_TMR1_MASK | MCF5272_ICR1_TMR1_PI); - icr |= (MCF5272_ICR1_TMR1_IPL(BSP_INTLVL_TMR1) | MCF5272_ICR1_TMR1_PI); - g_intctrl_regs->icr1 = icr; - - /* Register the driver exit procedure so we can shutdown */ - atexit(Clock_exit); -} - -void _Clock_Initialize( void ) -{ - Install_clock (Clock_isr); -} diff --git a/bsps/m68k/csb360/dev/timer.c b/bsps/m68k/csb360/dev/timer.c deleted file mode 100644 index 812310fbea..0000000000 --- a/bsps/m68k/csb360/dev/timer.c +++ /dev/null @@ -1,159 +0,0 @@ -/** - * @file - * - * This module initializes TIMER 2 for on the MCF5272 for benchmarks. - */ - -/* - * Copyright (C) 2000 OKTET Ltd., St.-Petersburg, Russia - * Author: Victor V. Vengerov - * - * Based on work: - * Author: - * David Fiddes, D.J@fiddes.surfaid.org - * http://www.calm.hw.ac.uk/davidf/coldfire/ - * - * COPYRIGHT (c) 1989-1998. - * On-Line Applications Research Corporation (OAR). - * - * The license and distribution terms for this file may be - * found in the file LICENSE in this distribution or at - * http://www.rtems.org/license/LICENSE. - */ - -#include -#include -#include -#include - -#define TRR2_VAL 65530 - -uint32_t Timer_interrupts; - -bool benchmark_timer_find_average_overhead; - -/* External assembler interrupt handler routine */ -extern rtems_isr timerisr(rtems_vector_number vector); - - -/* benchmark_timer_initialize -- - * Initialize timer 2 for accurate time measurement. - * - * PARAMETERS: - * none - * - * RETURNS: - * none - */ -void -benchmark_timer_initialize(void) -{ - uint32_t icr; - /* Catch timer2 interrupts */ - set_vector(timerisr, BSP_INTVEC_TMR2, 0); - - /* Reset Timer */ - g_timer_regs->tmr2 = MCF5272_TMR_RST; - g_timer_regs->tmr2 = MCF5272_TMR_CLK_STOP; - g_timer_regs->tmr2 = MCF5272_TMR_RST; - g_timer_regs->tcn2 = 0; /* reset counter */ - Timer_interrupts = 0; /* Clear timer ISR counter */ - g_timer_regs->ter2 = MCF5272_TER_REF | MCF5272_TER_CAP; - g_timer_regs->trr2 = TRR2_VAL -1 ; - - - /* Set Timer 2 prescaler so that it counts in microseconds */ - g_timer_regs->tmr2 = ( - (((BSP_SYSTEM_FREQUENCY / 1000000) - 1) << MCF5272_TMR_PS_SHIFT) | - MCF5272_TMR_CE_DISABLE | - MCF5272_TMR_ORI | - MCF5272_TMR_FRR | - MCF5272_TMR_CLK_MSTR | - MCF5272_TMR_RST); - - /* Initialize interrupts for timer2 */ - icr = g_intctrl_regs->icr1; - icr = icr & ~(MCF5272_ICR1_TMR2_MASK | MCF5272_ICR1_TMR2_PI); - icr |= (MCF5272_ICR1_TMR2_IPL(BSP_INTLVL_TMR2) | MCF5272_ICR1_TMR2_PI); - g_intctrl_regs->icr1 = icr; - -} - -/* - * The following controls the behavior of benchmark_timer_read(). - * - * FIND_AVG_OVERHEAD * instructs the routine to return the "raw" count. - * - * AVG_OVEREHAD is the overhead for starting and stopping the timer. It - * is usually deducted from the number returned. - * - * LEAST_VALID is the lowest number this routine should trust. Numbers - * below this are "noise" and zero is returned. - */ - -#define AVG_OVERHEAD 0 /* It typically takes 2.0 microseconds */ - /* (Y countdowns) to start/stop the timer. */ - /* This value is in microseconds. */ -#define LEAST_VALID 1 /* Don't trust a clicks value lower than this */ - -/* benchmark_timer_read -- - * Read timer value in microsecond units since timer start. - * - * PARAMETERS: - * none - * - * RETURNS: - * number of microseconds since timer has been started - */ -benchmark_timer_t -benchmark_timer_read( void ) -{ - uint16_t clicks; - uint32_t total; - - /* - * Read the timer and see how many clicks it has been since counter - * rolled over. - */ - clicks = g_timer_regs->tcn2; - - /* Stop Timer... */ - g_timer_regs->tmr2 = MCF5272_TMR_CLK_STOP | MCF5272_TMR_RST; - - /* - * Total is calculated by taking into account the number of timer - * overflow interrupts since the timer was initialized and clicks - * since the last interrupts. - */ - - total = (Timer_interrupts * TRR2_VAL) + clicks; - - if ( benchmark_timer_find_average_overhead == 1 ) - return total; /* in XXX microsecond units */ - - if ( total < LEAST_VALID ) - return 0; /* below timer resolution */ - - /* - * Return the count in microseconds - */ - return (total - AVG_OVERHEAD); -} - -/* benchmark_timer_disable_subtracting_average_overhead -- - * This routine is invoked by the "Check Timer" (tmck) test in the - * RTEMS Timing Test Suite. It makes the benchmark_timer_read routine not - * subtract the overhead required to initialize and read the benchmark - * timer. - * - * PARAMETERS: - * find_flag - bool flag, true if overhead must not be subtracted. - * - * RETURNS: - * none - */ -void -benchmark_timer_disable_subtracting_average_overhead(bool find_flag) -{ - benchmark_timer_find_average_overhead = find_flag; -} diff --git a/bsps/m68k/csb360/dev/timerisr.S b/bsps/m68k/csb360/dev/timerisr.S deleted file mode 100644 index b9c28921c4..0000000000 --- a/bsps/m68k/csb360/dev/timerisr.S +++ /dev/null @@ -1,46 +0,0 @@ -/** - * @file - * @brief Handle MCF5272 TIMER2 interrupts. - * - * All code in this routine is pure overhead which can perturb the - * accuracy of RTEMS' timing test suite. - * - * See also: benchmark_timer_read() - * - * To reduce overhead this is best to be the "rawest" hardware interupt - * handler you can write. This should be the only interrupt which can - * occur during the measured time period. - * - * An external counter, Timer_interrupts, is incremented. - */ - -/* - * Copyright (C) 2000 OKTET Ltd., St.-Petersburg, Russia - * Author: Victor V. Vengerov - * - * This file based on work: - * Author: - * David Fiddes, D.J@fiddes.surfaid.org - * http://www.calm.hw.ac.uk/davidf/coldfire/ - * - * COPYRIGHT (c) 1989-1998. - * On-Line Applications Research Corporation (OAR). - * - * The license and distribution terms for this file may be - * found in the file LICENSE in this distribution or at - * http://www.rtems.org/license/LICENSE. - */ - -#include -#include - -BEGIN_CODE - PUBLIC(timerisr) -SYM(timerisr): - move.l a0, a7@- - move.b # (MCF5272_TER_REF + MCF5272_TER_CAP), (a0) - addq.l #1,SYM(Timer_interrupts) | increment timer value - move.l a7@+, a0 - rte -END_CODE -END diff --git a/bsps/m68k/csb360/include/bsp.h b/bsps/m68k/csb360/include/bsp.h deleted file mode 100644 index 84ad6a7b23..0000000000 --- a/bsps/m68k/csb360/include/bsp.h +++ /dev/null @@ -1,192 +0,0 @@ -/** - * @file - * - * @ingroup RTEMSBSPsM68kCSB3602 - * - * @brief Global BSP definitions. - */ - -/* - * Board Support Package for CSB360 evaluation board - * BSP definitions - * - * Copyright 2004 Cogent Computer Systems - * Author: Jay Monkman - * - * Derived from mcf5206elite BSP: - * Copyright (C) 2000 OKTET Ltd., St.-Petersburg, Russia - * Author: Victor V. Vengerov - * - * The license and distribution terms for this file may be - * found in the file LICENSE in this distribution or at - * - * http://www.rtems.org/license/LICENSE. - */ - -#ifndef LIBBSP_M68K_CSB360_BSP_H -#define LIBBSP_M68K_CSB360_BSP_H - -/** - * @defgroup RTEMSBSPsM68kCSB3602 CSB3602 - * - * @ingroup RTEMSBSPsM68k - * - * @brief CSB3602 Board Support Package. - * - * @{ - */ - -#include - -/*** Board resources allocation ***/ -#define BSP_MEM_ADDR_SRAM 0x20000000 -#define BSP_MEM_SIZE_SRAM 4096 - -/* Location and size of sdram. Note this includes space used by - * umon. - */ -#define BSP_MEM_ADDR_SDRAM 0x00000000 -#define BSP_MEM_MASK_SDRAM 0x01ffffff -#define BSP_MEM_SIZE_SDRAM (32 * 1024 * 1024) - -/* Address to put SIM Modules */ -#define BSP_MBAR 0x10000000 - -/* Address to put SRAM */ -#define BSP_RAMBAR BSP_MEM_ADDR_SRAM - -/* Interrupt Vectors */ -#define BSP_INTVEC_INT1 65 -#define BSP_INTVEC_INT2 66 -#define BSP_INTVEC_INT3 67 -#define BSP_INTVEC_INT4 68 -#define BSP_INTVEC_TMR0 69 -#define BSP_INTVEC_TMR1 70 -#define BSP_INTVEC_TMR2 71 -#define BSP_INTVEC_TMR3 72 -#define BSP_INTVEC_UART1 73 -#define BSP_INTVEC_UART2 74 -#define BSP_INTVEC_PLIP 75 -#define BSP_INTVEC_PLIA 76 -#define BSP_INTVEC_USB0 77 -#define BSP_INTVEC_USB1 78 -#define BSP_INTVEC_USB2 79 -#define BSP_INTVEC_USB3 80 -#define BSP_INTVEC_USB4 81 -#define BSP_INTVEC_USB5 82 -#define BSP_INTVEC_USB6 83 -#define BSP_INTVEC_USB7 84 -#define BSP_INTVEC_DMA 85 -#define BSP_INTVEC_ERX 86 -#define BSP_INTVEC_ETX 87 -#define BSP_INTVEC_ENTC 88 -#define BSP_INTVEC_QSPI 89 -#define BSP_INTVEC_INT5 90 -#define BSP_INTVEC_INT6 91 -#define BSP_INTVEC_SWTO 92 - -#define BSP_INTLVL_INT1 1 -#define BSP_INTLVL_INT2 1 -#define BSP_INTLVL_INT3 1 -#define BSP_INTLVL_INT4 1 -#define BSP_INTLVL_TMR0 1 -#define BSP_INTLVL_TMR1 1 -#define BSP_INTLVL_TMR2 1 -#define BSP_INTLVL_TMR3 1 -#define BSP_INTLVL_UART1 1 -#define BSP_INTLVL_UART2 1 -#define BSP_INTLVL_PLIP 1 -#define BSP_INTLVL_PLIA 1 -#define BSP_INTLVL_USB0 1 -#define BSP_INTLVL_USB1 1 -#define BSP_INTLVL_USB2 1 -#define BSP_INTLVL_USB3 1 -#define BSP_INTLVL_USB4 1 -#define BSP_INTLVL_USB5 1 -#define BSP_INTLVL_USB6 1 -#define BSP_INTLVL_USB7 1 -#define BSP_INTLVL_DMA 1 -#define BSP_INTLVL_ERX 1 -#define BSP_INTLVL_ETX 1 -#define BSP_INTLVL_ENTC 1 -#define BSP_INTLVL_QSPI 1 -#define BSP_INTLVL_INT5 1 -#define BSP_INTLVL_INT6 1 -#define BSP_INTLVL_SWTO 1 - - - -#ifndef ASM - -#include -#include -#include - -#ifdef __cplusplus -extern "C" { -#endif - -struct rtems_bsdnet_ifconfig; -extern int rtems_enet_driver_attach (struct rtems_bsdnet_ifconfig *config); -#define RTEMS_BSP_NETWORK_DRIVER_NAME "eth0" -#define RTEMS_BSP_NETWORK_DRIVER_ATTACH rtems_enet_driver_attach - -/* System frequency */ -#define BSP_SYSTEM_FREQUENCY (66 * 1000 * 1000) - -/* - * Simple spin delay in microsecond units for device drivers. - * This is very dependent on the clock speed of the target. - */ - -#define rtems_bsp_delay( microseconds ) \ - { register uint32_t _delay=(microseconds); \ - register uint32_t _tmp=123; \ - __asm__ volatile( "0: \ - nbcd %0 ; \ - nbcd %0 ; \ - dbf %1,0b" \ - : "=d" (_tmp), "=d" (_delay) \ - : "0" (_tmp), "1" (_delay) ); \ - } - -/* - * Real-Time Clock Driver Table Entry - * NOTE: put this entry to the device driver table AFTER I2C bus driver! - */ -#define RTC_DRIVER_TABLE_ENTRY \ - { rtc_initialize, NULL, NULL, NULL, NULL, NULL } -extern rtems_device_driver rtc_initialize( - rtems_device_major_number major, - rtems_device_minor_number minor, - void *arg -); - -/* miscellaneous stuff assumed to exist */ - -extern rtems_isr_entry M68Kvec[]; /* vector table address */ - -extern rtems_isr (*rtems_clock_hook)(rtems_vector_number); - -/* functions */ - -rtems_isr_entry set_vector( - rtems_isr_entry handler, - rtems_vector_number vector, - int type -); - -/* - * Prototypes for BSP methods which cross file boundaries - */ -void init5272(void); - -#ifdef __cplusplus -} -#endif - -#endif /* ASM */ - -/** @} */ - -#endif diff --git a/bsps/m68k/csb360/include/bsp/irq.h b/bsps/m68k/csb360/include/bsp/irq.h deleted file mode 100644 index 8a97d7a1b0..0000000000 --- a/bsps/m68k/csb360/include/bsp/irq.h +++ /dev/null @@ -1 +0,0 @@ -#include diff --git a/bsps/m68k/csb360/include/tm27.h b/bsps/m68k/csb360/include/tm27.h deleted file mode 100644 index 27b96a5370..0000000000 --- a/bsps/m68k/csb360/include/tm27.h +++ /dev/null @@ -1,41 +0,0 @@ -/** - * @file - * - * @ingroup m68k_csb360 - * - * @brief Time Test 27 routines. - */ - -/* - * tm27.h - * - * The license and distribution terms for this file may be - * found in the file LICENSE in this distribution or at - * http://www.rtems.org/license/LICENSE. - */ - -#ifndef _RTEMS_TMTEST27 -#error "This is an RTEMS internal file you must not include directly." -#endif - -#ifndef __tm27_h -#define __tm27_h - -/* - * Stuff for Time Test 27 - * Don't bother with hardware -- just use a software-interrupt - */ - -#define MUST_WAIT_FOR_INTERRUPT 0 - -#define TM27_USE_VECTOR_HANDLER - -#define Install_tm27_vector( handler ) set_vector( (handler), 34, 1 ) - -#define Cause_tm27_intr() asm volatile ("trap #2"); - -#define Clear_tm27_intr() /* empty */ - -#define Lower_tm27_intr() /* empty */ - -#endif diff --git a/bsps/m68k/csb360/start/idle-mcf5272.c b/bsps/m68k/csb360/start/idle-mcf5272.c deleted file mode 100644 index ac52b9b9ef..0000000000 --- a/bsps/m68k/csb360/start/idle-mcf5272.c +++ /dev/null @@ -1,45 +0,0 @@ -/* SPDX-License-Identifier: BSD-2-Clause */ - -/* - * Motorola MC68xxx Dependent Idle Body Source - * - * This kernel routine is the idle thread. The idle thread runs any time - * no other thread is ready to run. This thread loops forever with - * interrupts enabled. - */ - -/* - * COPYRIGHT (c) 1989-2002. - * On-Line Applications Research Corporation (OAR). - * - * 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. - * - * 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. - */ - -#include - -void *_CPU_Thread_Idle_body( uintptr_t ignored ) -{ - for( ; ; ) { - __asm__ volatile( "nop" ); - __asm__ volatile( "nop" ); - } -} diff --git a/bsps/m68k/csb360/start/init5272.c b/bsps/m68k/csb360/start/init5272.c deleted file mode 100644 index 267fd551b4..0000000000 --- a/bsps/m68k/csb360/start/init5272.c +++ /dev/null @@ -1,146 +0,0 @@ -/* - * CSB360 hardware startup routines - * - * This is where the real hardware setup is done. A minimal stack - * has been provided by the start.S code. No normal C or RTEMS - * functions can be called from here. - * - * This initialization code based on hardware settings of dBUG - * monitor. This must be changed if you like to run it immediately - * after reset. - */ - -/* - * Copyright (C) 2000 OKTET Ltd., St.-Petersburg, Russia - * Author: Victor V. Vengerov - * - * Based on work: - * Author: - * David Fiddes, D.J@fiddes.surfaid.org - * http://www.calm.hw.ac.uk/davidf/coldfire/ - * - * COPYRIGHT (c) 1989-1998. - * On-Line Applications Research Corporation (OAR). - * - * The license and distribution terms for this file may be - * found in the file LICENSE in this distribution or at - * http://www.rtems.org/license/LICENSE. - */ - -#include -#include - -/* externs */ -extern void clear_bss(void); -extern void start_csb360(void); -extern void INTERRUPT_VECTOR(void); - -/* Set the pointers to the modules */ -sim_regs_t *g_sim_regs = (void *) MCF5272_SIM_BASE(BSP_MBAR); -intctrl_regs_t *g_intctrl_regs = (void *) MCF5272_INT_BASE(BSP_MBAR); -chipsel_regs_t *g_chipsel_regs = (void *) MCF5272_CS_BASE(BSP_MBAR); -gpio_regs_t *g_gpio_regs = (void *) MCF5272_GPIO_BASE(BSP_MBAR); -qspi_regs_t *g_qspi_regs = (void *) MCF5272_QSPI_BASE(BSP_MBAR); -pwm_regs_t *g_pwm_regs = (void *) MCF5272_PWM_BASE(BSP_MBAR); -dma_regs_t *g_dma_regs = (void *) MCF5272_DMAC_BASE(BSP_MBAR); -uart_regs_t *g_uart0_regs = (void *) MCF5272_UART0_BASE(BSP_MBAR); -uart_regs_t *g_uart1_regs = (void *) MCF5272_UART1_BASE(BSP_MBAR); -timer_regs_t *g_timer_regs = (void *) MCF5272_TIMER_BASE(BSP_MBAR); -plic_regs_t *g_plic_regs = (void *) MCF5272_PLIC_BASE(BSP_MBAR); -enet_regs_t *g_enet_regs = (void *) MCF5272_ENET_BASE(BSP_MBAR); -usb_regs_t *g_usb_regs = (void *) MCF5272_USB_BASE(BSP_MBAR); - -#define m68k_set_srambar( _rambar0 ) \ - __asm__ volatile ( "movec %0,%%rambar0\n\t" \ - "nop\n\t" \ - : : "d" (_rambar0) ) - -#define m68k_set_mbar( _mbar ) \ - __asm__ volatile ( "movec %0,%%mbar\n\t" \ - "nop\n\t" \ - : : "d" (_mbar) ) - -#define mcf5272_enable_cache() \ - m68k_set_cacr( MCF5272_CACR_CENB ) - - -#define mcf5272_disable_cache() \ - __asm__ volatile ( "nop\n\t" \ - "movec %0,%%cacr\n\t" \ - "nop\n\t" \ - "movec %0,%%cacr\n\t" \ - "nop\n\t" \ - : : "d" (MCF5272_CACR_CINV) ) - -/* - * Initialize MCF5272 on-chip modules - */ -void init5272(void) -{ - /* Invalidate the cache - WARNING: It won't complete for 64 clocks */ - m68k_set_cacr(MCF5272_CACR_CINV); - - /* Set Module Base Address register */ - m68k_set_mbar((BSP_MBAR & MCF5272_MBAR_BA) | MCF5272_MBAR_V); - - /* Set RAM Base Address register */ - m68k_set_srambar((BSP_RAMBAR & MCF5272_RAMBAR_BA) | MCF5272_RAMBAR_V); - - /* Set System Control Register: - * Enet has highest priority, 16384 bus cycles before timeout - */ - g_sim_regs->scr = (MCF5272_SCR_HWR_16384); - - /* System Protection Register: - * Enable Hardware watchdog timer. - */ - g_sim_regs->spr = MCF5272_SPR_HWTEN; - - /* Clear and mask all interrupts */ - g_intctrl_regs->icr1 = 0x88888888; - g_intctrl_regs->icr2 = 0x88888888; - g_intctrl_regs->icr3 = 0x88888888; - g_intctrl_regs->icr4 = 0x88880000; - - /* Copy the interrupt vector table to SRAM */ - { - uint32_t *inttab = (uint32_t *)&INTERRUPT_VECTOR; - uint32_t *intvec = (uint32_t *)BSP_RAMBAR; - register int i; - for (i = 0; i < 256; i++) { - *(intvec++) = *(inttab++); - } - } - m68k_set_vbr(BSP_RAMBAR); - - - /* - * Setup ACRs so that if cache turned on, periphal accesses - * are not messed up. (Non-cacheable, serialized) - */ - m68k_set_acr0(MCF5272_ACR_BASE(BSP_MEM_ADDR_SDRAM) | - MCF5272_ACR_MASK(BSP_MEM_MASK_SDRAM) | - MCF5272_ACR_EN | - MCF5272_ACR_SM_ANY); - -/* - m68k_set_acr1 (MCF5206E_ACR_BASE(BSP_MEM_ADDR_FLASH) | - MCF5206E_ACR_MASK(BSP_MEM_MASK_FLASH) | - MCF5206E_ACR_EN | - MCF5206E_ACR_SM_ANY); -*/ - - /* Enable the caches */ - m68k_set_cacr(MCF5272_CACR_CENB | - MCF5272_CACR_DCM); /* Default is not cached */ - -/* - * Copy data, clear BSS, switch stacks and call boot_card() - */ -/* -CopyDataClearBSSAndStart(BSP_MEM_SIZE_ESRAM - 0x400); -*/ - clear_bss(); - start_csb360(); - -} diff --git a/bsps/m68k/csb360/start/linkcmds b/bsps/m68k/csb360/start/linkcmds deleted file mode 100644 index 84e2da9daf..0000000000 --- a/bsps/m68k/csb360/start/linkcmds +++ /dev/null @@ -1,182 +0,0 @@ -/* - * This file contains GNU linker directives for the Cogent - * CSB360 development board. - * - * Copyright (C) 2004 Cogent Computer Systems - * Author: Jay Monkman - */ - -/* - * Declare size of heap. - * A heap size of 0 means "Use all available memory for the heap". - * Initial stack located in on-chip SRAM and not declared there. - */ -HeapSize = DEFINED(HeapSize) ? HeapSize : 0x0; -RamBase = DEFINED(RamBase) ? RamBase : 0x00100000; -RamSize = DEFINED(RamSize) ? RamSize : 31M; -RamEnd = RamBase + RamSize; - -/* This is needed for _CPU_ISR_install_vector - -* WARNING: it MUST match BSP_RAMBAR !!!!!!!!!!! */ -_VBR = 0x20000000; - -ENTRY(start) -STARTUP(start.o) - -/* - * Setup the memory map of the CSB360 board - * - * The "ram" section is placed in RAM after the space used by umon. - * - */ -MEMORY -{ - ram : ORIGIN = 0x00100000, LENGTH = 31M -} - -SECTIONS -{ - - /* - * Text, data and bss segments - */ - .text : - { - RamBase = .; - RamBase = .; - CREATE_OBJECT_SYMBOLS - *(.text*) - - /* - * C++ constructors/destructors - */ - *(.gnu.linkonce.t.*) - - /* - * Initialization and finalization code. - */ - . = ALIGN (16); - PROVIDE (_init = .); - *crti.o(.init) - *(.init) - *crtn.o(.init) - . = ALIGN (16); - PROVIDE (_fini = .); - *crti.o(.fini) - *(.fini) - *crtn.o(.fini) - - /* - * Special FreeBSD sysctl sections. - */ - . = ALIGN (16); - __start_set_sysctl_set = .; - *(set_sysctl_*); - __stop_set_sysctl_set = ABSOLUTE(.); - *(set_domain_*); - *(set_pseudo_*); - - /* - * C++ constructors/destructors - */ - . = ALIGN (16); - *crtbegin.o(.ctors) - *(.ctors) - *crtend.o(.ctors) - *crtbegin.o(.dtors) - *(.dtors) - *crtend.o(.dtors) - - /* - * Exception frame info - */ - . = ALIGN (16); - *(.eh_frame) - - /* - * Read-only data - */ - . = ALIGN (16); - _rodata_start = .; - *(.rodata*) - KEEP (*(SORT(.rtemsroset.*))) - *(.gnu.linkonce.r*) - - . = ALIGN (16); - PROVIDE (etext = .); - - } > ram - - .tdata : { - _TLS_Data_begin = .; - *(.tdata .tdata.* .gnu.linkonce.td.*) - _TLS_Data_end = .; - } >ram - - .tbss : { - _TLS_BSS_begin = .; - *(.tbss .tbss.* .gnu.linkonce.tb.*) *(.tcommon) - _TLS_BSS_end = .; - } >ram - - _TLS_Data_size = _TLS_Data_end - _TLS_Data_begin; - _TLS_Data_begin = _TLS_Data_size != 0 ? _TLS_Data_begin : _TLS_BSS_begin; - _TLS_Data_end = _TLS_Data_size != 0 ? _TLS_Data_end : _TLS_BSS_begin; - _TLS_BSS_size = _TLS_BSS_end - _TLS_BSS_begin; - _TLS_Size = _TLS_BSS_end - _TLS_Data_begin; - _TLS_Alignment = MAX (ALIGNOF (.tdata), ALIGNOF (.tbss)); - - - .data : - { - copy_start = .; - *(.shdata) - . = ALIGN (0x10); - *(.data*) - KEEP (*(SORT(.rtemsrwset.*))) - . = ALIGN (0x10); - *(.gcc_exc) - *(.gcc_except_table*) - *(.jcr) - . = ALIGN (0x10); - *(.gnu.linkonce.d*) - . = ALIGN (0x10); - _edata = .; - copy_end = .; - } > ram - - .bss : - { - clear_start = . ; - *(.shbss) - *(.dynbss) - *(.bss* .gnu.linkonce.b.*) - *(COMMON) - . = ALIGN(0x10); - _end = .; - - clear_end = .; - } > ram - - .noinit (NOLOAD) : { - *(SORT_BY_NAME (SORT_BY_ALIGNMENT (.noinit*))) - } >ram - - .rtemsstack (NOLOAD) : { - *(SORT(.rtemsstack.*)) - WorkAreaBase = .; - } >ram - - .stab 0 (NOLOAD) : - { - *(.stab) - } - - .stabstr 0 (NOLOAD) : - { - *(.stabstr) - } - - /* Addition to let linker know about custom section for GDB pretty-printing support. */ - .debug_gdb_scripts 0 : { *(.debug_gdb_scripts) } -} diff --git a/bsps/m68k/csb360/start/start.S b/bsps/m68k/csb360/start/start.S deleted file mode 100644 index b90db2276e..0000000000 --- a/bsps/m68k/csb360/start/start.S +++ /dev/null @@ -1,414 +0,0 @@ -/* - * CSB360 startup code - * - * This file contains the entry point for the application. - * The name of this entry point is compiler dependent. - * It jumps to the BSP which is responsible for performing - * all initialization. - */ - -/* - * Copyright (C) 2004 Cogent Computer Systems - * Author: Jay Monkman - * - * Based on start.S from mcf520elite BSP: - * Copyright (C) 2000 OKTET Ltd., St.-Petersburg, Russia - * Author: Victor V. Vengerov - * - * Based on work: - * David Fiddes, D.J@fiddes.surfaid.org - * http://www.calm.hw.ac.uk/davidf/coldfire/ - * - * COPYRIGHT (c) 1989-1998. - * On-Line Applications Research Corporation (OAR). - * - * The license and distribution terms for this file may be - * found in the file LICENSE in this distribution or at - * http://www.rtems.org/license/LICENSE. - */ - -#include -#include - -BEGIN_CODE - -/* Initial stack situated in on-chip static memory */ -#define INITIAL_STACK BSP_MEM_ADDR_SRAM+BSP_MEM_SIZE_SRAM-4 - - PUBLIC (INTERRUPT_VECTOR) -SYM(INTERRUPT_VECTOR): - .long INITIAL_STACK | 00: initial SSP - .long start | 01: Initial PC - .long _unexp_exception | 02: Access Error - .long _unexp_exception | 03: Address Error - .long _unexp_exception | 04: Illegal Instruction - .long _reserved_int | 05: Reserved - .long _reserved_int | 06: Reserved - .long _reserved_int | 07: Reserved - .long _unexp_exception | 08: Priveledge Violation - .long _unexp_exception | 09: Trace - .long _unexp_exception | 0A: Unimplemented A-Line - .long _unexp_exception | 0B: Unimplemented F-Line - .long _unexp_exception | 0C: Debug interrupt - .long _reserved_int | 0D: Reserved - .long _unexp_exception | 0E: Format error - .long _unexp_exception | 0F: Uninitialized interrupt - .long _reserved_int | 10: Reserved - .long _reserved_int | 11: Reserved - .long _reserved_int | 12: Reserved - .long _reserved_int | 13: Reserved - .long _reserved_int | 14: Reserved - .long _reserved_int | 15: Reserved - .long _reserved_int | 16: Reserved - .long _reserved_int | 17: Reserved - .long _spurious_int | 18: Spurious interrupt - .long _avec1_int | 19: Autovector Level 1 - .long _avec2_int | 1A: Autovector Level 2 - .long _avec3_int | 1B: Autovector Level 3 - .long _avec4_int | 1C: Autovector Level 4 - .long _avec5_int | 1D: Autovector Level 5 - .long _avec6_int | 1E: Autovector Level 6 - .long _avec7_int | 1F: Autovector Level 7 - .long _unexp_exception | 20: TRAP #0 - .long _unexp_exception | 21: TRAP #1 - .long _unexp_exception | 22: TRAP #2 - .long _unexp_exception | 23: TRAP #3 - .long _unexp_exception | 24: TRAP #4 - .long _unexp_exception | 25: TRAP #5 - .long _unexp_exception | 26: TRAP #6 - .long _unexp_exception | 27: TRAP #7 - .long _unexp_exception | 28: TRAP #8 - .long _unexp_exception | 29: TRAP #9 - .long _unexp_exception | 2A: TRAP #10 - .long _unexp_exception | 2B: TRAP #11 - .long _unexp_exception | 2C: TRAP #12 - .long _unexp_exception | 2D: TRAP #13 - .long _unexp_exception | 2E: TRAP #14 - .long _unexp_exception | 2F: TRAP #15 - .long _reserved_int | 30: Reserved - .long _reserved_int | 31: Reserved - .long _reserved_int | 32: Reserved - .long _reserved_int | 33: Reserved - .long _reserved_int | 34: Reserved - .long _reserved_int | 35: Reserved - .long _reserved_int | 36: Reserved - .long _reserved_int | 37: Reserved - .long _reserved_int | 38: Reserved - .long _reserved_int | 39: Reserved - .long _reserved_int | 3A: Reserved - .long _reserved_int | 3B: Reserved - .long _reserved_int | 3C: Reserved - .long _reserved_int | 3D: Reserved - .long _reserved_int | 3E: Reserved - .long _reserved_int | 3F: Reserved - - .long _unexp_int | 40-FF: User defined interrupts - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - - .long _unexp_int | 50: - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - - .long _unexp_int | 60: - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - - .long _unexp_int | 70: - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - - .long _unexp_int | 80: - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - - .long _unexp_int | 90: - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - - .long _unexp_int | A0: - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - - .long _unexp_int | B0: - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - - .long _unexp_int | C0: - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - - .long _unexp_int | D0: - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - - .long _unexp_int | E0: - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - - .long _unexp_int | F0: - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - .long _unexp_int - - PUBLIC(start) -SYM(start): - move.w #0x2700,sr | First turn off all interrupts! - - move.l #(BSP_RAMBAR + MCF5272_RAMBAR_V), d0 - movec d0,rambar0 | ...so we have a stack - - move.l #(INITIAL_STACK),sp | Set up stack again (may be we are - | going here from monitor or with - | BDM interface assistance) - - /* - * Remainder of the startup code is handled by C code - */ - jmp SYM(init5272) | Start C code (which never returns) - -/*************************************************************************** - Function : clear_bss - - Description : clear BSS segment - ***************************************************************************/ - PUBLIC (clear_bss) -SYM(clear_bss): - lea clear_start,a0 | Get start of BSS - lea clear_end,a1 | Get end of BSS - clrl d0 | Value to set - bra.s ZEROLOOPTEST | Branch into clear loop -ZEROLOOP: - movel d0,a0@+ | Clear a word -ZEROLOOPTEST: - cmpl a1,a0 | Done? - bcs.s ZEROLOOP | No, skip - - rts - - - - - PUBLIC (start_csb360) -SYM(start_csb360): - /* - * Right : Now we're ready to boot RTEMS - */ - move.l #_ISR_Stack_area_end,sp | Use configuration defined stack - clrl d0 | Pass in null to all boot_card() params - movel d0,a7@- | command line - jsr SYM(boot_card) | Call C boot_card function to startup RTEMS - - - -# Wait forever -_stop: - nop - stop #0x2700 - jmp _stop - -# The following labelled nops is a placeholders for breakpoints -_unexp_exception: - nop - jmp _stop - -_unexp_int: - nop - jmp _stop - -_reserved_int: - nop - jmp _stop - -_spurious_int: - nop - jmp _stop - -_avec1_int: - nop - jmp _unexp_int - -_avec2_int: - nop - jmp _unexp_int - -_avec3_int: - nop - jmp _unexp_int - -_avec4_int: - nop - jmp _unexp_int - -_avec5_int: - nop - jmp _unexp_int - -_avec6_int: - nop - jmp _unexp_int - -_avec7_int: - nop - jmp _unexp_int - - -END_CODE - -END - diff --git a/spec/build/bsps/m68k/csb360/abi.yml b/spec/build/bsps/m68k/csb360/abi.yml deleted file mode 100644 index 50965041fb..0000000000 --- a/spec/build/bsps/m68k/csb360/abi.yml +++ /dev/null @@ -1,18 +0,0 @@ -SPDX-License-Identifier: CC-BY-SA-4.0 OR BSD-2-Clause -actions: -- get-string: null -- split: null -- env-append: null -build-type: option -copyrights: -- Copyright (C) 2020 embedded brains GmbH & Co. KG -default: -- enabled-by: true - value: - - -mcpu=5272 -description: | - ABI flags -enabled-by: true -links: [] -name: ABI_FLAGS -type: build diff --git a/spec/build/bsps/m68k/csb360/bspcsb360.yml b/spec/build/bsps/m68k/csb360/bspcsb360.yml deleted file mode 100644 index 5137090bee..0000000000 --- a/spec/build/bsps/m68k/csb360/bspcsb360.yml +++ /dev/null @@ -1,55 +0,0 @@ -SPDX-License-Identifier: CC-BY-SA-4.0 OR BSD-2-Clause -arch: m68k -bsp: csb360 -build-type: bsp -cflags: [] -copyrights: -- Copyright (C) 2020 embedded brains GmbH & Co. KG -cppflags: [] -enabled-by: true -family: csb360 -includes: [] -install: -- destination: ${BSP_INCLUDEDIR} - source: - - bsps/m68k/csb360/include/bsp.h -- destination: ${BSP_INCLUDEDIR}/bsp - source: - - bsps/m68k/csb360/include/bsp/irq.h -- destination: ${BSP_LIBDIR} - source: - - bsps/m68k/csb360/start/linkcmds -links: -- role: build-dependency - uid: abi -- role: build-dependency - uid: start -- role: build-dependency - uid: ../grp -- role: build-dependency - uid: ../../obj -- role: build-dependency - uid: ../../objirqdflt -- role: build-dependency - uid: ../../objmem -- role: build-dependency - uid: ../../opto2 -- role: build-dependency - uid: ../../bspopts -source: -- bsps/m68k/csb360/console/console-io.c -- bsps/m68k/csb360/dev/ckinit.c -- bsps/m68k/csb360/dev/timer.c -- bsps/m68k/csb360/dev/timerisr.S -- bsps/m68k/csb360/start/idle-mcf5272.c -- bsps/m68k/csb360/start/init5272.c -- bsps/m68k/shared/memProbe.c -- bsps/shared/cache/nocache.c -- bsps/shared/dev/getentropy/getentropy-cpucounter.c -- bsps/shared/dev/serial/console-polled.c -- bsps/shared/start/bspreset-loop.c -- bsps/shared/start/bspstart-empty.c -- bsps/shared/start/gettargethash-default.c -- bsps/shared/start/sbrk.c -- bsps/shared/start/setvec.c -type: build diff --git a/spec/build/bsps/m68k/csb360/start.yml b/spec/build/bsps/m68k/csb360/start.yml deleted file mode 100644 index f181613511..0000000000 --- a/spec/build/bsps/m68k/csb360/start.yml +++ /dev/null @@ -1,14 +0,0 @@ -SPDX-License-Identifier: CC-BY-SA-4.0 OR BSD-2-Clause -asflags: [] -build-type: start-file -copyrights: -- Copyright (C) 2020 embedded brains GmbH & Co. KG -cppflags: [] -enabled-by: true -includes: [] -install-path: ${BSP_LIBDIR} -links: [] -source: -- bsps/m68k/csb360/start/start.S -target: start.o -type: build