00001 //***************************************************************************** 00002 // 00003 // startup_gcc.c - Startup code for use with GNU tools. 00004 // 00005 // Copyright (c) 2009-2012 Texas Instruments Incorporated. All rights reserved. 00006 // Software License Agreement 00007 // 00008 // Redistribution and use in source and binary forms, with or without 00009 // modification, are permitted provided that the following conditions 00010 // are met: 00011 // 00012 // Redistributions of source code must retain the above copyright 00013 // notice, this list of conditions and the following disclaimer. 00014 // 00015 // Redistributions in binary form must reproduce the above copyright 00016 // notice, this list of conditions and the following disclaimer in the 00017 // documentation and/or other materials provided with the 00018 // distribution. 00019 // 00020 // Neither the name of Texas Instruments Incorporated nor the names of 00021 // its contributors may be used to endorse or promote products derived 00022 // from this software without specific prior written permission. 00023 // 00024 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00025 // "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00026 // LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR 00027 // A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT 00028 // OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, 00029 // SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT 00030 // LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, 00031 // DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY 00032 // THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT 00033 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 00034 // OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 00035 // 00036 //***************************************************************************** 00037 00038 #include <stdint.h> 00039 #include "inc/hw_nvic.h" 00040 #include "inc/hw_types.h" 00041 00042 //***************************************************************************** 00043 // 00044 // Forward declaration of the default fault handlers. 00045 // 00046 //***************************************************************************** 00047 void ResetISR(void); 00048 static void NmiSR(void); 00049 static void FaultISR(void); 00050 static void IntDefaultHandler(void); 00051 00052 //***************************************************************************** 00053 // 00054 // The entry point for the application. 00055 // 00056 //***************************************************************************** 00057 extern int main(void); 00058 00059 //***************************************************************************** 00060 // System stack start determined by ldscript, normally highest ram address 00061 //***************************************************************************** 00062 extern uint32_t _estack; 00063 00064 //***************************************************************************** 00065 // 00066 // The vector table. Note that the proper constructs must be placed on this to 00067 // ensure that it ends up at physical address 0x0000.0000. 00068 // 00069 //***************************************************************************** 00070 #ifdef TM4C123GXL 00071 __attribute__ ((section(".isr_vector"))) 00072 void (* const g_pfnVectors[])(void) = 00073 { 00074 (void (*)(void))((uint32_t)&_estack), // The initial stack pointer, 0x20008000 32K 00075 ResetISR, // The reset handler 00076 NmiSR, // The NMI handler 00077 FaultISR, // The hard fault handler 00078 IntDefaultHandler, // The MPU fault handler 00079 IntDefaultHandler, // The bus fault handler 00080 IntDefaultHandler, // The usage fault handler 00081 0, // Reserved 00082 0, // Reserved 00083 0, // Reserved 00084 0, // Reserved 00085 IntDefaultHandler, // SVCall handler 00086 IntDefaultHandler, // Debug monitor handler 00087 0, // Reserved 00088 IntDefaultHandler, // The PendSV handler 00089 IntDefaultHandler, // The SysTick handler 00090 IntDefaultHandler, // GPIO Port A 00091 IntDefaultHandler, // GPIO Port B 00092 IntDefaultHandler, // GPIO Port C 00093 IntDefaultHandler, // GPIO Port D 00094 IntDefaultHandler, // GPIO Port E 00095 IntDefaultHandler, // UART0 Rx and Tx 00096 IntDefaultHandler, // UART1 Rx and Tx 00097 IntDefaultHandler, // SSI0 Rx and Tx 00098 IntDefaultHandler, // I2C0 Master and Slave 00099 IntDefaultHandler, // PWM Fault 00100 IntDefaultHandler, // PWM Generator 0 00101 IntDefaultHandler, // PWM Generator 1 00102 IntDefaultHandler, // PWM Generator 2 00103 IntDefaultHandler, // Quadrature Encoder 0 00104 IntDefaultHandler, // ADC Sequence 0 00105 IntDefaultHandler, // ADC Sequence 1 00106 IntDefaultHandler, // ADC Sequence 2 00107 IntDefaultHandler, // ADC Sequence 3 00108 IntDefaultHandler, // Watchdog timer 00109 IntDefaultHandler, // Timer 0 subtimer A 00110 IntDefaultHandler, // Timer 0 subtimer B 00111 IntDefaultHandler, // Timer 1 subtimer A 00112 IntDefaultHandler, // Timer 1 subtimer B 00113 IntDefaultHandler, // Timer 2 subtimer A 00114 IntDefaultHandler, // Timer 2 subtimer B 00115 IntDefaultHandler, // Analog Comparator 0 00116 IntDefaultHandler, // Analog Comparator 1 00117 IntDefaultHandler, // Analog Comparator 2 00118 IntDefaultHandler, // System Control (PLL, OSC, BO) 00119 IntDefaultHandler, // FLASH Control 00120 IntDefaultHandler, // GPIO Port F 00121 IntDefaultHandler, // GPIO Port G 00122 IntDefaultHandler, // GPIO Port H 00123 IntDefaultHandler, // UART2 Rx and Tx 00124 IntDefaultHandler, // SSI1 Rx and Tx 00125 IntDefaultHandler, // Timer 3 subtimer A 00126 IntDefaultHandler, // Timer 3 subtimer B 00127 IntDefaultHandler, // I2C1 Master and Slave 00128 IntDefaultHandler, // Quadrature Encoder 1 00129 IntDefaultHandler, // CAN0 00130 IntDefaultHandler, // CAN1 00131 0, // Reserved 00132 0, // Reserved 00133 IntDefaultHandler, // Hibernate 00134 IntDefaultHandler, // USB0 00135 IntDefaultHandler, // PWM Generator 3 00136 IntDefaultHandler, // uDMA Software Transfer 00137 IntDefaultHandler, // uDMA Error 00138 IntDefaultHandler, // ADC1 Sequence 0 00139 IntDefaultHandler, // ADC1 Sequence 1 00140 IntDefaultHandler, // ADC1 Sequence 2 00141 IntDefaultHandler, // ADC1 Sequence 3 00142 0, // Reserved 00143 0, // Reserved 00144 IntDefaultHandler, // GPIO Port J 00145 IntDefaultHandler, // GPIO Port K 00146 IntDefaultHandler, // GPIO Port L 00147 IntDefaultHandler, // SSI2 Rx and Tx 00148 IntDefaultHandler, // SSI3 Rx and Tx 00149 IntDefaultHandler, // UART3 Rx and Tx 00150 IntDefaultHandler, // UART4 Rx and Tx 00151 IntDefaultHandler, // UART5 Rx and Tx 00152 IntDefaultHandler, // UART6 Rx and Tx 00153 IntDefaultHandler, // UART7 Rx and Tx 00154 0, // Reserved 00155 0, // Reserved 00156 0, // Reserved 00157 0, // Reserved 00158 IntDefaultHandler, // I2C2 Master and Slave 00159 IntDefaultHandler, // I2C3 Master and Slave 00160 IntDefaultHandler, // Timer 4 subtimer A 00161 IntDefaultHandler, // Timer 4 subtimer B 00162 0, // Reserved 00163 0, // Reserved 00164 0, // Reserved 00165 0, // Reserved 00166 0, // Reserved 00167 0, // Reserved 00168 0, // Reserved 00169 0, // Reserved 00170 0, // Reserved 00171 0, // Reserved 00172 0, // Reserved 00173 0, // Reserved 00174 0, // Reserved 00175 0, // Reserved 00176 0, // Reserved 00177 0, // Reserved 00178 0, // Reserved 00179 0, // Reserved 00180 0, // Reserved 00181 0, // Reserved 00182 IntDefaultHandler, // Timer 5 subtimer A 00183 IntDefaultHandler, // Timer 5 subtimer B 00184 IntDefaultHandler, // Wide Timer 0 subtimer A 00185 IntDefaultHandler, // Wide Timer 0 subtimer B 00186 IntDefaultHandler, // Wide Timer 1 subtimer A 00187 IntDefaultHandler, // Wide Timer 1 subtimer B 00188 IntDefaultHandler, // Wide Timer 2 subtimer A 00189 IntDefaultHandler, // Wide Timer 2 subtimer B 00190 IntDefaultHandler, // Wide Timer 3 subtimer A 00191 IntDefaultHandler, // Wide Timer 3 subtimer B 00192 IntDefaultHandler, // Wide Timer 4 subtimer A 00193 IntDefaultHandler, // Wide Timer 4 subtimer B 00194 IntDefaultHandler, // Wide Timer 5 subtimer A 00195 IntDefaultHandler, // Wide Timer 5 subtimer B 00196 IntDefaultHandler, // FPU 00197 0, // Reserved 00198 0, // Reserved 00199 IntDefaultHandler, // I2C4 Master and Slave 00200 IntDefaultHandler, // I2C5 Master and Slave 00201 IntDefaultHandler, // GPIO Port M 00202 IntDefaultHandler, // GPIO Port N 00203 IntDefaultHandler, // Quadrature Encoder 2 00204 0, // Reserved 00205 0, // Reserved 00206 IntDefaultHandler, // GPIO Port P (Summary or P0) 00207 IntDefaultHandler, // GPIO Port P1 00208 IntDefaultHandler, // GPIO Port P2 00209 IntDefaultHandler, // GPIO Port P3 00210 IntDefaultHandler, // GPIO Port P4 00211 IntDefaultHandler, // GPIO Port P5 00212 IntDefaultHandler, // GPIO Port P6 00213 IntDefaultHandler, // GPIO Port P7 00214 IntDefaultHandler, // GPIO Port Q (Summary or Q0) 00215 IntDefaultHandler, // GPIO Port Q1 00216 IntDefaultHandler, // GPIO Port Q2 00217 IntDefaultHandler, // GPIO Port Q3 00218 IntDefaultHandler, // GPIO Port Q4 00219 IntDefaultHandler, // GPIO Port Q5 00220 IntDefaultHandler, // GPIO Port Q6 00221 IntDefaultHandler, // GPIO Port Q7 00222 IntDefaultHandler, // GPIO Port R 00223 IntDefaultHandler, // GPIO Port S 00224 IntDefaultHandler, // PWM 1 Generator 0 00225 IntDefaultHandler, // PWM 1 Generator 1 00226 IntDefaultHandler, // PWM 1 Generator 2 00227 IntDefaultHandler, // PWM 1 Generator 3 00228 IntDefaultHandler // PWM 1 Fault 00229 }; 00230 #endif 00231 #ifdef TM4C1294XL 00232 __attribute__ ((section(".isr_vector"))) 00233 void (* const g_pfnVectors[])(void) = 00234 { 00235 (void (*)(void))((uint32_t)&_estack), // The initial stack pointer 00236 ResetISR, // The reset handler 00237 NmiSR, // The NMI handler 00238 FaultISR, // The hard fault handler 00239 IntDefaultHandler, // The MPU fault handler 00240 IntDefaultHandler, // The bus fault handler 00241 IntDefaultHandler, // The usage fault handler 00242 0, // Reserved 00243 0, // Reserved 00244 0, // Reserved 00245 0, // Reserved 00246 IntDefaultHandler, // SVCall handler 00247 IntDefaultHandler, // Debug monitor handler 00248 0, // Reserved 00249 IntDefaultHandler, // The PendSV handler 00250 IntDefaultHandler, // The SysTick handler 00251 IntDefaultHandler, // GPIO Port A 00252 IntDefaultHandler, // GPIO Port B 00253 IntDefaultHandler, // GPIO Port C 00254 IntDefaultHandler, // GPIO Port D 00255 IntDefaultHandler, // GPIO Port E 00256 IntDefaultHandler, // UART0 Rx and Tx 00257 IntDefaultHandler, // UART1 Rx and Tx 00258 IntDefaultHandler, // SSI0 Rx and Tx 00259 IntDefaultHandler, // I2C0 Master and Slave 00260 IntDefaultHandler, // PWM Fault 00261 IntDefaultHandler, // PWM Generator 0 00262 IntDefaultHandler, // PWM Generator 1 00263 IntDefaultHandler, // PWM Generator 2 00264 IntDefaultHandler, // Quadrature Encoder 0 00265 IntDefaultHandler, // ADC Sequence 0 00266 IntDefaultHandler, // ADC Sequence 1 00267 IntDefaultHandler, // ADC Sequence 2 00268 IntDefaultHandler, // ADC Sequence 3 00269 IntDefaultHandler, // Watchdog timer 00270 IntDefaultHandler, // Timer 0 subtimer A 00271 IntDefaultHandler, // Timer 0 subtimer B 00272 IntDefaultHandler, // Timer 1 subtimer A 00273 IntDefaultHandler, // Timer 1 subtimer B 00274 IntDefaultHandler, // Timer 2 subtimer A 00275 IntDefaultHandler, // Timer 2 subtimer B 00276 IntDefaultHandler, // Analog Comparator 0 00277 IntDefaultHandler, // Analog Comparator 1 00278 IntDefaultHandler, // Analog Comparator 2 00279 IntDefaultHandler, // System Control (PLL, OSC, BO) 00280 IntDefaultHandler, // FLASH Control 00281 IntDefaultHandler, // GPIO Port F 00282 IntDefaultHandler, // GPIO Port G 00283 IntDefaultHandler, // GPIO Port H 00284 IntDefaultHandler, // UART2 Rx and Tx 00285 IntDefaultHandler, // SSI1 Rx and Tx 00286 IntDefaultHandler, // Timer 3 subtimer A 00287 IntDefaultHandler, // Timer 3 subtimer B 00288 IntDefaultHandler, // I2C1 Master and Slave 00289 IntDefaultHandler, // CAN0 00290 IntDefaultHandler, // CAN1 00291 IntDefaultHandler, // Ethernet 00292 IntDefaultHandler, // Hibernate 00293 IntDefaultHandler, // USB0 00294 IntDefaultHandler, // PWM Generator 3 00295 IntDefaultHandler, // uDMA Software Transfer 00296 IntDefaultHandler, // uDMA Error 00297 IntDefaultHandler, // ADC1 Sequence 0 00298 IntDefaultHandler, // ADC1 Sequence 1 00299 IntDefaultHandler, // ADC1 Sequence 2 00300 IntDefaultHandler, // ADC1 Sequence 3 00301 IntDefaultHandler, // External Bus Interface 0 00302 IntDefaultHandler, // GPIO Port J 00303 IntDefaultHandler, // GPIO Port K 00304 IntDefaultHandler, // GPIO Port L 00305 IntDefaultHandler, // SSI2 Rx and Tx 00306 IntDefaultHandler, // SSI3 Rx and Tx 00307 IntDefaultHandler, // UART3 Rx and Tx 00308 IntDefaultHandler, // UART4 Rx and Tx 00309 IntDefaultHandler, // UART5 Rx and Tx 00310 IntDefaultHandler, // UART6 Rx and Tx 00311 IntDefaultHandler, // UART7 Rx and Tx 00312 IntDefaultHandler, // I2C2 Master and Slave 00313 IntDefaultHandler, // I2C3 Master and Slave 00314 IntDefaultHandler, // Timer 4 subtimer A 00315 IntDefaultHandler, // Timer 4 subtimer B 00316 IntDefaultHandler, // Timer 5 subtimer A 00317 IntDefaultHandler, // Timer 5 subtimer B 00318 IntDefaultHandler, // FPU 00319 0, // Reserved 00320 0, // Reserved 00321 IntDefaultHandler, // I2C4 Master and Slave 00322 IntDefaultHandler, // I2C5 Master and Slave 00323 IntDefaultHandler, // GPIO Port M 00324 IntDefaultHandler, // GPIO Port N 00325 0, // Reserved 00326 IntDefaultHandler, // Tamper 00327 IntDefaultHandler, // GPIO Port P (Summary or P0) 00328 IntDefaultHandler, // GPIO Port P1 00329 IntDefaultHandler, // GPIO Port P2 00330 IntDefaultHandler, // GPIO Port P3 00331 IntDefaultHandler, // GPIO Port P4 00332 IntDefaultHandler, // GPIO Port P5 00333 IntDefaultHandler, // GPIO Port P6 00334 IntDefaultHandler, // GPIO Port P7 00335 IntDefaultHandler, // GPIO Port Q (Summary or Q0) 00336 IntDefaultHandler, // GPIO Port Q1 00337 IntDefaultHandler, // GPIO Port Q2 00338 IntDefaultHandler, // GPIO Port Q3 00339 IntDefaultHandler, // GPIO Port Q4 00340 IntDefaultHandler, // GPIO Port Q5 00341 IntDefaultHandler, // GPIO Port Q6 00342 IntDefaultHandler, // GPIO Port Q7 00343 IntDefaultHandler, // GPIO Port R 00344 IntDefaultHandler, // GPIO Port S 00345 IntDefaultHandler, // SHA/MD5 0 00346 IntDefaultHandler, // AES 0 00347 IntDefaultHandler, // DES3DES 0 00348 IntDefaultHandler, // LCD Controller 0 00349 IntDefaultHandler, // Timer 6 subtimer A 00350 IntDefaultHandler, // Timer 6 subtimer B 00351 IntDefaultHandler, // Timer 7 subtimer A 00352 IntDefaultHandler, // Timer 7 subtimer B 00353 IntDefaultHandler, // I2C6 Master and Slave 00354 IntDefaultHandler, // I2C7 Master and Slave 00355 IntDefaultHandler, // HIM Scan Matrix Keyboard 0 00356 IntDefaultHandler, // One Wire 0 00357 IntDefaultHandler, // HIM PS/2 0 00358 IntDefaultHandler, // HIM LED Sequencer 0 00359 IntDefaultHandler, // HIM Consumer IR 0 00360 IntDefaultHandler, // I2C8 Master and Slave 00361 IntDefaultHandler, // I2C9 Master and Slave 00362 IntDefaultHandler // GPIO Port T 00363 }; 00364 #endif 00365 00366 //***************************************************************************** 00367 // 00368 // The following are constructs created by the linker, indicating where the 00369 // the "data" and "bss" segments reside in memory. The initializers for the 00370 // for the "data" segment resides immediately following the "text" segment. 00371 // 00372 //***************************************************************************** 00373 extern uint32_t _etext; 00374 extern uint32_t _data; 00375 extern uint32_t _edata; 00376 extern uint32_t _bss; 00377 extern uint32_t _ebss; 00378 extern void (*__preinit_array_start[])(void); 00379 extern void (*__preinit_array_end[])(void); 00380 extern void (*__init_array_start[])(void); 00381 extern void (*__init_array_end[])(void); 00382 00383 //***************************************************************************** 00384 // 00385 // This is the code that gets called when the processor first starts execution 00386 // following a reset event. Only the absolutely necessary set is performed, 00387 // after which the application supplied entry() routine is called. Any fancy 00388 // actions (such as making decisions based on the reset cause register, and 00389 // resetting the bits in that register) are left solely in the hands of the 00390 // application. 00391 // 00392 //***************************************************************************** 00393 void 00394 ResetISR(void) 00395 { 00396 uint32_t *pui32Src, *pui32Dest; 00397 uint32_t i, cnt; 00398 00399 // 00400 // Copy the data segment initializers from flash to SRAM. 00401 // 00402 pui32Src = &_etext; 00403 for(pui32Dest = &_data; pui32Dest < &_edata; ) 00404 { 00405 *pui32Dest++ = *pui32Src++; 00406 } 00407 00408 // 00409 // Zero fill the bss segment. 00410 // 00411 __asm(" ldr r0, =_bss\n" 00412 " ldr r1, =_ebss\n" 00413 " mov r2, #0\n" 00414 " .thumb_func\n" 00415 "zero_loop:\n" 00416 " cmp r0, r1\n" 00417 " it lt\n" 00418 " strlt r2, [r0], #4\n" 00419 " blt zero_loop"); 00420 00421 // 00422 // Enable the floating-point unit. This must be done here to handle the 00423 // case where main() uses floating-point and the function prologue saves 00424 // floating-point registers (which will fault if floating-point is not 00425 // enabled). Any configuration of the floating-point unit using DriverLib 00426 // APIs must be done here prior to the floating-point unit being enabled. 00427 // 00428 HWREG(NVIC_CPAC) = ((HWREG(NVIC_CPAC) & 00429 ~(NVIC_CPAC_CP10_M | NVIC_CPAC_CP11_M)) | 00430 NVIC_CPAC_CP10_FULL | NVIC_CPAC_CP11_FULL); 00431 00432 // 00433 // call any global c++ ctors 00434 // 00435 cnt = __preinit_array_end - __preinit_array_start; 00436 for (i = 0; i < cnt; i++) 00437 __preinit_array_start[i](); 00438 cnt = __init_array_end - __init_array_start; 00439 for (i = 0; i < cnt; i++) 00440 __init_array_start[i](); 00441 00442 // 00443 // Call the application's entry point. 00444 // 00445 main(); 00446 } 00447 00448 //***************************************************************************** 00449 // 00450 // This is the code that gets called when the processor receives a NMI. This 00451 // simply enters an infinite loop, preserving the system state for examination 00452 // by a debugger. 00453 // 00454 //***************************************************************************** 00455 static void 00456 NmiSR(void) 00457 { 00458 // 00459 // Enter an infinite loop. 00460 // 00461 while(1) 00462 { 00463 } 00464 } 00465 00466 //***************************************************************************** 00467 // 00468 // This is the code that gets called when the processor receives a fault 00469 // interrupt. This simply enters an infinite loop, preserving the system state 00470 // for examination by a debugger. 00471 // 00472 //***************************************************************************** 00473 static void 00474 FaultISR(void) 00475 { 00476 // 00477 // Enter an infinite loop. 00478 // 00479 while(1) 00480 { 00481 } 00482 } 00483 00484 //***************************************************************************** 00485 // 00486 // This is the code that gets called when the processor receives an unexpected 00487 // interrupt. This simply enters an infinite loop, preserving the system state 00488 // for examination by a debugger. 00489 // 00490 //***************************************************************************** 00491 static void 00492 IntDefaultHandler(void) 00493 { 00494 // 00495 // Go into an infinite loop. 00496 // 00497 while(1) 00498 { 00499 } 00500 } 00501 00502 /* syscall stuff */ 00503 void *__dso_handle = 0;