2 ******************************************************************************
3 * @file startup_stm32f40_41xxx.s
4 * @author MCD Application Team
6 * @date 21-October-2015
7 * @brief STM32F40xxx/41xxx Devices vector table for Atollic TrueSTUDIO toolchain.
8 * Same as startup_stm32f40_41xxx.s and maintained for legacy purpose
9 * This module performs:
10 * - Set the initial SP
11 * - Set the initial PC == Reset_Handler,
12 * - Set the vector table entries with the exceptions ISR address
13 * - Configure the clock system and the external SRAM mounted on
14 * STM324xG-EVAL board to be used as data memory (optional,
15 * to be enabled by user)
16 * - Branches to main in the C library (which eventually
18 * After Reset the Cortex-M4 processor is in Thread mode,
19 * priority is Privileged, and the Stack is set to Main.
20 ******************************************************************************
23 * <h2><center>© COPYRIGHT 2015 STMicroelectronics</center></h2>
25 * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
26 * You may not use this file except in compliance with the License.
27 * You may obtain a copy of the License at:
29 * http://www.st.com/software_license_agreement_liberty_v2
31 * Unless required by applicable law or agreed to in writing, software
32 * distributed under the License is distributed on an "AS IS" BASIS,
33 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
34 * See the License for the specific language governing permissions and
35 * limitations under the License.
37 ******************************************************************************
46 .global Default_Handler
49 /* start address for the initialization values of the .data section.
50 defined in linker script */
52 /* start address for the .data section. defined in linker script */
54 /* end address for the .data section. defined in linker script */
56 /* start address for the .bss section. defined in linker script */
58 /* end address for the .bss section. defined in linker script */
60 /* stack used for SystemInit_ExtMemCtl; always internal RAM used */
63 * @brief This is the code that gets called when the processor first
64 * starts execution following a reset event. Only the absolutely
65 * necessary set is performed, after which the application
66 * supplied main() routine is called.
71 .section .text.Reset_Handler
73 .type Reset_Handler, %function
76 // RCC-
>AHB1ENR |
= RCC_AHB1ENR_CCMDATARAMEN;
77 ldr
r0, =0x40023800 // RCC_BASE
78 ldr
r1, [r0, #0x30] // AHB1ENR
79 orr
r1, r1, 0x00100000 // RCC_AHB1ENR_CCMDATARAMEN
84 bl persistentObjectInit
85 bl checkForBootLoaderRequest
87 /* Copy the data segment initializers from flash to SRAM */
105 /* Zero fill the bss segment. */
115 /* Zero fill FASTRAM */
116 ldr
r2, =__fastram_bss_start__
117 b LoopFillZeroFASTRAM
124 ldr
r3, = __fastram_bss_end__
128 /* Mark the heap and stack */
129 ldr
r2, =_heap_stack_begin
137 ldr
r3, = _heap_stack_end
142 ldr
r0, =0xE000ED88 /* Enable CP10,CP11 */
144 orr
r1,r1,#(0xF << 20)
147 /* Call the clock system intitialization function.*/
150 /* Call the application's entry point.*/
157 Reboot_Loader
: // mj666
159 // Reboot to ROM
// mj666
160 ldr
r0, =0x1FFF0000 // mj666
161 ldr sp
,[r0, #0] // mj666
162 ldr
r0,[r0, #4] // mj666
164 .size Reset_Handler, .-Reset_Handler
167 * @brief This is the code that gets called when the processor receives an
168 * unexpected interrupt. This simply enters an infinite loop, preserving
169 * the system state for examination by a debugger.
173 .section .text.Default_Handler,"ax",%progbits
177 .size Default_Handler, .-Default_Handler
178 /******************************************************************************
180 * The minimal vector table for a Cortex M3. Note that the proper constructs
181 * must be placed on this to ensure that it ends up at physical address
184 *******************************************************************************/
185 .section .isr_vector,"a",%progbits
186 .type g_pfnVectors, %object
187 .size g_pfnVectors, .-g_pfnVectors
194 .word HardFault_Handler
195 .word MemManage_Handler
196 .word BusFault_Handler
197 .word UsageFault_Handler
203 .word DebugMon_Handler
206 .word SysTick_Handler
208 /* External Interrupts */
209 .word WWDG_IRQHandler /* Window WatchDog */
210 .word PVD_IRQHandler /* PVD through EXTI Line detection */
211 .word TAMP_STAMP_IRQHandler /* Tamper and TimeStamps through the EXTI line */
212 .word RTC_WKUP_IRQHandler /* RTC Wakeup through the EXTI line */
213 .word FLASH_IRQHandler /* FLASH */
214 .word RCC_IRQHandler /* RCC */
215 .word EXTI0_IRQHandler /* EXTI Line0 */
216 .word EXTI1_IRQHandler /* EXTI Line1 */
217 .word EXTI2_IRQHandler /* EXTI Line2 */
218 .word EXTI3_IRQHandler /* EXTI Line3 */
219 .word EXTI4_IRQHandler /* EXTI Line4 */
220 .word DMA1_Stream0_IRQHandler /* DMA1 Stream 0 */
221 .word DMA1_Stream1_IRQHandler /* DMA1 Stream 1 */
222 .word DMA1_Stream2_IRQHandler /* DMA1 Stream 2 */
223 .word DMA1_Stream3_IRQHandler /* DMA1 Stream 3 */
224 .word DMA1_Stream4_IRQHandler /* DMA1 Stream 4 */
225 .word DMA1_Stream5_IRQHandler /* DMA1 Stream 5 */
226 .word DMA1_Stream6_IRQHandler /* DMA1 Stream 6 */
227 .word ADC_IRQHandler /* ADC1, ADC2 and ADC3s */
228 .word 0 /* CAN1 TX */
229 .word 0 /* CAN1 RX0 */
230 .word 0 /* CAN1 RX1 */
231 .word 0 /* CAN1 SCE */
232 .word EXTI9_5_IRQHandler /* External Line[9:5]s */
233 .word TIM1_BRK_TIM9_IRQHandler /* TIM1 Break and TIM9 */
234 .word TIM1_UP_TIM10_IRQHandler /* TIM1 Update and TIM10 */
235 .word TIM1_TRG_COM_TIM11_IRQHandler /* TIM1 Trigger and Commutation and TIM11 */
236 .word TIM1_CC_IRQHandler /* TIM1 Capture Compare */
237 .word TIM2_IRQHandler /* TIM2 */
238 .word TIM3_IRQHandler /* TIM3 */
239 .word TIM4_IRQHandler /* TIM4 */
240 .word I2C1_EV_IRQHandler /* I2C1 Event */
241 .word I2C1_ER_IRQHandler /* I2C1 Error */
242 .word I2C2_EV_IRQHandler /* I2C2 Event */
243 .word I2C2_ER_IRQHandler /* I2C2 Error */
244 .word SPI1_IRQHandler /* SPI1 */
245 .word SPI2_IRQHandler /* SPI2 */
246 .word USART1_IRQHandler /* USART1 */
247 .word USART2_IRQHandler /* USART2 */
249 .word EXTI15_10_IRQHandler /* External Line[15:10]s */
250 .word RTC_Alarm_IRQHandler /* RTC Alarm (A and B) through EXTI Line */
251 .word OTG_FS_WKUP_IRQHandler /* USB OTG FS Wakeup through EXTI line */
252 .word 0 /* TIM8 Break and TIM12 */
253 .word 0 /* TIM8 Update and TIM13 */
254 .word 0 /* TIM8 Trigger and Commutation and TIM14 */
255 .word 0 /* TIM8 Capture Compare */
256 .word DMA1_Stream7_IRQHandler /* DMA1 Stream7 */
258 .word SDIO_IRQHandler /* SDIO */
259 .word TIM5_IRQHandler /* TIM5 */
260 .word SPI3_IRQHandler /* SPI3 */
263 .word 0 /* TIM6 and DAC1&2 underrun errors */
265 .word DMA2_Stream0_IRQHandler /* DMA2 Stream 0 */
266 .word DMA2_Stream1_IRQHandler /* DMA2 Stream 1 */
267 .word DMA2_Stream2_IRQHandler /* DMA2 Stream 2 */
268 .word DMA2_Stream3_IRQHandler /* DMA2 Stream 3 */
269 .word DMA2_Stream4_IRQHandler /* DMA2 Stream 4 */
270 .word 0 /* Ethernet */
271 .word 0 /* Ethernet Wakeup through EXTI line */
272 .word 0 /* CAN2 TX */
273 .word 0 /* CAN2 RX0 */
274 .word 0 /* CAN2 RX1 */
275 .word 0 /* CAN2 SCE */
276 .word OTG_FS_IRQHandler /* USB OTG FS */
277 .word DMA2_Stream5_IRQHandler /* DMA2 Stream 5 */
278 .word DMA2_Stream6_IRQHandler /* DMA2 Stream 6 */
279 .word DMA2_Stream7_IRQHandler /* DMA2 Stream 7 */
280 .word USART6_IRQHandler /* USART6 */
281 .word I2C3_EV_IRQHandler /* I2C3 event */
282 .word I2C3_ER_IRQHandler /* I2C3 error */
283 .word 0 /* USB OTG HS End Point 1 Out */
284 .word 0 /* USB OTG HS End Point 1 In */
285 .word 0 /* USB OTG HS Wakeup through EXTI */
286 .word 0 /* USB OTG HS */
288 .word 0 /* CRYP crypto */
289 .word 0 /* Hash and Rng */
290 .word FPU_IRQHandler /* FPU */
291 .word 0 /* Reserved */
292 .word 0 /* Reserved */
293 .word SPI4_IRQHandler /* SPI4 */
294 .word SPI5_IRQHandler /* SPI5 */
295 /*******************************************************************************
297 * Provide weak aliases for each Exception handler to the Default_Handler.
298 * As they are weak aliases, any function with the same name will override
301 *******************************************************************************/
303 .thumb_set NMI_Handler,Default_Handler
305 .weak HardFault_Handler
306 .thumb_set HardFault_Handler,Default_Handler
308 .weak MemManage_Handler
309 .thumb_set MemManage_Handler,Default_Handler
311 .weak BusFault_Handler
312 .thumb_set BusFault_Handler,Default_Handler
314 .weak UsageFault_Handler
315 .thumb_set UsageFault_Handler,Default_Handler
318 .thumb_set SVC_Handler,Default_Handler
320 .weak DebugMon_Handler
321 .thumb_set DebugMon_Handler,Default_Handler
324 .thumb_set PendSV_Handler,Default_Handler
326 .weak SysTick_Handler
327 .thumb_set SysTick_Handler,Default_Handler
329 .weak WWDG_IRQHandler
330 .thumb_set WWDG_IRQHandler,Default_Handler
333 .thumb_set PVD_IRQHandler,Default_Handler
335 .weak TAMP_STAMP_IRQHandler
336 .thumb_set TAMP_STAMP_IRQHandler,Default_Handler
338 .weak RTC_WKUP_IRQHandler
339 .thumb_set RTC_WKUP_IRQHandler,Default_Handler
341 .weak FLASH_IRQHandler
342 .thumb_set FLASH_IRQHandler,Default_Handler
345 .thumb_set RCC_IRQHandler,Default_Handler
347 .weak EXTI0_IRQHandler
348 .thumb_set EXTI0_IRQHandler,Default_Handler
350 .weak EXTI1_IRQHandler
351 .thumb_set EXTI1_IRQHandler,Default_Handler
353 .weak EXTI2_IRQHandler
354 .thumb_set EXTI2_IRQHandler,Default_Handler
356 .weak EXTI3_IRQHandler
357 .thumb_set EXTI3_IRQHandler,Default_Handler
359 .weak EXTI4_IRQHandler
360 .thumb_set EXTI4_IRQHandler,Default_Handler
362 .weak DMA1_Stream0_IRQHandler
363 .thumb_set DMA1_Stream0_IRQHandler,Default_Handler
365 .weak DMA1_Stream1_IRQHandler
366 .thumb_set DMA1_Stream1_IRQHandler,Default_Handler
368 .weak DMA1_Stream2_IRQHandler
369 .thumb_set DMA1_Stream2_IRQHandler,Default_Handler
371 .weak DMA1_Stream3_IRQHandler
372 .thumb_set DMA1_Stream3_IRQHandler,Default_Handler
374 .weak DMA1_Stream4_IRQHandler
375 .thumb_set DMA1_Stream4_IRQHandler,Default_Handler
377 .weak DMA1_Stream5_IRQHandler
378 .thumb_set DMA1_Stream5_IRQHandler,Default_Handler
380 .weak DMA1_Stream6_IRQHandler
381 .thumb_set DMA1_Stream6_IRQHandler,Default_Handler
384 .thumb_set ADC_IRQHandler,Default_Handler
386 .weak EXTI9_5_IRQHandler
387 .thumb_set EXTI9_5_IRQHandler,Default_Handler
389 .weak TIM1_BRK_TIM9_IRQHandler
390 .thumb_set TIM1_BRK_TIM9_IRQHandler,Default_Handler
392 .weak TIM1_UP_TIM10_IRQHandler
393 .thumb_set TIM1_UP_TIM10_IRQHandler,Default_Handler
395 .weak TIM1_TRG_COM_TIM11_IRQHandler
396 .thumb_set TIM1_TRG_COM_TIM11_IRQHandler,Default_Handler
398 .weak TIM1_CC_IRQHandler
399 .thumb_set TIM1_CC_IRQHandler,Default_Handler
401 .weak TIM2_IRQHandler
402 .thumb_set TIM2_IRQHandler,Default_Handler
404 .weak TIM3_IRQHandler
405 .thumb_set TIM3_IRQHandler,Default_Handler
407 .weak TIM4_IRQHandler
408 .thumb_set TIM4_IRQHandler,Default_Handler
410 .weak I2C1_EV_IRQHandler
411 .thumb_set I2C1_EV_IRQHandler,Default_Handler
413 .weak I2C1_ER_IRQHandler
414 .thumb_set I2C1_ER_IRQHandler,Default_Handler
416 .weak I2C2_EV_IRQHandler
417 .thumb_set I2C2_EV_IRQHandler,Default_Handler
419 .weak I2C2_ER_IRQHandler
420 .thumb_set I2C2_ER_IRQHandler,Default_Handler
422 .weak SPI1_IRQHandler
423 .thumb_set SPI1_IRQHandler,Default_Handler
425 .weak SPI2_IRQHandler
426 .thumb_set SPI2_IRQHandler,Default_Handler
428 .weak USART1_IRQHandler
429 .thumb_set USART1_IRQHandler,Default_Handler
431 .weak USART2_IRQHandler
432 .thumb_set USART2_IRQHandler,Default_Handler
434 .weak EXTI15_10_IRQHandler
435 .thumb_set EXTI15_10_IRQHandler,Default_Handler
437 .weak RTC_Alarm_IRQHandler
438 .thumb_set RTC_Alarm_IRQHandler,Default_Handler
440 .weak OTG_FS_WKUP_IRQHandler
441 .thumb_set OTG_FS_WKUP_IRQHandler,Default_Handler
443 .weak DMA1_Stream7_IRQHandler
444 .thumb_set DMA1_Stream7_IRQHandler,Default_Handler
446 .weak SDIO_IRQHandler
447 .thumb_set SDIO_IRQHandler,Default_Handler
449 .weak TIM5_IRQHandler
450 .thumb_set TIM5_IRQHandler,Default_Handler
452 .weak SPI3_IRQHandler
453 .thumb_set SPI3_IRQHandler,Default_Handler
455 .weak DMA2_Stream0_IRQHandler
456 .thumb_set DMA2_Stream0_IRQHandler,Default_Handler
458 .weak DMA2_Stream1_IRQHandler
459 .thumb_set DMA2_Stream1_IRQHandler,Default_Handler
461 .weak DMA2_Stream2_IRQHandler
462 .thumb_set DMA2_Stream2_IRQHandler,Default_Handler
464 .weak DMA2_Stream3_IRQHandler
465 .thumb_set DMA2_Stream3_IRQHandler,Default_Handler
467 .weak DMA2_Stream4_IRQHandler
468 .thumb_set DMA2_Stream4_IRQHandler,Default_Handler
470 .weak OTG_FS_IRQHandler
471 .thumb_set OTG_FS_IRQHandler,Default_Handler
473 .weak DMA2_Stream5_IRQHandler
474 .thumb_set DMA2_Stream5_IRQHandler,Default_Handler
476 .weak DMA2_Stream6_IRQHandler
477 .thumb_set DMA2_Stream6_IRQHandler,Default_Handler
479 .weak DMA2_Stream7_IRQHandler
480 .thumb_set DMA2_Stream7_IRQHandler,Default_Handler
482 .weak USART6_IRQHandler
483 .thumb_set USART6_IRQHandler,Default_Handler
485 .weak I2C3_EV_IRQHandler
486 .thumb_set I2C3_EV_IRQHandler,Default_Handler
488 .weak I2C3_ER_IRQHandler
489 .thumb_set I2C3_ER_IRQHandler,Default_Handler
492 .thumb_set FPU_IRQHandler,Default_Handler
494 .weak SPI4_IRQHandler
495 .thumb_set SPI4_IRQHandler,Default_Handler
497 .weak SPI5_IRQHandler
498 .thumb_set SPI5_IRQHandler,Default_Handler
500 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/