fmu-v6xrt: Tune ITCM function mapping

This commit is contained in:
Peter van der Perk 2024-01-04 16:13:15 +01:00 committed by David Sidrane
parent b24d9bf009
commit 0df7ee423f
1 changed files with 62 additions and 53 deletions

View File

@ -1,4 +1,66 @@
/* 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)
*(.text._ZN7Mavlink16update_rate_multEv)
@ -12,20 +74,16 @@
*(.text._ZN4uORB12Subscription9subscribeEv.part.0)
*(.text._ZN4uORB7Manager13orb_data_copyEPvS1_Rjb)
*(.text._ZN4uORB10DeviceNode5writeEP4filePKcj)
*(.text.exception_common)
*(.text.strcmp)
*(.text._ZN4uORB10DeviceNode7publishEPK12orb_metadataPvPKv)
*(.text._ZN4uORB12DeviceMaster19getDeviceNodeLockedEPK12orb_metadatah)
*(.text._Z12get_orb_meta6ORB_ID)
*(.text.nxsem_wait)
*(.text._ZN9ICM42688P12ProcessAccelERKyPKN20InvenSense_ICM42688P4FIFO4DATAEh)
*(.text.nxsem_post)
*(.text._ZN3px49WorkQueue3RunEv)
*(.text._ZN9ICM42688P11ProcessGyroERKyPKN20InvenSense_ICM42688P4FIFO4DATAEh)
*(.text._ZN4EKF23RunEv)
*(.text.imxrt_lpspi_exchange)
*(.text.imxrt_dmach_xfrsetup)
*(.text.arm_doirq)
*(.text._ZN7sensors10VehicleIMU7PublishEv)
*(.text._ZN4math17WelfordMeanVectorIfLj3EE6updateERKN6matrix6VectorIfLj3EEE)
*(.text._ZN7sensors10VehicleIMU10UpdateGyroEv)
@ -40,16 +98,11 @@
*(.text.perf_set_elapsed.part.0)
*(.text._ZN4uORB12Subscription6updateEPv)
*(.text._ZN12PX4Gyroscope10updateFIFOER18sensor_gyro_fifo_s)
*(.text.hrt_tim_isr)
*(.text.nxsig_timedwait)
*(.text.nxsem_foreachholder)
*(.text._ZN7sensors10VehicleIMU3RunEv)
*(.text.up_unblock_task)
*(.text.__aeabi_l2f)
*(.text._ZN39ControlAllocationSequentialDesaturation23computeDesaturationGainERKN6matrix6VectorIfLj16EEES4_)
*(.text.sched_unlock)
*(.text.pthread_mutex_timedlock)
*(.text.nxsem_restore_baseprio)
*(.text._ZN7sensors22VehicleAngularVelocity21FilterAngularVelocityEiPfi)
*(.text._ZN26MulticopterAttitudeControl3RunEv.part.0)
*(.text._ZN6device3SPI9_transferEPhS1_j)
@ -59,12 +112,10 @@
*(.text.fs_getfilep)
*(.text.MEM_DataCopy0_1)
*(.text._ZN7sensors19VehicleAcceleration3RunEv)
*(.text.sched_note_resume)
*(.text.uart_ioctl)
*(.text._ZN26MulticopterPositionControl3RunEv.part.0)
*(.text.pthread_mutex_take)
*(.text._ZN14ImuDownSampler6updateERKN9estimator9imuSampleE)
*(.text.irq_dispatch)
*(.text._ZN39ControlAllocationSequentialDesaturation6mixYawEv)
*(.text._ZN16ControlAllocator25publish_actuator_controlsEv.part.0)
*(.text._ZN9ICM42688P7RunImplEv)
@ -74,39 +125,27 @@
*(.text._ZN7sensors22VehicleAngularVelocity21SensorSelectionUpdateERKyb)
*(.text._ZN3px49WorkQueue3AddEPNS_8WorkItemE)
*(.text.wd_start)
*(.text.sq_rem)
*(.text.nxsem_add_holder_tcb)
*(.text.imxrt_dmaterminate)
*(.text.hrt_call_enter)
*(.text._ZN4EKF220PublishLocalPositionERKy)
*(.text._mav_finalize_message_chan_send)
*(.text.nxsched_add_blocked)
*(.text.arm_switchcontext)
*(.text._ZN3Ekf19fixCovarianceErrorsEb)
*(.text.nxsched_add_prioritized)
*(.text._ZN7sensors22VehicleAngularVelocity16ParametersUpdateEb)
*(.text.ioctl)
*(.text._ZN6events12SendProtocol6updateERKy)
*(.text.imxrt_dmach_interrupt)
*(.text.sched_lock)
*(.text._ZN6device3SPI8transferEPhS1_j)
*(.text._ZN27MavlinkStreamDistanceSensor4sendEv)
*(.text.hrt_call_internal)
*(.text.arm_svcall)
*(.text._ZN39ControlAllocationSequentialDesaturation18mixAirmodeDisabledEv)
*(.text._ZN7Mavlink15get_free_tx_bufEv)
*(.text.nx_poll)
*(.text.sched_note_suspend)
*(.text._ZN15MavlinkReceiver3runEv)
*(.text._ZN9ICM42688P18ProcessTemperatureEPKN20InvenSense_ICM42688P4FIFO4DATAEh)
*(.text._ZN15OutputPredictor19correctOutputStatesEyRKN6matrix10QuaternionIfEERKNS0_7Vector3IfEES8_S8_S8_)
*(.text._ZN3Ekf12predictStateERKN9estimator9imuSampleE)
*(.text._ZN3px46logger6Logger3runEv)
*(.text.nxsem_freecount0holder)
*(.text._ZN4uORB20SubscriptionInterval7updatedEv)
*(.text._ZN24MavlinkStreamCommandLong4sendEv)
*(.text._ZN9Commander3runEv)
*(.text.nxsem_release_holder)
*(.text._ZN3Ekf17predictCovarianceERKN9estimator9imuSampleE)
*(.text.wd_cancel)
*(.text._ZN7Sensors3RunEv)
@ -123,16 +162,13 @@
*(.text._ZN16ControlAllocator32publish_control_allocator_statusEi)
*(.text.__ieee754_atan2f)
*(.text._ZNK18DynamicSparseLayer3getEt)
*(.text.nxsched_remove_readytorun)
*(.text.__udivmoddi4)
*(.text._ZN8Failsafe17checkStateAndModeERKyRKN12FailsafeBase5StateERK16failsafe_flags_s)
*(.text._ZN29MavlinkStreamHygrometerSensor4sendEv)
*(.text.nxsched_remove_blocked)
*(.text.pthread_mutex_give)
*(.text._ZN3Ekf18controlFusionModesERKN9estimator9imuSampleE)
*(.text._ZN4cdev4CDev11poll_notifyEm)
*(.text.file_vioctl)
*(.text.wd_timer)
*(.text._ZN7sensors18VotedSensorsUpdate11sensorsPollER17sensor_combined_s)
*(.text.nxsig_nanosleep)
*(.text.imxrt_lpspi1select)
@ -148,7 +184,6 @@
*(.text.cdcuart_ioctl)
*(.text.cdcacm_sndpacket)
*(.text._ZN7sensors22VehicleAngularVelocity16SensorBiasUpdateEb)
*(.text.nxsched_merge_pending)
*(.text._ZN13MavlinkStream11update_dataEv)
*(.text._ZN7sensors18VotedSensorsUpdate21calcGyroInconsistencyEv)
*(.text.param_set_used)
@ -162,18 +197,14 @@
*(.text._ZN22MavlinkStreamCollision4sendEv)
*(.text.imxrt_lpi2c_transfer)
*(.text.uart_putxmitchar)
*(.text.nxsem_tickwait)
*(.text.clock_nanosleep)
*(.text.memcpy)
*(.text.up_release_pending)
*(.text.MEM_DataCopy0)
*(.text._ZN22MavlinkStreamGPSRawInt4sendEv)
*(.text.dq_rem)
*(.text._ZN15GyroCalibration3RunEv.part.0)
*(.text.imxrt_edma_interrupt)
*(.text._ZN7sensors18VotedSensorsUpdate22calcAccelInconsistencyEv)
*(.text._ZN24MavlinkStreamADSBVehicle4sendEv)
*(.text.nxsched_process_timer)
*(.text.sinf)
*(.text.hrt_call_after)
*(.text._ZN39ControlAllocationSequentialDesaturation8allocateEv)
@ -184,8 +215,6 @@
*(.text._ZN20MavlinkStreamESCInfo4sendEv)
*(.text.sem_post)
*(.text._ZN3px417ScheduledWorkItem15ScheduleDelayedEm)
*(.text.nxsched_resume_scheduler)
*(.text.nxsched_add_readytorun)
*(.text._ZN10FlightTaskC1Ev)
*(.text.usleep)
*(.text._ZN14FlightTaskAutoC1Ev)
@ -194,7 +223,6 @@
*(.text.imxrt_gpio_write)
*(.text._ZN3Ekf6updateEv)
*(.text.__ieee754_acosf)
*(.text.nxsem_wait_uninterruptible)
*(.text._ZN3Ekf20updateIMUBiasInhibitERKN9estimator9imuSampleE)
*(.text._ZN9Commander13dataLinkCheckEv)
*(.text._ZN17FlightModeManager10switchTaskE15FlightTaskIndex)
@ -204,10 +232,8 @@
*(.text._ZN18MavlinkStreamDebug4sendEv)
*(.text._ZN27MavlinkStreamServoOutputRawILi0EE4sendEv)
*(.text.asinf)
*(.text.nxsem_freeholder)
*(.text._ZN6matrix5EulerIfEC1ERKNS_3DcmIfEE)
*(.text._ZN4EKF227PublishInnovationTestRatiosERKy)
*(.text.imxrt_gpio3_16_31_interrupt)
*(.text._ZN4EKF213PublishStatusERKy)
*(.text._ZN4EKF226PublishInnovationVariancesERKy)
*(.text._ZN13land_detector23MulticopterLandDetector25_get_ground_contact_stateEv)
@ -222,7 +248,6 @@
*(.text._ZNK10ConstLayer3getEt)
*(.text.__aeabi_uldivmod)
*(.text.up_udelay)
*(.text.imxrt_usbinterrupt)
*(.text.up_idle)
*(.text._ZN20MavlinkStreamGPS2Raw4sendEv)
*(.text._ZN4EKF217UpdateCalibrationERKyRNS_19InFlightCalibrationERKN6matrix7Vector3IfEES8_fbb)
@ -268,11 +293,9 @@
*(.text._ZN36MavlinkStreamPositionTargetGlobalInt4sendEv)
*(.text._ZN4uORB12Subscription4copyEPv)
*(.text._ZN7sensors19VehicleAcceleration21SensorSelectionUpdateEb)
*(.text.nxsem_add_holder)
*(.text.crc_accumulate)
*(.text._ZN3px46logger6Logger13update_paramsEv)
*(.text._ZN11calibration14DeviceExternalEm)
*(.text.sq_addafter)
*(.text._ZN25MavlinkStreamHomePosition8get_sizeEv)
*(.text.imxrt_lpspi_modifyreg32)
*(.text._ZN7sensors19VehicleAcceleration16SensorBiasUpdateEb)
@ -280,7 +303,6 @@
*(.text._ZNK6matrix6MatrixIfLj3ELj1EEmlEf)
*(.text._ZN6matrix5EulerIfEC1ERKNS_10QuaternionIfEE)
*(.text.imxrt_queuedtd)
*(.text.nxsched_suspend_scheduler)
*(.text._ZN27MavlinkStreamDistanceSensor8get_sizeEv)
*(.text._ZN3Ekf16fuseVelPosHeightEffi)
*(.text._ZN3Ekf23controlBaroHeightFusionEv)
@ -294,7 +316,6 @@
*(.text._ZN7sensors14VehicleAirData3RunEv)
*(.text.perf_count)
*(.text._ZN3Ekf16controlMagFusionEv)
*(.text.nxsem_clockwait)
*(.text.pthread_sem_give)
*(.text._ZN7sensors10VehicleIMU16ParametersUpdateEb)
*(.text._ZN30MavlinkStreamUTMGlobalPosition4sendEv)
@ -302,13 +323,11 @@
*(.text._ZN12I2CSPIDriverI9ICM42688PE3RunEv)
*(.text._ZN17ObstacleAvoidanceC1EP12ModuleParams)
*(.text.imxrt_epcomplete.constprop.0)
*(.text.imxrt_tcd_free)
*(.text._ZNK6matrix6MatrixIfLj3ELj1EEmiERKS1_)
*(.text._ZN9Commander30handleModeIntentionAndFailsafeEv)
*(.text.perf_event_count)
*(.text._ZN4EKF215PublishAttitudeERKy)
*(.text._ZN19MavlinkStreamRawRpm8get_sizeEv)
*(.text.nxsem_trywait)
*(.text._ZNK3px46atomicIbE4loadEv)
*(.text._ZN29MavlinkStreamHygrometerSensor8get_sizeEv)
*(.text.pthread_mutex_add)
@ -332,7 +351,6 @@
*(.text._ZN3Ekf31checkVerticalAccelerationHealthERKN9estimator9imuSampleE)
*(.text._ZN6matrix6MatrixIfLj3ELj1EEC1ERKS1_)
*(.text.udp_pollsetup)
*(.text.nxsem_timeout)
*(.text._ZL14timer_callbackPv)
*(.text._ZN3Ekf4fuseERKN6matrix6VectorIfLj23EEEf)
*(.text._ZN13land_detector23MulticopterLandDetector22_set_hysteresis_factorEi)
@ -396,7 +414,6 @@
*(.text._ZN17MavlinkLogHandler4sendEv)
*(.text._ZN7control10SuperBlock5setDtEf)
*(.text._ZN29MavlinkStreamMountOrientation8get_sizeEv)
*(.text.board_autoled_on)
*(.text._ZN5PX4IO13io_get_statusEv)
*(.text._ZN26MulticopterAttitudeControl3RunEv)
*(.text._ZThn16_N31ActuatorEffectivenessMultirotor22getEffectivenessMatrixERN21ActuatorEffectiveness13ConfigurationE25EffectivenessUpdateReason)
@ -432,7 +449,6 @@
*(.text._ZN36MavlinkStreamGimbalDeviceSetAttitude4sendEv)
*(.text._ZN16PreFlightChecker6updateEfRK23estimator_innovations_s)
*(.text._ZN4math13expo_deadzoneIfEEKT_RS2_S3_S3_.isra.0)
*(.text.nxsched_get_tcb)
*(.text._ZN19StickAccelerationXYC1EP12ModuleParams)
*(.text.imxrt_epsubmit)
*(.text._ZN15PositionControl6updateEf)
@ -455,7 +471,6 @@
*(.text._ZN6Sticks25checkAndUpdateStickInputsEv)
*(.text.atan2f)
*(.text._ZN23MavlinkStreamRCChannels4sendEv)
*(.text.sq_remfirst)
*(.text._ZN4EKF221UpdateExtVisionSampleER17ekf2_timestamps_s)
*(.text.imxrt_dmach_stop)
*(.text._ZN9Commander16handleAutoDisarmEv)
@ -488,7 +503,6 @@
*(.text._ZN33FlightTaskManualAltitudeSmoothVelC1Ev)
*(.text.powf)
*(.text._ZN4EKF217PublishEventFlagsERKy)
*(.text.sq_remafter)
*(.text._ZN17FlightTaskDescend6updateEv)
*(.text.imxrt_iomux_configure)
*(.text.hrt_store_absolute_time)
@ -593,7 +607,6 @@
*(.text._ZN20MavlinkStreamESCInfo8get_sizeEv)
*(.text._ZNK6matrix6VectorIfLj2EE4normEv)
*(.text._Z15arm_auth_updateyb)
*(.text.imxrt_lpi2c_isr)
*(.text._ZN3LED5ioctlEP4fileim)
*(.text._ZNK3px46logger9LogWriter20had_file_write_errorEv)
*(.text._ZN29MavlinkStreamLocalPositionNED4sendEv)
@ -627,13 +640,11 @@
*(.text._ZN4EKF216PublishEvPosBiasERKy)
*(.text._ZN21MavlinkStreamAttitude8get_sizeEv)
*(.text._ZThn16_N7sensors19VehicleAcceleration3RunEv)
*(.text.imxrt_timerisr)
*(.text._ZN3Ekf24controlRangeHeightFusionEv)
*(.text._ZN33MavlinkStreamTimeEstimateToTarget4sendEv)
*(.text._ZN6matrix6MatrixIfLj3ELj1EE6setAllEf)
*(.text._ZN12ModuleParamsD1Ev)
*(.text._ZN3Ekf20controlFakeHgtFusionEv)
*(.text.sq_addlast)
*(.text.imxrt_reqcomplete)
*(.text._ZNK6matrix7Vector3IfEmlEf)
*(.text._ZN18ZeroVelocityUpdate6updateER3EkfRKN9estimator9imuSampleE)
@ -653,7 +664,6 @@
*(.text._ZN13BatteryChecks14checkAndReportERK7ContextR6Report)
*(.text._ZN18DataValidatorGroup16get_sensor_stateEj)
*(.text.uart_xmitchars_done)
*(.text.nxsched_get_files)
*(.text._ZN4EKF225PublishYawEstimatorStatusERKy)
*(.text.sin)
*(.text._ZN16PreFlightChecker27preFlightCheckVertVelFailedERK23estimator_innovations_sf)
@ -702,7 +712,6 @@
*(.text._ZThn8_N3ADC3RunEv)
*(.text._ZN11StickTiltXYC1EP12ModuleParams)
*(.text._ZN12SafetyButton3RunEv)
*(.text.arm_ack_irq)
*(.text._ZN6BMP38811set_op_modeEh)
*(.text._ZN3GPS8callbackE15GPSCallbackTypePviS1_)
*(.text._ZN13AnalogBattery19get_current_channelEv)