mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
v6x-rt: Split ITCM static and auto-generated functions
This commit is contained in:
parent
d5b66cac2c
commit
8817f59108
@ -1,65 +1,3 @@
|
||||
/* Static */
|
||||
*(.text.arm_ack_irq)
|
||||
*(.text.arm_doirq)
|
||||
*(.text.arm_svcall)
|
||||
*(.text.arm_switchcontext)
|
||||
*(.text.board_autoled_on)
|
||||
*(.text.clock_timer)
|
||||
*(.text.exception_common)
|
||||
*(.text.hrt_absolute_time)
|
||||
*(.text.hrt_tim_isr)
|
||||
*(.text.imxrt_configwaitints)
|
||||
*(.text.imxrt_dma_callback)
|
||||
*(.text.imxrt_dmach_interrupt)
|
||||
*(.text.imxrt_dmaterminate)
|
||||
*(.text.imxrt_edma_interrupt)
|
||||
*(.text.imxrt_endwait)
|
||||
*(.text.imxrt_gpio3_16_31_interrupt)
|
||||
*(.text.imxrt_interrupt)
|
||||
*(.text.imxrt_lpi2c_isr)
|
||||
*(.text.imxrt_recvdma)
|
||||
*(.text.imxrt_tcd_free)
|
||||
*(.text.imxrt_timerisr)
|
||||
*(.text.imxrt_usbinterrupt)
|
||||
*(.text.irq_dispatch)
|
||||
*(.text.memcpy)
|
||||
*(.text.nxsched_add_blocked)
|
||||
*(.text.nxsched_add_prioritized)
|
||||
*(.text.nxsched_add_readytorun)
|
||||
*(.text.nxsched_get_files)
|
||||
*(.text.nxsched_get_tcb)
|
||||
*(.text.nxsched_merge_pending)
|
||||
*(.text.nxsched_process_timer)
|
||||
*(.text.nxsched_remove_blocked)
|
||||
*(.text.nxsched_remove_readytorun)
|
||||
*(.text.nxsched_resume_scheduler)
|
||||
*(.text.nxsched_suspend_scheduler)
|
||||
*(.text.nxsem_add_holder)
|
||||
*(.text.nxsem_add_holder_tcb)
|
||||
*(.text.nxsem_clockwait)
|
||||
*(.text.nxsem_foreachholder)
|
||||
*(.text.nxsem_freecount0holder)
|
||||
*(.text.nxsem_freeholder)
|
||||
*(.text.nxsem_post)
|
||||
*(.text.nxsem_release_holder)
|
||||
*(.text.nxsem_restore_baseprio)
|
||||
*(.text.nxsem_tickwait)
|
||||
*(.text.nxsem_timeout)
|
||||
*(.text.nxsem_trywait)
|
||||
*(.text.nxsem_wait)
|
||||
*(.text.nxsem_wait_uninterruptible)
|
||||
*(.text.nxsig_timedwait)
|
||||
*(.text.sched_lock)
|
||||
*(.text.sched_note_resume)
|
||||
*(.text.sched_note_suspend)
|
||||
*(.text.sched_unlock)
|
||||
*(.text.sq_addafter)
|
||||
*(.text.sq_addlast)
|
||||
*(.text.sq_rem)
|
||||
*(.text.sq_remafter)
|
||||
*(.text.sq_remfirst)
|
||||
*(.text.uart_connected)
|
||||
*(.text.wd_timer)
|
||||
/* Auto-generated */
|
||||
*(.text._ZN4uORB7Manager27orb_add_internal_subscriberE6ORB_IDhPj)
|
||||
*(.text._ZN13MavlinkStream6updateERKy)
|
||||
@ -70,11 +8,9 @@
|
||||
*(.text._ZN22MulticopterRateControl3RunEv.part.0)
|
||||
*(.text._ZN7Mavlink9task_mainEiPPc)
|
||||
*(.text._ZN7sensors22VehicleAngularVelocity3RunEv)
|
||||
*(.text.memset)
|
||||
*(.text._ZN4uORB12Subscription9subscribeEv.part.0)
|
||||
*(.text._ZN4uORB7Manager13orb_data_copyEPvS1_Rjb)
|
||||
*(.text._ZN4uORB10DeviceNode5writeEP4filePKcj)
|
||||
*(.text.strcmp)
|
||||
*(.text._ZN4uORB10DeviceNode7publishEPK12orb_metadataPvPKv)
|
||||
*(.text._ZN4uORB12DeviceMaster19getDeviceNodeLockedEPK12orb_metadatah)
|
||||
*(.text._Z12get_orb_meta6ORB_ID)
|
||||
@ -82,15 +18,12 @@
|
||||
*(.text._ZN3px49WorkQueue3RunEv)
|
||||
*(.text._ZN9ICM42688P11ProcessGyroERKyPKN20InvenSense_ICM42688P4FIFO4DATAEh)
|
||||
*(.text._ZN4EKF23RunEv)
|
||||
*(.text.imxrt_lpspi_exchange)
|
||||
*(.text.imxrt_dmach_xfrsetup)
|
||||
*(.text._ZN7sensors10VehicleIMU7PublishEv)
|
||||
*(.text._ZN4math17WelfordMeanVectorIfLj3EE6updateERKN6matrix6VectorIfLj3EEE)
|
||||
*(.text._ZN7sensors10VehicleIMU10UpdateGyroEv)
|
||||
*(.text._ZN9ICM42688P8FIFOReadERKyh)
|
||||
*(.text._ZN3Ekf20controlGravityFusionERKN9estimator9imuSampleE)
|
||||
*(.text._ZN16PX4Accelerometer10updateFIFOER19sensor_accel_fifo_s)
|
||||
*(.text.up_block_task)
|
||||
*(.text._ZN7sensors22VehicleAngularVelocity19CalibrateAndPublishERKyRKN6matrix7Vector3IfEES7_)
|
||||
*(.text._ZN4uORB12Subscription10advertisedEv)
|
||||
*(.text._ZNK15AttitudeControl6updateERKN6matrix10QuaternionIfEE)
|
||||
@ -99,7 +32,6 @@
|
||||
*(.text._ZN4uORB12Subscription6updateEPv)
|
||||
*(.text._ZN12PX4Gyroscope10updateFIFOER18sensor_gyro_fifo_s)
|
||||
*(.text._ZN7sensors10VehicleIMU3RunEv)
|
||||
*(.text.up_unblock_task)
|
||||
*(.text.__aeabi_l2f)
|
||||
*(.text._ZN39ControlAllocationSequentialDesaturation23computeDesaturationGainERKN6matrix6VectorIfLj16EEES4_)
|
||||
*(.text.pthread_mutex_timedlock)
|
||||
@ -121,16 +53,12 @@
|
||||
*(.text._ZN9ICM42688P7RunImplEv)
|
||||
*(.text._ZN4uORB12Subscription9subscribeEv)
|
||||
*(.text.param_get)
|
||||
*(.text._do_memcpy)
|
||||
*(.text._ZN7sensors22VehicleAngularVelocity21SensorSelectionUpdateERKyb)
|
||||
*(.text._ZN3px49WorkQueue3AddEPNS_8WorkItemE)
|
||||
*(.text.wd_start)
|
||||
*(.text.hrt_call_enter)
|
||||
*(.text._ZN4EKF220PublishLocalPositionERKy)
|
||||
*(.text._mav_finalize_message_chan_send)
|
||||
*(.text._ZN3Ekf19fixCovarianceErrorsEb)
|
||||
*(.text._ZN7sensors22VehicleAngularVelocity16ParametersUpdateEb)
|
||||
*(.text.ioctl)
|
||||
*(.text._ZN6events12SendProtocol6updateERKy)
|
||||
*(.text._ZN6device3SPI8transferEPhS1_j)
|
||||
*(.text._ZN27MavlinkStreamDistanceSensor4sendEv)
|
||||
|
||||
@ -0,0 +1,72 @@
|
||||
/* Static */
|
||||
*(.text.arm_ack_irq)
|
||||
*(.text.arm_doirq)
|
||||
*(.text.arm_svcall)
|
||||
*(.text.arm_switchcontext)
|
||||
*(.text.board_autoled_on)
|
||||
*(.text.clock_timer)
|
||||
*(.text.exception_common)
|
||||
*(.text.hrt_absolute_time)
|
||||
*(.text.hrt_call_enter)
|
||||
*(.text.hrt_tim_isr)
|
||||
*(.text.imxrt_configwaitints)
|
||||
*(.text.imxrt_dma_callback)
|
||||
*(.text.imxrt_dmach_interrupt)
|
||||
*(.text.imxrt_dmach_xfrsetup)
|
||||
*(.text.imxrt_dmaterminate)
|
||||
*(.text.imxrt_edma_interrupt)
|
||||
*(.text.imxrt_endwait)
|
||||
*(.text.imxrt_gpio3_16_31_interrupt)
|
||||
*(.text.imxrt_interrupt)
|
||||
*(.text.imxrt_lpi2c_isr)
|
||||
*(.text.imxrt_lpspi_exchange)
|
||||
*(.text.imxrt_recvdma)
|
||||
*(.text.imxrt_tcd_free)
|
||||
*(.text.imxrt_timerisr)
|
||||
*(.text.imxrt_usbinterrupt)
|
||||
*(.text.irq_dispatch)
|
||||
*(.text.ioctl)
|
||||
*(.text.memcpy)
|
||||
*(.text.memset)
|
||||
*(.text.nxsched_add_blocked)
|
||||
*(.text.nxsched_add_prioritized)
|
||||
*(.text.nxsched_add_readytorun)
|
||||
*(.text.nxsched_get_files)
|
||||
*(.text.nxsched_get_tcb)
|
||||
*(.text.nxsched_merge_pending)
|
||||
*(.text.nxsched_process_timer)
|
||||
*(.text.nxsched_remove_blocked)
|
||||
*(.text.nxsched_remove_readytorun)
|
||||
*(.text.nxsched_resume_scheduler)
|
||||
*(.text.nxsched_suspend_scheduler)
|
||||
*(.text.nxsem_add_holder)
|
||||
*(.text.nxsem_add_holder_tcb)
|
||||
*(.text.nxsem_clockwait)
|
||||
*(.text.nxsem_foreachholder)
|
||||
*(.text.nxsem_freecount0holder)
|
||||
*(.text.nxsem_freeholder)
|
||||
*(.text.nxsem_post)
|
||||
*(.text.nxsem_release_holder)
|
||||
*(.text.nxsem_restore_baseprio)
|
||||
*(.text.nxsem_tickwait)
|
||||
*(.text.nxsem_timeout)
|
||||
*(.text.nxsem_trywait)
|
||||
*(.text.nxsem_wait)
|
||||
*(.text.nxsem_wait_uninterruptible)
|
||||
*(.text.nxsig_timedwait)
|
||||
*(.text.sched_lock)
|
||||
*(.text.sched_note_resume)
|
||||
*(.text.sched_note_suspend)
|
||||
*(.text.sched_unlock)
|
||||
*(.text.strcmp)
|
||||
*(.text.sq_addafter)
|
||||
*(.text.sq_addlast)
|
||||
*(.text.sq_rem)
|
||||
*(.text.sq_remafter)
|
||||
*(.text.sq_remfirst)
|
||||
*(.text.uart_connected)
|
||||
*(.text.up_block_task)
|
||||
*(.text.up_unblock_task)
|
||||
*(.text.wd_timer)
|
||||
*(.text.wd_start)
|
||||
*(.text._do_memcpy)
|
||||
@ -83,6 +83,7 @@ SECTIONS
|
||||
_sitcmfuncs = ABSOLUTE(.);
|
||||
FILL(0xFF)
|
||||
. = 0x40 ;
|
||||
INCLUDE "itcm_static_functions.ld"
|
||||
INCLUDE "itcm_functions_includes.ld"
|
||||
. = ALIGN(8);
|
||||
_eitcmfuncs = ABSOLUTE(.);
|
||||
|
||||
@ -266,7 +266,7 @@ else()
|
||||
-fno-exceptions
|
||||
-fno-rtti
|
||||
-Wl,--script=${NUTTX_CONFIG_DIR_CYG}/scripts/${SCRIPT_PREFIX}script.ld
|
||||
-L${NUTTX_CONFIG_DIR_CYG}/scripts/${SCRIPT_PREFIX}
|
||||
-L${NUTTX_CONFIG_DIR_CYG}/scripts
|
||||
-Wl,-Map=${PX4_CONFIG}.map
|
||||
-Wl,--warn-common
|
||||
-Wl,--gc-sections
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user