diff --git a/FreeRTOS/Demo/CORTEX_A5_SAMA5D3x_Xplained_IAR/AtmelFiles/libboard_sama5d3x-ek/source/board_cstartup_gnu.S b/FreeRTOS/Demo/CORTEX_A5_SAMA5D3x_Xplained_IAR/AtmelFiles/libboard_sama5d3x-ek/source/board_cstartup_gnu.S
deleted file mode 100644
index 590d563b3..000000000
--- a/FreeRTOS/Demo/CORTEX_A5_SAMA5D3x_Xplained_IAR/AtmelFiles/libboard_sama5d3x-ek/source/board_cstartup_gnu.S
+++ /dev/null
@@ -1,218 +0,0 @@
-/* ----------------------------------------------------------------------------
- * SAM Software Package License
- * ----------------------------------------------------------------------------
- * Copyright (c) 2012, Atmel Corporation
- *
- * All rights reserved.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- *
- * - Redistributions of source code must retain the above copyright notice,
- * this list of conditions and the disclaimer below.
- *
- * Atmel's name may not be used to endorse or promote products derived from
- * this software without specific prior written permission.
- *
- * DISCLAIMER: THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR
- * IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
- * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
- * DISCLAIMED. IN NO EVENT SHALL ATMEL 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.
- * ----------------------------------------------------------------------------
- */
-
-
-//------------------------------------------------------------------------------
-// Definitions
-//------------------------------------------------------------------------------
-
-
-#define AIC 0xFFFFF000
-#define AIC_IVR 0x10
-#define AIC_EOICR 0x38
-
-#define IRQ_STACK_SIZE 8*3*4
-
-#define ARM_MODE_ABT 0x17
-#define ARM_MODE_FIQ 0x11
-#define ARM_MODE_IRQ 0x12
-#define ARM_MODE_SVC 0x13
-#define ARM_MODE_SYS 0x1F
-
-#define I_BIT 0x80
-#define F_BIT 0x40
-
-//------------------------------------------------------------------------------
-// Startup routine
-//------------------------------------------------------------------------------
-
- .align 4
- .arm
-
-/* Exception vectors
- *******************/
- .section .vectors, "a", %progbits
-
-resetVector:
- ldr pc, =resetHandler /* Reset */
-undefVector:
- b undefVector /* Undefined instruction */
-swiVector:
- b swiVector /* Software interrupt */
-prefetchAbortVector:
- b prefetchAbortVector /* Prefetch abort */
-dataAbortVector:
- b dataAbortVector /* Data abort */
-reservedVector:
- b reservedVector /* Reserved for future use */
-irqVector:
- b irqHandler /* Interrupt */
-fiqVector:
- /* Fast interrupt */
-//------------------------------------------------------------------------------
-/// Handles a fast interrupt request by branching to the address defined in the
-/// AIC.
-//------------------------------------------------------------------------------
-fiqHandler:
- b fiqHandler
-
-//------------------------------------------------------------------------------
-/// Handles incoming interrupt requests by branching to the corresponding
-/// handler, as defined in the AIC. Supports interrupt nesting.
-//------------------------------------------------------------------------------
-irqHandler:
- /* Save interrupt context on the stack to allow nesting */
- SUB lr, lr, #4
- STMFD sp!, {lr}
- MRS lr, SPSR
- STMFD sp!, {r0, lr}
-
- /* Write in the IVR to support Protect Mode */
- LDR lr, =AIC
- LDR r0, [r14, #AIC_IVR]
- STR lr, [r14, #AIC_IVR]
-
- /* Branch to interrupt handler in Supervisor mode */
- MSR CPSR_c, #ARM_MODE_SVC
- STMFD sp!, {r1-r3, r4, r12, lr}
-
- /* Check for 8-byte alignment and save lr plus a */
- /* word to indicate the stack adjustment used (0 or 4) */
- AND r1, sp, #4
- SUB sp, sp, r1
- STMFD sp!, {r1, lr}
-
- BLX r0
-
- LDMIA sp!, {r1, lr}
- ADD sp, sp, r1
-
- LDMIA sp!, {r1-r3, r4, r12, lr}
- MSR CPSR_c, #ARM_MODE_IRQ | I_BIT
-
- /* Acknowledge interrupt */
- LDR lr, =AIC
- STR lr, [r14, #AIC_EOICR]
-
- /* Restore interrupt context and branch back to calling code */
- LDMIA sp!, {r0, lr}
- MSR SPSR_cxsf, lr
- LDMIA sp!, {pc}^
-
-
-//------------------------------------------------------------------------------
-/// Initializes the chip and branches to the main() function.
-//------------------------------------------------------------------------------
- .section .textEntry
- .global entry
-
-entry:
-resetHandler:
-
- CPSIE A
-
-/* Enable VFP */
- /* - Enable access to CP10 and CP11 in CP15.CACR */
- mrc p15, 0, r0, c1, c0, 2
- orr r0, r0, #0xf00000
- mcr p15, 0, r0, c1, c0, 2
-/* - Enable access to CP10 and CP11 in CP15.NSACR */
-/* - Set FPEXC.EN (B30) */
- fmrx r0, fpexc
- orr r0, r0, #0x40000000
- fmxr fpexc, r0
-
-/* Useless instruction for referencing the .vectors section */
- ldr r0, =resetVector
-
-/* Set pc to actual code location (i.e. not in remap zone) */
- ldr pc, =1f
-
-/* Initialize the prerelocate segment */
-1:
- ldr r0, =_efixed
- ldr r1, =_sprerelocate
- ldr r2, =_eprerelocate
-1:
- cmp r1, r2
- ldrcc r3, [r0], #4
- strcc r3, [r1], #4
- bcc 1b
-
-/* Perform low-level initialization of the chip using LowLevelInit() */
- ldr sp, =_sstack
- stmfd sp!, {r0}
- ldr r0, =LowLevelInit
- blx r0
-
-/* Initialize the postrelocate segment */
-
- ldmfd sp!, {r0}
- ldr r1, =_spostrelocate
- ldr r2, =_epostrelocate
-1:
- cmp r1, r2
- ldrcc r3, [r0], #4
- strcc r3, [r1], #4
- bcc 1b
-
-/* Clear the zero segment */
- ldr r0, =_szero
- ldr r1, =_ezero
- mov r2, #0
-1:
- cmp r0, r1
- strcc r2, [r0], #4
- bcc 1b
-
-/* Setup stacks
- **************/
-/* IRQ mode */
- msr CPSR_c, #ARM_MODE_IRQ | I_BIT | F_BIT
- ldr sp, =_sstack
- sub r4, sp, #IRQ_STACK_SIZE
-
-/* Supervisor mode (interrupts enabled) */
- msr CPSR_c, #ARM_MODE_SVC | F_BIT
- mov sp, r4
-
-/*Initialize the C library */
- ldr r3, =__libc_init_array
- mov lr, pc
- bx r3
-
-/* Branch to main()
- ******************/
- ldr r0, =main
- blx r0
-
-/* Loop indefinitely when program is finished */
-1:
- b 1b
-
diff --git a/FreeRTOS/Demo/CORTEX_A5_SAMA5D3x_Xplained_IAR/FreeRTOSConfig.h b/FreeRTOS/Demo/CORTEX_A5_SAMA5D3x_Xplained_IAR/FreeRTOSConfig.h
index 55c34e7f5..c7a79294a 100644
--- a/FreeRTOS/Demo/CORTEX_A5_SAMA5D3x_Xplained_IAR/FreeRTOSConfig.h
+++ b/FreeRTOS/Demo/CORTEX_A5_SAMA5D3x_Xplained_IAR/FreeRTOSConfig.h
@@ -78,29 +78,6 @@
* See http://www.freertos.org/a00110.html.
*----------------------------------------------------------*/
-/*
- * The FreeRTOS Cortex-A port implements a full interrupt nesting model.
- *
- * Interrupts that are assigned a priority at or below
- * configMAX_API_CALL_INTERRUPT_PRIORITY (which counter-intuitively in the ARM
- * generic interrupt controller [GIC] means a priority that has a numerical
- * value above configMAX_API_CALL_INTERRUPT_PRIORITY) can call FreeRTOS safe API
- * functions and will nest.
- *
- * Interrupts that are assigned a priority above
- * configMAX_API_CALL_INTERRUPT_PRIORITY (which in the GIC means a numerical
- * value below configMAX_API_CALL_INTERRUPT_PRIORITY) cannot call any FreeRTOS
- * API functions, will nest, and will not be masked by FreeRTOS critical
- * sections (although it is necessary for interrupts to be globally disabled
- * extremely briefly as the interrupt mask is updated in the GIC).
- *
- * FreeRTOS functions that can be called from an interrupt are those that end in
- * "FromISR". FreeRTOS maintains a separate interrupt safe API to enable
- * interrupt entry to be shorter, faster, simpler and smaller.
- */
-#define configMAX_API_CALL_INTERRUPT_PRIORITY 25
-
-
#define configCPU_CLOCK_HZ 100000000UL
#define configUSE_PORT_OPTIMISED_TASK_SELECTION 1
#define configUSE_TICKLESS_IDLE 0
@@ -158,8 +135,8 @@ used. */
void vInitialiseRunTimeStats( void );
#define configGENERATE_RUN_TIME_STATS 0
-// #define portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() vInitialiseRunTimeStats()
-// #define portGET_RUN_TIME_COUNTER_VALUE() ulGetRunTimeCounterValue()
+//_RB_ #define portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() vInitialiseRunTimeStats()
+//_RB_ #define portGET_RUN_TIME_COUNTER_VALUE() ulGetRunTimeCounterValue()
/* The size of the global output buffer that is available for use when there
are multiple command interpreters running at once (for example, one on a UART
@@ -185,18 +162,10 @@ used. */
*/
void vConfigureTickInterrupt( void );
#define configSETUP_TICK_INTERRUPT() vConfigureTickInterrupt()
+
+ #define configPIT_PIVR ( *( ( volatile uint32_t * ) 0xFFFFFE38UL ) )
+ #define configCLEAR_TICK_INTERRUPT() ( void ) configPIT_PIVR /* Read PIT_PIVR to clear interrupt. */
#endif /* __IASMARM__ */
-/* The following constants describe the hardware, and are correct for the
-Atmel SAMA5 MPU. */
-#define configINTERRUPT_CONTROLLER_BASE_ADDRESS 0xE8201000
-#define configINTERRUPT_CONTROLLER_CPU_INTERFACE_OFFSET 0x1000
-#define configUNIQUE_INTERRUPT_PRIORITIES 32
-
-/* Map the FreeRTOS IRQ and SVC/SWI handlers to the names used in the C startup
-code (which is where the vector table is defined). */
-#define FreeRTOS_IRQ_Handler IRQ_Handler
-#define FreeRTOS_SWI_Handler SWI_Handler
-
#endif /* FREERTOS_CONFIG_H */
diff --git a/FreeRTOS/Demo/CORTEX_A5_SAMA5D3x_Xplained_IAR/FreeRTOS_tick_config.c b/FreeRTOS/Demo/CORTEX_A5_SAMA5D3x_Xplained_IAR/FreeRTOS_tick_config.c
index cdde1261f..663b3f95b 100644
--- a/FreeRTOS/Demo/CORTEX_A5_SAMA5D3x_Xplained_IAR/FreeRTOS_tick_config.c
+++ b/FreeRTOS/Demo/CORTEX_A5_SAMA5D3x_Xplained_IAR/FreeRTOS_tick_config.c
@@ -67,6 +67,9 @@
#include "FreeRTOS.h"
#include "Task.h"
+/* Library includes. */
+#include "board.h"
+
/*
* The application must provide a function that configures a peripheral to
* create the FreeRTOS tick interrupt, then define configSETUP_TICK_INTERRUPT()
@@ -75,23 +78,27 @@
*/
void vConfigureTickInterrupt( void )
{
-#warning Needs implementing.
+extern void FreeRTOS_Tick_Handler( void );
+
+ /* NOTE: The PIT interrupt is cleared by the configCLEAR_TICK_INTERRUPT()
+ macro in FreeRTOSConfig.h. */
+
+ /* Enable the PIT clock. */
+ PMC->PMC_PCER0 = 1 << ID_PIT;
+
+ /* Initialize the PIT to the desired frequency - specified in uS. */
+ PIT_Init( 1000000UL / configTICK_RATE_HZ, BOARD_MCK / 1000000 );
+
+ /* Configure interrupt on PIT */
+#warning This is on the system interrupt and other interrupts may need processing to.
+ IRQ_ConfigureIT( ID_PIT, 0, FreeRTOS_Tick_Handler );
+ IRQ_EnableIT( ID_PIT );
+ PIT_EnableIT();
+
+ /* Enable the pit. */
+ PIT_Enable();
}
/*-----------------------------------------------------------*/
-void vApplicationIRQHandler( uint32_t ulICCIAR );
-void vApplicationIRQHandler( uint32_t ulICCIAR )
-{
-uint32_t ulInterruptID;
-
- /* Re-enable interrupts. */
- __asm ( "cpsie i" );
-
- /* The ID of the interrupt is obtained by bitwise anding the ICCIAR value
- with 0x3FF. */
- ulInterruptID = ulICCIAR & 0x3FFUL;
-
-#warning Needs implementing.
-}
diff --git a/FreeRTOS/Demo/CORTEX_A5_SAMA5D3x_Xplained_IAR/LEDs.c b/FreeRTOS/Demo/CORTEX_A5_SAMA5D3x_Xplained_IAR/LEDs.c
index 1922b0d0c..2e6264c64 100644
--- a/FreeRTOS/Demo/CORTEX_A5_SAMA5D3x_Xplained_IAR/LEDs.c
+++ b/FreeRTOS/Demo/CORTEX_A5_SAMA5D3x_Xplained_IAR/LEDs.c
@@ -76,20 +76,34 @@
/* Demo includes. */
#include "partest.h"
+/* Library includes. */
+#include "board.h"
+
/*-----------------------------------------------------------*/
void vParTestInitialise( void )
{
+ LED_Configure( 0 );
+ LED_Configure( 1 );
}
/*-----------------------------------------------------------*/
void vParTestSetLED( UBaseType_t uxLED, BaseType_t xValue )
{
+ if( xValue == pdTRUE )
+ {
+ LED_Set( uxLED );
+ }
+ else
+ {
+ LED_Clear( uxLED );
+ }
}
/*-----------------------------------------------------------*/
void vParTestToggleLED( unsigned portBASE_TYPE uxLED )
{
+ LED_Toggle( uxLED );
}
diff --git a/FreeRTOS/Demo/CORTEX_A5_SAMA5D3x_Xplained_IAR/RTOSDemo.ewd b/FreeRTOS/Demo/CORTEX_A5_SAMA5D3x_Xplained_IAR/RTOSDemo.ewd
index f5a8a5ee4..604ac47a9 100644
--- a/FreeRTOS/Demo/CORTEX_A5_SAMA5D3x_Xplained_IAR/RTOSDemo.ewd
+++ b/FreeRTOS/Demo/CORTEX_A5_SAMA5D3x_Xplained_IAR/RTOSDemo.ewd
@@ -49,7 +49,7 @@