feat(boards): Update ITCM mapping for NuttX 12.12

NuttX 12.12 changed symbols for certain calls or inlined them.
This commit is contained in:
Peter van der Perk
2026-03-17 09:58:51 +01:00
parent 6c8b20d3c6
commit 0f44a98291
7 changed files with 110 additions and 114 deletions
@@ -40,8 +40,7 @@
*(.text._ZN15OutputPredictor21calculateOutputStatesEyRKN6matrix7Vector3IfEEfS4_f)
*(.text._ZN7sensors18VotedSensorsUpdate7imuPollER17sensor_combined_s)
*(.text._Z9rotate_3i8RotationRsS0_S0_)
*(.text.fs_getfilep)
*(.text.MEM_DataCopy0_1)
*(.text.file_get2)
*(.text._ZN7sensors19VehicleAcceleration3RunEv)
*(.text.uart_ioctl)
*(.text._ZN26MulticopterPositionControl3RunEv.part.0)
@@ -63,7 +62,6 @@
*(.text.hrt_call_internal)
*(.text._ZN39ControlAllocationSequentialDesaturation18mixAirmodeDisabledEv)
*(.text._ZN7Mavlink15get_free_tx_bufEv)
*(.text.nx_poll)
*(.text._ZN15MavlinkReceiver3runEv)
*(.text._ZN9ICM42688P18ProcessTemperatureEPKN20InvenSense_ICM42688P4FIFO4DATAEh)
*(.text._ZN15OutputPredictor19correctOutputStatesEyRKN6matrix10QuaternionIfEERKNS0_7Vector3IfEERK9LatLonAltS8_S8_)
@@ -80,10 +78,8 @@
*(.text._ZN13land_detector12LandDetector3RunEv)
*(.text.sched_idletask)
*(.text.atanf)
*(.text.uart_write)
*(.text.pthread_mutex_unlock)
*(.text.__ieee754_asinf)
*(.text.MEM_DataCopy0_2)
*(.text._ZN20MavlinkCommandSender13check_timeoutE17mavlink_channel_t)
*(.text._ZN16ControlAllocator32publish_control_allocator_statusEi)
*(.text.__ieee754_atan2f)
@@ -100,7 +96,6 @@
*(.text.sem_wait)
*(.text.perf_count_interval.part.0)
*(.text._ZN16ControlAllocator37update_effectiveness_matrix_if_neededE25EffectivenessUpdateReason)
*(.text.MEM_LongCopyJump)
*(.text.px4_arch_adc_sample)
*(.text._ZN31MulticopterHoverThrustEstimator3RunEv)
*(.text._ZNK17ControlAllocation20clipActuatorSetpointERN6matrix6VectorIfLj16EEE)
@@ -122,10 +117,7 @@
*(.text.imxrt_lpi2c_transfer)
*(.text.uart_putxmitchar)
*(.text.clock_nanosleep)
*(.text.up_release_pending)
*(.text.MEM_DataCopy0)
*(.text._ZN22MavlinkStreamGPSRawInt4sendEv)
*(.text.dq_rem)
*(.text._ZN15GyroCalibration3RunEv.part.0)
*(.text._ZN7sensors18VotedSensorsUpdate22calcAccelInconsistencyEv)
*(.text._ZN24MavlinkStreamADSBVehicle4sendEv)
@@ -235,7 +227,6 @@
*(.text._ZN7sensors14VehicleAirData3RunEv)
*(.text.perf_count)
*(.text._ZN3Ekf16controlMagFusionERKN9estimator9imuSampleE)
*(.text.pthread_sem_give)
*(.text._ZN7sensors10VehicleIMU16ParametersUpdateEb)
*(.text._ZN4uORB20SubscriptionInterval4copyEPv)
*(.text._ZN12I2CSPIDriverI9ICM42688PE3RunEv)
@@ -249,7 +240,6 @@
*(.text._ZN29MavlinkStreamHygrometerSensor8get_sizeEv)
*(.text.pthread_mutex_add)
*(.text._ZN12HomePosition6updateEbb)
*(.text.poll_fdsetup)
*(.text._ZN15PositionControl20_accelerationControlEv)
*(.text._ZN3Ekf19controlHeightFusionERKN9estimator9imuSampleE)
*(.text._ZN9Commander19control_status_ledsEbh)
@@ -271,12 +261,10 @@
*(.text._ZN3Ekf4fuseERKN6matrix6VectorIfLj24EEEf)
*(.text.nxsem_wait_irq)
*(.text._ZN20MavlinkCommandSender4lockEv)
*(.text.MEM_LongCopyEnd)
*(.text._ZThn24_N16ControlAllocator3RunEv)
*(.text._ZN15TimestampedListIN20MavlinkCommandSender14command_item_sELi3EE8get_nextEv)
*(.text._ZNK3Ekf21get_ekf_lpos_accuracyEPfS0_)
*(.text._ZN17FlightModeManager17start_flight_taskEv)
*(.text.MEM_DataCopyBytes)
*(.text._ZN29MavlinkStreamLocalPositionNED8get_sizeEv)
*(.text._ZN6SticksC1EP12ModuleParams)
*(.text._ZN27MavlinkStreamServoOutputRawILi1EE4sendEv)
@@ -366,7 +354,6 @@
*(.text.vsprintf_internal.constprop.0)
*(.text.udp_pollteardown)
*(.text._ZN12MixingOutput6updateEv)
*(.text.clock_abstime2ticks)
*(.text._ZN13BatteryStatus3RunEv)
*(.text._ZN32MavlinkStreamGimbalManagerStatus8get_sizeEv)
*(.text._ZN10FlightTask15_resetSetpointsEv)
@@ -388,7 +375,6 @@
*(.text._ZNK3px46logger9LogWriter10is_startedENS0_7LogTypeE)
*(.text._ZN24FlightTaskManualAltitudeD1Ev)
*(.text._Z35px4_indicate_external_reset_lockout16LockoutComponentb)
*(.text.uart_pollnotify)
*(.text._ZN4EKF215PublishBaroBiasERKy)
*(.text._ZN4EKF221UpdateGyroCalibrationERKy)
*(.text._ZN6matrix9constrainIfLj3ELj1EEENS_6MatrixIT_XT0_EXT1_EEERKS3_S2_S2_)
@@ -426,7 +412,6 @@
*(.text._ZN10FlightTask37_evaluateVehicleLocalPositionSetpointEv)
*(.text._ZN4uORB12Subscription11unsubscribeEv)
*(.text.net_lock)
*(.text.clock_time2ticks)
*(.text._ZN12FailsafeBase16updateStartDelayERKyb)
*(.text._ZN23MavlinkStreamStatustext8get_sizeEv)
*(.text._ZN11calibration13Accelerometer13set_device_idEm)
@@ -438,7 +423,6 @@
*(.text.nxsig_timeout)
*(.text._ZN11RateControl19setSaturationStatusERKN6matrix7Vector3IbEES4_)
*(.text._ZN3Ekf17measurementUpdateERN6matrix6VectorIfLj24EEERKS2_ff)
*(.text.dq_addlast)
*(.text._ZN19MavlinkStreamVFRHUD4sendEv)
*(.text.hrt_call_reschedule)
*(.text.nxsem_boost_priority)
@@ -486,7 +470,6 @@
*(.text._ZN22MavlinkStreamGPSStatus8get_sizeEv)
*(.text.nxsem_destroyholder)
*(.text.psock_udp_cansend)
*(.text.MEM_DataCopy2_2)
*(.text._ZN10FlightTask8activateERK21trajectory_setpoint_s)
*(.text.sock_file_poll)
*(.text._ZN10Ringbuffer9pop_frontEPhj)
@@ -496,7 +479,6 @@
*(.text.nxsem_canceled)
*(.text._ZN10FlightTask21getTrajectorySetpointEv)
*(.text.imxrt_dmach_getcount)
*(.text.sem_clockwait)
*(.text.inet_poll)
*(.text._ZN6BMP3887collectEv)
*(.text._ZNK15PositionControl24getLocalPositionSetpointER33vehicle_local_position_setpoint_s)
@@ -577,7 +559,6 @@
*(.text.up_flush_dcache)
*(.text._ZN15GyroCalibration3RunEv)
*(.text.mavlink_start_uart_send)
*(.text.MEM_DataCopy2)
*(.text._ZNK9Commander14getPrearmStateEv)
*(.text._ZN15EstimatorChecks14checkAndReportERK7ContextR6Report)
*(.text._ZN28FlightTaskManualAccelerationD1Ev)
@@ -614,7 +595,6 @@
*(.text._ZN12SafetyButton19CheckPairingRequestEb)
*(.text.imxrt_dma_txavailable)
*(.text.perf_set_elapsed)
*(.text.pthread_sem_take)
*(.text._ZN8StickYawD1Ev)
*(.text._Z15blink_msg_statev)
*(.text._ZN19AccelerometerChecks14checkAndReportERK7ContextR6Report)
@@ -660,7 +640,6 @@
*(.text._ZN15EstimatorChecks15checkSensorBiasERK7ContextR6Report8NavModes)
*(.text._ZN20ImuConsistencyChecks14checkAndReportERK7ContextR6Report)
*(.text._ZN28MavlinkStreamGpsGlobalOrigin8get_sizeEv)
*(.text.MEM_DataCopy2_1)
*(.text._ZN6BMP3887measureEv)
*(.text._ZN4EKF217PublishRngHgtBiasERKy)
*(.text._ZN36MavlinkStreamPositionTargetGlobalInt8get_sizeEv)
@@ -2,8 +2,6 @@
*(.text.arm_ack_irq)
*(.text.arm_doirq)
*(.text.arm_svcall)
*(.text.arm_switchcontext)
*(.text.clock_timer)
*(.text.exception_common)
*(.text.flexio_irq_handler)
*(.text.hrt_absolute_time)
@@ -42,17 +40,16 @@
*(.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_fdlist)
*(.text.nxsched_get_fdlist_from_tcb)
*(.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.nxsched_switch_context)
*(.text.nxsem_add_holder)
*(.text.nxsem_add_holder_tcb)
*(.text.nxsem_clockwait)
@@ -74,20 +71,16 @@
*(.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.work_thread)
*(.text.work_queue)
*(.text._do_memcpy)
*(.text.memcpy)
/* Tropic Eth tune */
/* Eth tune */
*(.text.devif_poll)
*(.text.devif_poll_tcp_connections)
*(.text.tcp_poll)
@@ -114,7 +107,6 @@
*(.text.net_ipv4addr_copy) /* itcm-check-ignore */
*(.text.net_ipv4addr_broadcast) /* itcm-check-ignore */
*(.text.wd_start)
*(.text.arp_arpin)
*(.text.ipv4_input)
*(.text.work_thread)
*(.text.work_queue)
@@ -40,8 +40,7 @@
*(.text._ZN15OutputPredictor21calculateOutputStatesEyRKN6matrix7Vector3IfEEfS4_f)
*(.text._ZN7sensors18VotedSensorsUpdate7imuPollER17sensor_combined_s)
*(.text._Z9rotate_3i8RotationRsS0_S0_)
*(.text.fs_getfilep)
*(.text.MEM_DataCopy0_1)
*(.text.file_get2)
*(.text._ZN7sensors19VehicleAcceleration3RunEv)
*(.text.uart_ioctl)
*(.text._ZN26MulticopterPositionControl3RunEv.part.0)
@@ -63,7 +62,6 @@
*(.text.hrt_call_internal)
*(.text._ZN39ControlAllocationSequentialDesaturation18mixAirmodeDisabledEv)
*(.text._ZN7Mavlink15get_free_tx_bufEv)
*(.text.nx_poll)
*(.text._ZN15MavlinkReceiver3runEv)
*(.text._ZN9ICM42688P18ProcessTemperatureEPKN20InvenSense_ICM42688P4FIFO4DATAEh)
*(.text._ZN15OutputPredictor19correctOutputStatesEyRKN6matrix10QuaternionIfEERKNS0_7Vector3IfEERK9LatLonAltS8_S8_)
@@ -80,10 +78,8 @@
*(.text._ZN13land_detector12LandDetector3RunEv)
*(.text.sched_idletask)
*(.text.atanf)
*(.text.uart_write)
*(.text.pthread_mutex_unlock)
*(.text.__ieee754_asinf)
*(.text.MEM_DataCopy0_2)
*(.text._ZN20MavlinkCommandSender13check_timeoutE17mavlink_channel_t)
*(.text._ZN16ControlAllocator32publish_control_allocator_statusEi)
*(.text.__ieee754_atan2f)
@@ -100,7 +96,6 @@
*(.text.sem_wait)
*(.text.perf_count_interval.part.0)
*(.text._ZN16ControlAllocator37update_effectiveness_matrix_if_neededE25EffectivenessUpdateReason)
*(.text.MEM_LongCopyJump)
*(.text.px4_arch_adc_sample)
*(.text._ZN31MulticopterHoverThrustEstimator3RunEv)
*(.text._ZNK17ControlAllocation20clipActuatorSetpointERN6matrix6VectorIfLj16EEE)
@@ -122,10 +117,7 @@
*(.text.imxrt_lpi2c_transfer)
*(.text.uart_putxmitchar)
*(.text.clock_nanosleep)
*(.text.up_release_pending)
*(.text.MEM_DataCopy0)
*(.text._ZN22MavlinkStreamGPSRawInt4sendEv)
*(.text.dq_rem)
*(.text._ZN15GyroCalibration3RunEv.part.0)
*(.text._ZN7sensors18VotedSensorsUpdate22calcAccelInconsistencyEv)
*(.text._ZN24MavlinkStreamADSBVehicle4sendEv)
@@ -235,7 +227,6 @@
*(.text._ZN7sensors14VehicleAirData3RunEv)
*(.text.perf_count)
*(.text._ZN3Ekf16controlMagFusionERKN9estimator9imuSampleE)
*(.text.pthread_sem_give)
*(.text._ZN7sensors10VehicleIMU16ParametersUpdateEb)
*(.text._ZN4uORB20SubscriptionInterval4copyEPv)
*(.text._ZN12I2CSPIDriverI9ICM42688PE3RunEv)
@@ -249,7 +240,6 @@
*(.text._ZN29MavlinkStreamHygrometerSensor8get_sizeEv)
*(.text.pthread_mutex_add)
*(.text._ZN12HomePosition6updateEbb)
*(.text.poll_fdsetup)
*(.text._ZN15PositionControl20_accelerationControlEv)
*(.text._ZN3Ekf19controlHeightFusionERKN9estimator9imuSampleE)
*(.text._ZN9Commander19control_status_ledsEbh)
@@ -271,12 +261,10 @@
*(.text._ZN3Ekf4fuseERKN6matrix6VectorIfLj24EEEf)
*(.text.nxsem_wait_irq)
*(.text._ZN20MavlinkCommandSender4lockEv)
*(.text.MEM_LongCopyEnd)
*(.text._ZThn24_N16ControlAllocator3RunEv)
*(.text._ZN15TimestampedListIN20MavlinkCommandSender14command_item_sELi3EE8get_nextEv)
*(.text._ZNK3Ekf21get_ekf_lpos_accuracyEPfS0_)
*(.text._ZN17FlightModeManager17start_flight_taskEv)
*(.text.MEM_DataCopyBytes)
*(.text._ZN29MavlinkStreamLocalPositionNED8get_sizeEv)
*(.text._ZN6SticksC1EP12ModuleParams)
*(.text._ZN27MavlinkStreamServoOutputRawILi1EE4sendEv)
@@ -366,7 +354,6 @@
*(.text.vsprintf_internal.constprop.0)
*(.text.udp_pollteardown)
*(.text._ZN12MixingOutput6updateEv)
*(.text.clock_abstime2ticks)
*(.text._ZN13BatteryStatus3RunEv)
*(.text._ZN32MavlinkStreamGimbalManagerStatus8get_sizeEv)
*(.text._ZN10FlightTask15_resetSetpointsEv)
@@ -388,7 +375,6 @@
*(.text._ZNK3px46logger9LogWriter10is_startedENS0_7LogTypeE)
*(.text._ZN24FlightTaskManualAltitudeD1Ev)
*(.text._Z35px4_indicate_external_reset_lockout16LockoutComponentb)
*(.text.uart_pollnotify)
*(.text._ZN4EKF215PublishBaroBiasERKy)
*(.text._ZN4EKF221UpdateGyroCalibrationERKy)
*(.text._ZN6matrix9constrainIfLj3ELj1EEENS_6MatrixIT_XT0_EXT1_EEERKS3_S2_S2_)
@@ -426,7 +412,6 @@
*(.text._ZN10FlightTask37_evaluateVehicleLocalPositionSetpointEv)
*(.text._ZN4uORB12Subscription11unsubscribeEv)
*(.text.net_lock)
*(.text.clock_time2ticks)
*(.text._ZN12FailsafeBase16updateStartDelayERKyb)
*(.text._ZN23MavlinkStreamStatustext8get_sizeEv)
*(.text._ZN11calibration13Accelerometer13set_device_idEm)
@@ -438,7 +423,6 @@
*(.text.nxsig_timeout)
*(.text._ZN11RateControl19setSaturationStatusERKN6matrix7Vector3IbEES4_)
*(.text._ZN3Ekf17measurementUpdateERN6matrix6VectorIfLj24EEERKS2_ff)
*(.text.dq_addlast)
*(.text._ZN19MavlinkStreamVFRHUD4sendEv)
*(.text.hrt_call_reschedule)
*(.text.nxsem_boost_priority)
@@ -486,7 +470,6 @@
*(.text._ZN22MavlinkStreamGPSStatus8get_sizeEv)
*(.text.nxsem_destroyholder)
*(.text.psock_udp_cansend)
*(.text.MEM_DataCopy2_2)
*(.text._ZN10FlightTask8activateERK21trajectory_setpoint_s)
*(.text.sock_file_poll)
*(.text._ZN10Ringbuffer9pop_frontEPhj)
@@ -496,7 +479,6 @@
*(.text.nxsem_canceled)
*(.text._ZN10FlightTask21getTrajectorySetpointEv)
*(.text.imxrt_dmach_getcount)
*(.text.sem_clockwait)
*(.text.inet_poll)
*(.text._ZN6BMP3887collectEv)
*(.text._ZNK15PositionControl24getLocalPositionSetpointER33vehicle_local_position_setpoint_s)
@@ -577,7 +559,6 @@
*(.text.up_flush_dcache)
*(.text._ZN15GyroCalibration3RunEv)
*(.text.mavlink_start_uart_send)
*(.text.MEM_DataCopy2)
*(.text._ZNK9Commander14getPrearmStateEv)
*(.text._ZN15EstimatorChecks14checkAndReportERK7ContextR6Report)
*(.text._ZN28FlightTaskManualAccelerationD1Ev)
@@ -614,7 +595,6 @@
*(.text._ZN12SafetyButton19CheckPairingRequestEb)
*(.text.imxrt_dma_txavailable)
*(.text.perf_set_elapsed)
*(.text.pthread_sem_take)
*(.text._ZN8StickYawD1Ev)
*(.text._Z15blink_msg_statev)
*(.text._ZN19AccelerometerChecks14checkAndReportERK7ContextR6Report)
@@ -660,7 +640,6 @@
*(.text._ZN15EstimatorChecks15checkSensorBiasERK7ContextR6Report8NavModes)
*(.text._ZN20ImuConsistencyChecks14checkAndReportERK7ContextR6Report)
*(.text._ZN28MavlinkStreamGpsGlobalOrigin8get_sizeEv)
*(.text.MEM_DataCopy2_1)
*(.text._ZN6BMP3887measureEv)
*(.text._ZN4EKF217PublishRngHgtBiasERKy)
*(.text._ZN36MavlinkStreamPositionTargetGlobalInt8get_sizeEv)
@@ -2,8 +2,6 @@
*(.text.arm_ack_irq)
*(.text.arm_doirq)
*(.text.arm_svcall)
*(.text.arm_switchcontext)
*(.text.clock_timer)
*(.text.exception_common)
*(.text.flexio_irq_handler)
*(.text.hrt_absolute_time)
@@ -38,17 +36,16 @@
*(.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_fdlist)
*(.text.nxsched_get_fdlist_from_tcb)
*(.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.nxsched_switch_context)
*(.text.nxsem_add_holder)
*(.text.nxsem_add_holder_tcb)
*(.text.nxsem_clockwait)
@@ -70,20 +67,16 @@
*(.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.work_thread)
*(.text.work_queue)
*(.text._do_memcpy)
*(.text.memcpy)
/* Tropic Eth tune */
/* Eth tune */
*(.text.devif_poll)
*(.text.devif_poll_tcp_connections)
*(.text.tcp_poll)
@@ -110,7 +103,6 @@
*(.text.net_ipv4addr_copy) /* itcm-check-ignore */
*(.text.net_ipv4addr_broadcast) /* itcm-check-ignore */
*(.text.wd_start)
*(.text.arp_arpin)
*(.text.ipv4_input)
*(.text.work_thread)
*(.text.work_queue)
@@ -3,8 +3,6 @@
*(.text.arm_ack_irq)
*(.text.arm_doirq)
*(.text.arm_svcall)
*(.text.arm_switchcontext)
*(.text.clock_timer)
*(.text.exception_common)
*(.text.hrt_call_enter)
*(.text.hrt_tim_isr)
@@ -28,17 +26,16 @@
*(.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_fdlist)
*(.text.nxsched_get_fdlist_from_tcb)
*(.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.nxsched_switch_context)
*(.text.nxsem_add_holder)
*(.text.nxsem_add_holder_tcb)
*(.text.nxsem_clockwait)
@@ -64,19 +61,15 @@
*(.text.spi_send)
*(.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_dma_receive)
*(.text.up_dma_send)
*(.text.up_dma_rxcallback)
*(.text.up_dma_txcallback)
*(.text.up_rxint)
*(.text.up_txint)
*(.text.up_unblock_task)
*(.text.wd_timer)
*(.text.wd_start)
*(.text._do_memcpy)
*(.text.memcpy)
@@ -40,8 +40,7 @@
*(.text._ZN15OutputPredictor21calculateOutputStatesEyRKN6matrix7Vector3IfEEfS4_f)
*(.text._ZN7sensors18VotedSensorsUpdate7imuPollER17sensor_combined_s)
*(.text._Z9rotate_3i8RotationRsS0_S0_)
*(.text.fs_getfilep)
*(.text.MEM_DataCopy0_1)
*(.text.file_get2)
*(.text._ZN7sensors19VehicleAcceleration3RunEv)
*(.text.uart_ioctl)
*(.text._ZN26MulticopterPositionControl3RunEv.part.0)
@@ -63,7 +62,6 @@
*(.text.hrt_call_internal)
*(.text._ZN39ControlAllocationSequentialDesaturation18mixAirmodeDisabledEv)
*(.text._ZN7Mavlink15get_free_tx_bufEv)
*(.text.nx_poll)
*(.text._ZN15MavlinkReceiver3runEv)
*(.text._ZN9ICM42688P18ProcessTemperatureEPKN20InvenSense_ICM42688P4FIFO4DATAEh)
*(.text._ZN15OutputPredictor19correctOutputStatesEyRKN6matrix10QuaternionIfEERKNS0_7Vector3IfEERK9LatLonAltS8_S8_)
@@ -80,10 +78,8 @@
*(.text._ZN13land_detector12LandDetector3RunEv)
*(.text.sched_idletask)
*(.text.atanf)
*(.text.uart_write)
*(.text.pthread_mutex_unlock)
*(.text.__ieee754_asinf)
*(.text.MEM_DataCopy0_2)
*(.text._ZN20MavlinkCommandSender13check_timeoutE17mavlink_channel_t)
*(.text._ZN16ControlAllocator32publish_control_allocator_statusEi)
*(.text.__ieee754_atan2f)
@@ -101,7 +97,6 @@
*(.text.sem_wait)
*(.text.perf_count_interval.part.0)
*(.text._ZN16ControlAllocator37update_effectiveness_matrix_if_neededE25EffectivenessUpdateReason)
*(.text.MEM_LongCopyJump)
*(.text.px4_arch_adc_sample)
*(.text._ZN31MulticopterHoverThrustEstimator3RunEv)
*(.text._ZNK17ControlAllocation20clipActuatorSetpointERN6matrix6VectorIfLj16EEE)
@@ -123,10 +118,7 @@
*(.text.imxrt_lpi2c_transfer)
*(.text.uart_putxmitchar)
*(.text.clock_nanosleep)
*(.text.up_release_pending)
*(.text.MEM_DataCopy0)
*(.text._ZN22MavlinkStreamGPSRawInt4sendEv)
*(.text.dq_rem)
*(.text._ZN15GyroCalibration3RunEv.part.0)
*(.text._ZN7sensors18VotedSensorsUpdate22calcAccelInconsistencyEv)
*(.text._ZN24MavlinkStreamADSBVehicle4sendEv)
@@ -238,7 +230,6 @@
*(.text._ZN7sensors14VehicleAirData3RunEv)
*(.text.perf_count)
*(.text._ZN3Ekf16controlMagFusionERKN9estimator9imuSampleE)
*(.text.pthread_sem_give)
*(.text._ZN7sensors10VehicleIMU16ParametersUpdateEb)
*(.text._ZN4uORB20SubscriptionInterval4copyEPv)
*(.text._ZN12I2CSPIDriverI9ICM42688PE3RunEv)
@@ -253,7 +244,6 @@
*(.text.pthread_mutex_add)
*(.text._ZN12HomePosition6updateEbb)
*(.text._ZN5PX4IO3RunEv)
*(.text.poll_fdsetup)
*(.text._ZN15PositionControl20_accelerationControlEv)
*(.text._ZN3Ekf19controlHeightFusionERKN9estimator9imuSampleE)
*(.text._ZN9Commander19control_status_ledsEbh)
@@ -275,12 +265,10 @@
*(.text._ZN3Ekf4fuseERKN6matrix6VectorIfLj24EEEf)
*(.text.nxsem_wait_irq)
*(.text._ZN20MavlinkCommandSender4lockEv)
*(.text.MEM_LongCopyEnd)
*(.text._ZThn24_N16ControlAllocator3RunEv)
*(.text._ZN15TimestampedListIN20MavlinkCommandSender14command_item_sELi3EE8get_nextEv)
*(.text._ZNK3Ekf21get_ekf_lpos_accuracyEPfS0_)
*(.text._ZN17FlightModeManager17start_flight_taskEv)
*(.text.MEM_DataCopyBytes)
*(.text._ZN29MavlinkStreamLocalPositionNED8get_sizeEv)
*(.text._ZN6SticksC1EP12ModuleParams)
*(.text._ZN27MavlinkStreamServoOutputRawILi1EE4sendEv)
@@ -374,7 +362,6 @@
*(.text.vsprintf_internal.constprop.0)
*(.text.udp_pollteardown)
*(.text._ZN12MixingOutput6updateEv)
*(.text.clock_abstime2ticks)
*(.text._ZN13BatteryStatus3RunEv)
*(.text._ZN32MavlinkStreamGimbalManagerStatus8get_sizeEv)
*(.text._ZN10FlightTask15_resetSetpointsEv)
@@ -396,7 +383,6 @@
*(.text._ZNK3px46logger9LogWriter10is_startedENS0_7LogTypeE)
*(.text._ZN24FlightTaskManualAltitudeD1Ev)
*(.text._Z35px4_indicate_external_reset_lockout16LockoutComponentb)
*(.text.uart_pollnotify)
*(.text._ZN4EKF215PublishBaroBiasERKy)
*(.text._ZN4EKF221UpdateGyroCalibrationERKy)
*(.text._ZN6matrix9constrainIfLj3ELj1EEENS_6MatrixIT_XT0_EXT1_EEERKS3_S2_S2_)
@@ -434,7 +420,6 @@
*(.text._ZN10FlightTask37_evaluateVehicleLocalPositionSetpointEv)
*(.text._ZN4uORB12Subscription11unsubscribeEv)
*(.text.net_lock)
*(.text.clock_time2ticks)
*(.text._ZN12FailsafeBase16updateStartDelayERKyb)
*(.text._ZN23MavlinkStreamStatustext8get_sizeEv)
*(.text._ZN11calibration13Accelerometer13set_device_idEm)
@@ -446,7 +431,6 @@
*(.text.nxsig_timeout)
*(.text._ZN11RateControl19setSaturationStatusERKN6matrix7Vector3IbEES4_)
*(.text._ZN3Ekf17measurementUpdateERN6matrix6VectorIfLj24EEERKS2_ff)
*(.text.dq_addlast)
*(.text._ZN19MavlinkStreamVFRHUD4sendEv)
*(.text.hrt_call_reschedule)
*(.text.nxsem_boost_priority)
@@ -494,7 +478,6 @@
*(.text._ZN22MavlinkStreamGPSStatus8get_sizeEv)
*(.text.nxsem_destroyholder)
*(.text.psock_udp_cansend)
*(.text.MEM_DataCopy2_2)
*(.text._ZN10FlightTask8activateERK21trajectory_setpoint_s)
*(.text.sock_file_poll)
*(.text._ZN10Ringbuffer9pop_frontEPhj)
@@ -504,7 +487,6 @@
*(.text.nxsem_canceled)
*(.text._ZN10FlightTask21getTrajectorySetpointEv)
*(.text.imxrt_dmach_getcount)
*(.text.sem_clockwait)
*(.text.inet_poll)
*(.text._ZN6BMP3887collectEv)
*(.text._ZN15ArchPX4IOSerial19_do_rx_dma_callbackEbi)
@@ -591,7 +573,6 @@
*(.text._ZN5PX4IO16io_handle_statusEt)
*(.text._ZN15GyroCalibration3RunEv)
*(.text.mavlink_start_uart_send)
*(.text.MEM_DataCopy2)
*(.text._ZNK9Commander14getPrearmStateEv)
*(.text._ZN15EstimatorChecks14checkAndReportERK7ContextR6Report)
*(.text._ZN28FlightTaskManualAccelerationD1Ev)
@@ -628,7 +609,6 @@
*(.text._ZN12SafetyButton19CheckPairingRequestEb)
*(.text.imxrt_dma_txavailable)
*(.text.perf_set_elapsed)
*(.text.pthread_sem_take)
*(.text._ZN8StickYawD1Ev)
*(.text._Z15blink_msg_statev)
*(.text._ZN19AccelerometerChecks14checkAndReportERK7ContextR6Report)
@@ -674,7 +654,6 @@
*(.text._ZN15EstimatorChecks15checkSensorBiasERK7ContextR6Report8NavModes)
*(.text._ZN20ImuConsistencyChecks14checkAndReportERK7ContextR6Report)
*(.text._ZN28MavlinkStreamGpsGlobalOrigin8get_sizeEv)
*(.text.MEM_DataCopy2_1)
*(.text._ZN6BMP3887measureEv)
*(.text._ZN4EKF217PublishRngHgtBiasERKy)
*(.text._ZN36MavlinkStreamPositionTargetGlobalInt8get_sizeEv)
@@ -2,9 +2,7 @@
*(.text.arm_ack_irq)
*(.text.arm_doirq)
*(.text.arm_svcall)
*(.text.arm_switchcontext)
*(.text.board_autoled_on)
*(.text.clock_timer)
*(.text.exception_common)
*(.text.flexio_irq_handler)
*(.text.hrt_absolute_time)
@@ -15,31 +13,43 @@
*(.text.imxrt_dmach_interrupt)
*(.text.imxrt_dmach_xfrsetup)
*(.text.imxrt_dmaterminate)
*(.text.imxrt_dispatch)
*(.text.imxrt_edma_interrupt)
*(.text.imxrt_endwait)
*(.text.imxrt_enet_interrupt)
*(.text.imxrt_enet_interrupt_work)
*(.text.imxrt_gpio3_16_31_interrupt)
*(.text.imxrt_interrupt)
*(.text.imxrt_lpi2c_isr)
*(.text.imxrt_lpspi2select)
*(.text.imxrt_lpspi3select)
*(.text.imxrt_lpspi_exchange)
*(.text.imxrt_recvdma)
*(.text.imxrt_tcd_free)
*(.text.imxrt_timerisr)
*(.text.imxrt_transmit)
*(.text.imxrt_txdone)
*(.text.imxrt_txtimeout_work)
*(.text.imxrt_txtimeout_expiry)
*(.text.imxrt_txpoll)
*(.text.imxrt_txringfull)
*(.text.imxrt_txavail_work)
*(.text.imxrt_txavail)
*(.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_fdlist)
*(.text.nxsched_get_fdlist_from_tcb)
*(.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.nxsched_switch_context)
*(.text.nxsem_add_holder)
*(.text.nxsem_add_holder_tcb)
*(.text.nxsem_clockwait)
@@ -61,13 +71,85 @@
*(.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)
*(.text.work_thread)
*(.text.work_queue)
*(.text.memcpy)
/* Eth tune */
*(.text.devif_poll)
*(.text.devif_poll_tcp_connections)
*(.text.tcp_poll)
*(.text.devif_poll_udp_connections)
*(.text.udp_nextconn)
*(.text.udp_poll)
*(.text.udp_ipv4_select)
*(.text.udp_callback)
*(.text.udp_datahandler)
*(.text.udp_send)
*(.text.udp_active)
*(.text.udp_ipv4_active)
*(.text.psock_udp_sendto)
*(.text.sendto_eventhandler)
*(.text.net_dataevent)
*(.text.devif_conn_event)
*(.text.devif_event_trigger)
*(.text.devif_poll_icmp)
*(.text.icmp_poll)
*(.text.arp_out)
*(.text.arp_find)
*(.text.arp_format)
*(.text.net_ipv4addr_hdrcmp) /* itcm-check-ignore */
*(.text.net_ipv4addr_copy) /* itcm-check-ignore */
*(.text.net_ipv4addr_broadcast) /* itcm-check-ignore */
*(.text.wd_start)
*(.text.ipv4_input)
*(.text.work_thread)
*(.text.work_queue)
/* ICM45686 */
*(.text._ZN8ICM4568612ProcessAccelERKyPKN19InvenSense_ICM456864FIFO4DATAEh)
*(.text._ZN8ICM4568611ProcessGyroERKyPKN19InvenSense_ICM456864FIFO4DATAEh)
*(.text._ZN8ICM456868FIFOReadERKy)
*(.text._ZN8ICM456867RunImplEv)
*(.text._ZN8ICM4568618ProcessTemperatureEPKN19InvenSense_ICM456864FIFO4DATAEh)
*(.text._ZN12I2CSPIDriverI8ICM45686E3RunEv)
*(.text._ZN8ICM4568613FIFOReadCountEv)
/* BMI088 */
*(.text._ZN5Bosch6BMI08813Accelerometer20BMI088_Accelerometer12RegisterReadENS1_8RegisterE)
*(.text._ZN5Bosch6BMI08813Accelerometer20BMI088_Accelerometer13FIFOReadCountEv)
*(.text._ZN5Bosch6BMI08813Accelerometer20BMI088_Accelerometer8FIFOReadERKyh)
*(.text._ZN5Bosch6BMI08813Accelerometer20BMI088_Accelerometer13RegisterCheckERKNS2_17register_config_tE)
*(.text._ZN5Bosch6BMI08813Accelerometer20BMI088_Accelerometer13RegisterWriteENS1_8RegisterEh)
*(.text._ZN5Bosch6BMI08813Accelerometer20BMI088_Accelerometer17UpdateTemperatureEv)
*(.text._ZN5Bosch6BMI08813Accelerometer20BMI088_Accelerometer23RegisterSetAndClearBitsENS1_8RegisterEhh)
*(.text._ZN5Bosch6BMI08813Accelerometer20BMI088_Accelerometer26DataReadyInterruptCallbackEiPvS3_)
*(.text._ZN5Bosch6BMI08813Accelerometer20BMI088_Accelerometer7RunImplEv)
*(.text._ZN5Bosch6BMI08813Accelerometer20BMI088_Accelerometer9DataReadyEv)
*(.text._ZN5Bosch6BMI08813Accelerometer20BMI088_AccelerometerD0Ev)
*(.text._ZN5Bosch6BMI08813Accelerometer20BMI088_AccelerometerD1Ev)
*(.text._ZN5Bosch6BMI08813Accelerometer20BMI088_AccelerometerD2Ev)
*(.text._ZN5Bosch6BMI0889Gyroscope16BMI088_Gyroscope12RegisterReadENS1_8RegisterE)
*(.text._ZN5Bosch6BMI0889Gyroscope16BMI088_Gyroscope13RegisterCheckERKNS2_17register_config_tE)
*(.text._ZN5Bosch6BMI0889Gyroscope16BMI088_Gyroscope13RegisterWriteENS1_8RegisterEh)
*(.text._ZN5Bosch6BMI0889Gyroscope16BMI088_Gyroscope23RegisterSetAndClearBitsENS1_8RegisterEhh)
*(.text._ZN5Bosch6BMI0889Gyroscope16BMI088_Gyroscope26DataReadyInterruptCallbackEiPvS3_)
*(.text._ZN5Bosch6BMI0889Gyroscope16BMI088_Gyroscope7RunImplEv)
*(.text._ZN5Bosch6BMI0889Gyroscope16BMI088_Gyroscope8FIFOReadERKyh)
*(.text._ZN5Bosch6BMI0889Gyroscope16BMI088_Gyroscope9DataReadyEv)
*(.text._ZN5Bosch6BMI0889Gyroscope16BMI088_GyroscopeD0Ev)
*(.text._ZN5Bosch6BMI0889Gyroscope16BMI088_GyroscopeD1Ev)
*(.text._ZN5Bosch6BMI0889Gyroscope16BMI088_GyroscopeD2Ev)
*(.text._ZN12I2CSPIDriverI6BMI088E3RunEv)
/* BMM350 */
*(.text._ZN12I2CSPIDriverI6BMM350E3RunEv)
*(.text._ZN6BMM3507RunImplEv)
*(.text._ZN6BMM35013RegisterWriteEN12Bosch_BMM3508RegisterEh)
*(.text._ZN6BMM35012RegisterReadEN12Bosch_BMM3508RegisterEPh)
*(.text._ZN6BMM35014ReadOutRawDataEPf)