diff --git a/.github/workflows/itcm_check.yml b/.github/workflows/itcm_check.yml new file mode 100644 index 0000000000..94ebab8780 --- /dev/null +++ b/.github/workflows/itcm_check.yml @@ -0,0 +1,61 @@ +name: ITCM check + +permissions: + contents: read + +on: + push: + branches: + - 'main' + paths-ignore: + - 'docs/**' + - '.github/**' + pull_request: + branches: + - '*' + paths-ignore: + - 'docs/**' + - '.github/**' + +jobs: + check_itcm: + name: Checking ${{ matrix.target }} + runs-on: [runs-on,runner=8cpu-linux-x64,image=ubuntu24-full-x64,"run-id=${{ github.run_id }}",spot=false] + container: + image: px4io/px4-dev:v1.16.0-ondemand + strategy: + fail-fast: false + matrix: + include: + - target: px4_fmu-v5x + scripts: > + boards/px4/fmu-v5x/nuttx-config/scripts/itcm_gen_functions.ld + boards/px4/fmu-v5x/nuttx-config/scripts/itcm_static_functions.ld + - target: px4_fmu-v6xrt + scripts: > + boards/px4/fmu-v6xrt/nuttx-config/scripts/itcm_functions_includes.ld + boards/px4/fmu-v6xrt/nuttx-config/scripts/itcm_static_functions.ld + - target: nxp_tropic-community + scripts: > + boards/nxp/tropic-community/nuttx-config/scripts/itcm_functions_includes.ld + boards/nxp/tropic-community/nuttx-config/scripts/itcm_static_functions.ld + steps: + - uses: actions/checkout@v4 + with: + fetch-depth: 0 + submodules: recursive + + - name: Git ownership workaround + run: git config --system --add safe.directory '*' + + - name: Build Target + run: make ${{ matrix.target }} + + - name: Copy built ELF + run: cp ./build/**/*.elf ./built.elf + + - name: Install itcm-check dependencies + run: pip3 install -r Tools/setup/optional-requirements.txt --break-system-packages + + - name: Execute the itcm-check + run: python3 Tools/itcm_check.py --elf-file built.elf --script-files ${{ matrix.scripts }} diff --git a/Tools/itcm_check.py b/Tools/itcm_check.py new file mode 100644 index 0000000000..ac1ffa63b7 --- /dev/null +++ b/Tools/itcm_check.py @@ -0,0 +1,185 @@ +#! /usr/bin/env python3 + +""" +Checks if the functions that should be mapped to ITCM are contained in the built ELF file. + +This helps against linker scripts that "rot" as the linker does not warn in case of a function +not existing. Thus, it is possible to forget to update the linker script after a code update. + +The tool uses the DWARF debug info and the ELF symbol table section to identify which functions +exist in the built ELF file. + +It is expected that the linker scripts that are analyzed by the tool are linker script include +files that only contain the name of the sections (functions) that should be mapped to ITCM in +the following format: +``` +*(.text.arm_ack_irq) +*(.text.arm_doirq) +*(.text._ZN4uORB12DeviceMaster19getDeviceNodeLockedEPK12orb_metadatah) +*(.text._ZN3Ekf20controlGravityFusionERKN9estimator9imuSampleE) +[...] +``` + +A specific entry in the linker script file can be ignored by adding a comment, as shown in the following example: +``` +*(.text.arm_ack_irq) /* itcm-check-ignore */ +``` +""" + +import argparse +import re +from elftools.elf.elffile import ELFFile +from elftools.elf.sections import SymbolTableSection +from elftools.dwarf.die import DIE +from pathlib import Path +from typing import List, Set + + +def die_get_funcs_rec(die: DIE, ret: Set[str]): + """ + Recursively gets the mangled and demangled name of all functions in the given `die`. + + :param die: DIE to be processed. Is gathered recursively after passing a top DIE. + :param ret: Output set where all function names are added to. + """ + if die.tag in ("DW_TAG_subprogram", "DW_TAG_inlined_subroutine"): + link_name_att = die.attributes.get("DW_AT_linkage_name") + name_att = die.attributes.get("DW_AT_name") + if link_name_att: + ret.add(link_name_att.value.decode("utf-8")) + if name_att: + ret.add(name_att.value.decode("utf-8")) + + # Recurse into the DIE children + for child in die.iter_children(): + die_get_funcs_rec(child, ret) + + +def get_elf_symbols_from_debug(elf_path: Path) -> Set[str]: + """ + Gets all functions contained in the built ELF file using the DWARF debug info. + + :param elf_path: Path to the ELF file. + + :return: The names of the contained functions. + """ + ret = set() + with open(elf_path, 'rb') as f: + elf = ELFFile(f) + if not elf.has_dwarf_info(): + print("ELF does not have debug info. Compile with debug info.") + exit(1) + dwarf_info = elf.get_dwarf_info() + for CU in dwarf_info.iter_CUs(): + top_die = CU.get_top_DIE() + die_get_funcs_rec(top_die, ret) + + return ret + + +def get_elf_symbols_from_sections(elf_path: Path) -> Set[str]: + """ + Gets all functions contained in the built ELF file using the symbol table section. + + :param elf_path: Path to the ELF file. + + :return: The names of the contained functions. + """ + ret = set() + with open(elf_path, 'rb') as f: + elf = ELFFile(f) + for section in elf.iter_sections(): + if isinstance(section, SymbolTableSection): + for sym in section.iter_symbols(): + ret.add(sym.name) + return ret + + +def is_section_supported(section: str) -> bool: + """ + Returns whether this type of section can be checked. + + :param section: Name of the section that should be checked for support. + + :return: Whether the type of section is supported. + """ + not_supported_sections = [".isra", ".part", ".constprop"] + return not any(not_supported in section for not_supported in not_supported_sections) + + +def get_input_sections(script_path: Path) -> List[str]: + """ + Gets all sections (named after the functions) that should be mapped to ITCM according + to the linker script. + + :param script_path: Path of the linker script. + + :return: The names of the sections + """ + ret = [] + section_pattern = re.compile(r"^\*\(\.([a-zA-Z0-9_\.]+)\)$") + ignored_marker = "itcm-check-ignore" + with open(script_path, 'r') as f: + for line in f: + match = section_pattern.match(line) + if match and ignored_marker not in line: + section_name = match.group(1).replace("text.", "") + if is_section_supported(section_name): + ret.append(section_name) + return ret + + +def check_itcm(elf_path: Path, script_paths: List[Path]): + """ + Checks if all the functions that should be mapped to ITCM are contained in the built ELF file. + + :param elf_path: Path of the ELF file. + :param script_paths: Path of all linker scripts that should be checked. + """ + elf_symbols_from_debug = get_elf_symbols_from_debug(elf_path) + elf_symbols_from_sections = get_elf_symbols_from_sections(elf_path) + elf_symbols = elf_symbols_from_debug.union(elf_symbols_from_sections) + input_sections = [] + for script_path in script_paths: + script_input_sections = get_input_sections(script_path) + if script_input_sections: + input_sections.extend(script_input_sections) + else: + print(f"No input sections found in {script_path}, please check if the path is correct.") + + check_passed = True + for input_section in input_sections: + if input_section not in elf_symbols: + check_passed = False + print(f"Section: {input_section} not found in the ELF file!") + + if check_passed: + print("ITCM check passed!") + exit(0) + else: + print("ITCM check failed!") + exit(1) + + +def main(): + parser = argparse.ArgumentParser(description="Checks if functions marked for ITCM mapping exist in the ELF file.") + parser.add_argument( + "--elf-file", + help="Path of the compiled ELF file", + type=Path, + required=True + ) + parser.add_argument( + "--script-files", + help="Paths of the linker script files", + nargs="+", + type=Path, + required=True + ) + + args = parser.parse_args() + check_itcm(args.elf_file, args.script_files) + + +if __name__ == '__main__': + main() diff --git a/Tools/setup/optional-requirements.txt b/Tools/setup/optional-requirements.txt index 844ad80bb5..57c243a237 100644 --- a/Tools/setup/optional-requirements.txt +++ b/Tools/setup/optional-requirements.txt @@ -1 +1,2 @@ +pyelftools>=0.32,<1 symforce>=0.9.0 diff --git a/boards/nxp/tropic-community/nuttx-config/scripts/itcm_functions_includes.ld b/boards/nxp/tropic-community/nuttx-config/scripts/itcm_functions_includes.ld index 60a76f97e1..0e6701aae2 100644 --- a/boards/nxp/tropic-community/nuttx-config/scripts/itcm_functions_includes.ld +++ b/boards/nxp/tropic-community/nuttx-config/scripts/itcm_functions_includes.ld @@ -2,7 +2,7 @@ *(.text._ZN4uORB7Manager27orb_add_internal_subscriberE6ORB_IDhPj) *(.text._ZN13MavlinkStream6updateERKy) *(.text._ZN7Mavlink16update_rate_multEv) -*(.text._ZN3sym17PredictCovarianceIfEEN6matrix6MatrixIT_Lj23ELj23EEERKNS2_IS3_Lj24ELj1EEERKS4_RKNS2_IS3_Lj3ELj1EEES3_SC_SC_S3_S3_) +*(.text._ZN3sym17PredictCovarianceIfEEN6matrix6MatrixIT_Lj23ELj23EEERKNS2_IS3_Lj24ELj1EEERKS4_RKNS2_IS3_Lj3ELj1EEES3_SC_SC_S3_S3_) /* itcm-check-ignore */ *(.text._ZN13MavlinkStream12get_size_avgEv) *(.text._ZN16ControlAllocator3RunEv) *(.text._ZN22MulticopterRateControl3RunEv.part.0) @@ -57,7 +57,6 @@ *(.text._ZN3px49WorkQueue3AddEPNS_8WorkItemE) *(.text._ZN4EKF220PublishLocalPositionERKy) *(.text._mav_finalize_message_chan_send) -*(.text._ZN3Ekf19fixCovarianceErrorsEb) *(.text._ZN7sensors22VehicleAngularVelocity16ParametersUpdateEb) *(.text._ZN6events12SendProtocol6updateERKy) *(.text._ZN6device3SPI8transferEPhS1_j) @@ -68,7 +67,7 @@ *(.text.nx_poll) *(.text._ZN15MavlinkReceiver3runEv) *(.text._ZN9ICM42688P18ProcessTemperatureEPKN20InvenSense_ICM42688P4FIFO4DATAEh) -*(.text._ZN15OutputPredictor19correctOutputStatesEyRKN6matrix10QuaternionIfEERKNS0_7Vector3IfEES8_S8_S8_) +*(.text._ZN15OutputPredictor19correctOutputStatesEyRKN6matrix10QuaternionIfEERKNS0_7Vector3IfEERK9LatLonAltS8_S8_) *(.text._ZN3Ekf12predictStateERKN9estimator9imuSampleE) *(.text._ZN3px46logger6Logger3runEv) *(.text._ZN4uORB20SubscriptionInterval7updatedEv) @@ -99,7 +98,6 @@ *(.text.file_vioctl) *(.text._ZN7sensors18VotedSensorsUpdate11sensorsPollER17sensor_combined_s) *(.text.nxsig_nanosleep) -*(.text.imxrt_lpspi1select) *(.text.sem_wait) *(.text.perf_count_interval.part.0) *(.text._ZN16ControlAllocator37update_effectiveness_matrix_if_neededE25EffectivenessUpdateReason) @@ -122,7 +120,6 @@ *(.text._ZN22MulticopterRateControl28updateActuatorControlsStatusERK25vehicle_torque_setpoint_sf) *(.text._ZN11RateControl6updateERKN6matrix7Vector3IfEES4_S4_fb) *(.text._ZN39ControlAllocationSequentialDesaturation19desaturateActuatorsERN6matrix6VectorIfLj16EEERKS2_b) -*(.text._ZN22MavlinkStreamCollision4sendEv) *(.text.imxrt_lpi2c_transfer) *(.text.uart_putxmitchar) *(.text.clock_nanosleep) @@ -154,7 +151,6 @@ *(.text._ZN3Ekf20updateIMUBiasInhibitERKN9estimator9imuSampleE) *(.text._ZN9Commander13dataLinkCheckEv) *(.text._ZN17FlightModeManager10switchTaskE15FlightTaskIndex) -*(.text._ZNK3Ekf26get_innovation_test_statusERtRfS1_S1_S1_S1_S1_S1_) *(.text._ZN12PX4Gyroscope9set_scaleEf) *(.text._ZN12FailsafeBase6updateERKyRKNS_5StateEbbRK16failsafe_flags_s) *(.text._ZN18MavlinkStreamDebug4sendEv) @@ -167,11 +163,10 @@ *(.text._ZN13land_detector23MulticopterLandDetector25_get_ground_contact_stateEv) *(.text.imxrt_dmach_start) *(.text._ZN3ADC19update_system_powerEy) -*(.text._ZNK3Ekf19get_ekf_soln_statusEPt) +*(.text._ZNK3Ekf19get_ekf_soln_statusEv) *(.text._ZN3px46logger15watchdog_updateERNS0_15watchdog_data_tEb) *(.text.imxrt_gpio_read) *(.text._ZN32MavlinkStreamNavControllerOutput4sendEv) -*(.text._ZN15ArchPX4IOSerial13_bus_exchangeEP8IOPacket) *(.text._ZN39MavlinkStreamGimbalDeviceAttitudeStatus4sendEv) *(.text._ZNK10ConstLayer3getEt) *(.text.__aeabi_uldivmod) @@ -194,11 +189,9 @@ *(.text._ZN22MavlinkStreamGPSStatus4sendEv) *(.text._ZN4EKF220UpdateAirspeedSampleER17ekf2_timestamps_s) *(.text._ZN23MavlinkStreamStatustext4sendEv) -*(.text._ZN3Ekf15constrainStatesEv) -*(.text._ZN12PX4IO_serial4readEjPvj) *(.text.uart_poll) *(.text._ZN24MavlinkParametersManager4sendEv) -*(.text._ZN26MulticopterPositionControl18set_vehicle_statesERK24vehicle_local_position_s) +*(.text._ZN26MulticopterPositionControl18set_vehicle_statesERK24vehicle_local_position_sf) *(.text.file_poll) *(.text.hrt_elapsed_time) *(.text._ZN7Mavlink11send_finishEv) @@ -232,8 +225,7 @@ *(.text._ZN6matrix5EulerIfEC1ERKNS_10QuaternionIfEE) *(.text.imxrt_queuedtd) *(.text._ZN27MavlinkStreamDistanceSensor8get_sizeEv) -*(.text._ZN3Ekf16fuseVelPosHeightEffi) -*(.text._ZN3Ekf23controlBaroHeightFusionEv) +*(.text._ZN3Ekf23controlBaroHeightFusionERKN9estimator9imuSampleE) *(.text._ZN16PX4Accelerometer9set_scaleEf) *(.text._ZN11ControlMath11constrainXYERKN6matrix7Vector2IfEES4_RKf) *(.text._ZN22MavlinkStreamEfiStatus4sendEv) @@ -243,13 +235,11 @@ *(.text._ZN15PositionControl11_inputValidEv) *(.text._ZN7sensors14VehicleAirData3RunEv) *(.text.perf_count) -*(.text._ZN3Ekf16controlMagFusionEv) +*(.text._ZN3Ekf16controlMagFusionERKN9estimator9imuSampleE) *(.text.pthread_sem_give) *(.text._ZN7sensors10VehicleIMU16ParametersUpdateEb) -*(.text._ZN30MavlinkStreamUTMGlobalPosition4sendEv) *(.text._ZN4uORB20SubscriptionInterval4copyEPv) *(.text._ZN12I2CSPIDriverI9ICM42688PE3RunEv) -*(.text._ZN17ObstacleAvoidanceC1EP12ModuleParams) *(.text.imxrt_epcomplete.constprop.0) *(.text._ZNK6matrix6MatrixIfLj3ELj1EEmiERKS1_) *(.text._ZN9Commander30handleModeIntentionAndFailsafeEv) @@ -260,7 +250,6 @@ *(.text._ZN29MavlinkStreamHygrometerSensor8get_sizeEv) *(.text.pthread_mutex_add) *(.text._ZN12HomePosition6updateEbb) -*(.text._ZN5PX4IO3RunEv) *(.text.poll_fdsetup) *(.text._ZN15PositionControl20_accelerationControlEv) *(.text._ZN3Ekf19controlHeightFusionERKN9estimator9imuSampleE) @@ -280,7 +269,7 @@ *(.text._ZN6matrix6MatrixIfLj3ELj1EEC1ERKS1_) *(.text.udp_pollsetup) *(.text._ZL14timer_callbackPv) -*(.text._ZN3Ekf4fuseERKN6matrix6VectorIfLj23EEEf) +*(.text._ZN3Ekf4fuseERKN6matrix6VectorIfLj24EEEf) *(.text._ZN13land_detector23MulticopterLandDetector22_set_hysteresis_factorEi) *(.text.nxsem_wait_irq) *(.text._ZN20MavlinkCommandSender4lockEv) @@ -299,7 +288,7 @@ *(.text._ZN25MavlinkStreamHomePosition4sendEv) *(.text._ZN24MavlinkParametersManager8send_oneEv) *(.text._ZN15OutputPredictor29applyCorrectionToOutputBufferERKN6matrix7Vector3IfEES4_) -*(.text._ZN21HealthAndArmingChecks6updateEb) +*(.text._ZN21HealthAndArmingChecks6updateEbb) *(.text._ZThn24_N22MulticopterRateControl3RunEv) *(.text._ZN26MavlinkStreamManualControl4sendEv) *(.text._ZN27MavlinkStreamOpticalFlowRad4sendEv) @@ -307,14 +296,11 @@ *(.text._ZN4uORB7Manager11orb_publishEPK12orb_metadataPvPKv) *(.text._ZN24MavlinkParametersManager18send_untransmittedEv) *(.text._ZN10MavlinkFTP4sendEv) -*(.text._ZN15ArchPX4IOSerial13_do_interruptEv) -*(.text._ZN3Ekf27controlExternalVisionFusionEv) +*(.text._ZN3Ekf27controlExternalVisionFusionERKN9estimator9imuSampleE) *(.text.clock_gettime) *(.text._ZN3ADC17update_adc_reportEy) -*(.text._ZN3sym25ComputeYaw312InnovVarAndHIfEEvRKN6matrix6MatrixIT_Lj24ELj1EEERKNS2_IS3_Lj23ELj23EEES3_S3_PS3_PNS2_IS3_Lj23ELj1EEE) -*(.text._ZN3Ekf19runTerrainEstimatorERKN9estimator9imuSampleE) *(.text._ZN32MavlinkStreamGimbalManagerStatus4sendEv) -*(.text._ZN9LockGuardD1Ev) +*(.text._ZN9LockGuardD1Ev) /* itcm-check-ignore */ *(.text._ZN4EKF213PublishStatesERKy) *(.text._ZN3ADC3RunEv) *(.text._ZN6BMP38815compensate_dataEhPK16bmp3_uncomp_dataP9bmp3_data) @@ -336,13 +322,11 @@ *(.text._ZThn16_N7sensors22VehicleAngularVelocity3RunEv) *(.text._ZN29MavlinkStreamObstacleDistance4sendEv) *(.text._ZN24MavlinkStreamOrbitStatus4sendEv) -*(.text._ZN16PreFlightChecker26preFlightCheckHeightFailedERK23estimator_innovations_sf) *(.text._ZN9Navigator3runEv) *(.text._ZN24MavlinkParametersManager11send_paramsEv) *(.text._ZN17MavlinkLogHandler4sendEv) *(.text._ZN7control10SuperBlock5setDtEf) *(.text._ZN29MavlinkStreamMountOrientation8get_sizeEv) -*(.text._ZN5PX4IO13io_get_statusEv) *(.text._ZN26MulticopterAttitudeControl3RunEv) *(.text._ZThn16_N31ActuatorEffectivenessMultirotor22getEffectivenessMatrixERN21ActuatorEffectiveness13ConfigurationE25EffectivenessUpdateReason) *(.text._ZN4EKF218PublishStatusFlagsERKy) @@ -350,13 +334,12 @@ *(.text._ZN15FailureDetector6updateERK16vehicle_status_sRK22vehicle_control_mode_s) *(.text._ZN7Mavlink10send_startEi) *(.text.imxrt_lpspi_setbits) -*(.text._ZN15OutputPredictor37applyCorrectionToVerticalOutputBufferEf) +*(.text._ZN15OutputPredictor37applyCorrectionToVerticalOutputBufferEff) *(.text._ZN4EKF222UpdateAccelCalibrationERKy) *(.text._ZN7sensors19VehicleMagnetometer3RunEv) *(.text._ZN29MavlinkStreamMountOrientation4sendEv) *(.text._ZN13land_detector12LandDetector19UpdateVehicleAtRestEv) *(.text._ZN10FlightTask29_evaluateVehicleLocalPositionEv) -*(.text.board_autoled_off) *(.text.__aeabi_f2lz) *(.text._ZN32MavlinkStreamCameraImageCaptured4sendEv) *(.text._ZN21MavlinkStreamOdometry8get_sizeEv) @@ -365,24 +348,19 @@ *(.text.poll) *(.text._ZN14FlightTaskAutoD1Ev) *(.text._ZN4uORB10DeviceNode22get_initial_generationEv) -*(.text._ZN3Ekf23controlGnssHeightFusionERKN9estimator9gpsSampleE) +*(.text._ZN3Ekf23controlGnssHeightFusionERKN9estimator10gnssSampleE) *(.text._ZN3Ekf40updateOnGroundMotionForOpticalFlowChecksEv) *(.text._ZN6matrix6MatrixIfLj3ELj1EEC1Ev) *(.text._ZN14ZeroGyroUpdate6updateER3EkfRKN9estimator9imuSampleE) *(.text._ZN30MavlinkStreamOpenDroneIdSystem4sendEv) *(.text._ZN22MavlinkStreamScaledIMU4sendEv) -*(.text._ZN46MavlinkStreamTrajectoryRepresentationWaypoints4sendEv) *(.text.imxrt_ioctl) -*(.text._ZN3Ekf25checkMagBiasObservabilityEv) *(.text._ZN36MavlinkStreamGimbalDeviceSetAttitude4sendEv) -*(.text._ZN16PreFlightChecker6updateEfRK23estimator_innovations_s) *(.text._ZN4math13expo_deadzoneIfEEKT_RS2_S3_S3_.isra.0) *(.text._ZN19StickAccelerationXYC1EP12ModuleParams) *(.text.imxrt_epsubmit) *(.text._ZN15PositionControl6updateEf) -*(.text._ZN3Ekf29checkVerticalAccelerationBiasERKN9estimator9imuSampleE) *(.text._ZN23MavlinkStreamScaledIMU24sendEv) -*(.text._ZN5PX4IO10io_reg_getEhhPtj) *(.text.imxrt_dma_send) *(.text._ZN20MavlinkStreamWindCov4sendEv) *(.text._ZN7sensors18VotedSensorsUpdate13checkFailoverERNS0_10SensorDataEPKcN6events3px45enums13sensor_type_tE) @@ -405,7 +383,7 @@ *(.text._ZN9Commander11updateTunesEv) *(.text._ZN4EKF215UpdateMagSampleER17ekf2_timestamps_s) *(.text._ZN18DataValidatorGroup3putEjyPKfmh) -*(.text._ZNK3Ekf19get_ekf_ctrl_limitsEPfS0_S0_S0_) +*(.text._ZNK3Ekf19get_ekf_ctrl_limitsEPfS0_S0_S0_S0_) *(.text._ZN12FailsafeBase13checkFailsafeEibbRKNS_13ActionOptionsE) *(.text._ZN17FlightTaskDescendD1Ev) *(.text._ZN30MavlinkStreamOpenDroneIdSystem8get_sizeEv) @@ -413,7 +391,6 @@ *(.text._ZN24FlightTaskManualAltitudeD1Ev) *(.text._Z35px4_indicate_external_reset_lockout16LockoutComponentb) *(.text.uart_pollnotify) -*(.text._ZN3Ekf11predictHaglERKN9estimator9imuSampleE) *(.text._ZN4EKF215PublishBaroBiasERKy) *(.text._ZN4EKF221UpdateGyroCalibrationERKy) *(.text._ZN6matrix9constrainIfLj3ELj1EEENS_6MatrixIT_XT0_EXT1_EEERKS3_S2_S2_) @@ -444,7 +421,7 @@ *(.text.clock_systime_timespec) *(.text._ZN4uORB10DeviceNode26remove_internal_subscriberEv) *(.text._ZThn16_N4EKF23RunEv) -*(.text._ZNK3Ekf22computeYawInnovVarAndHEfRfRN6matrix6VectorIfLj23EEE) +*(.text._ZNK3Ekf22computeYawInnovVarAndHEfRfRN6matrix6VectorIfLj24EEE) *(.text._ZN12ActuatorTest6updateEif) *(.text._ZN17VelocitySmoothingC1Efff) *(.text._ZN13AnalogBattery19get_voltage_channelEv) @@ -459,11 +436,10 @@ *(.text._ZN14FlightTaskAuto17_evaluateTripletsEv) *(.text._ZN11calibration9Gyroscope23SensorCorrectionsUpdateEb) *(.text._ZN25MavlinkStreamMagCalReport4sendEv) -*(.text._ZN16PreFlightChecker27preFlightCheckHeadingFailedERK23estimator_innovations_sf) *(.text.imxrt_config_gpio) *(.text.nxsig_timeout) *(.text._ZN11RateControl19setSaturationStatusERKN6matrix7Vector3IbEES4_) -*(.text._ZN3Ekf17measurementUpdateERN6matrix6VectorIfLj23EEEff) +*(.text._ZN3Ekf17measurementUpdateERN6matrix6VectorIfLj24EEERKS2_ff) *(.text.dq_addlast) *(.text._ZN19MavlinkStreamVFRHUD4sendEv) *(.text.hrt_call_reschedule) @@ -487,14 +463,13 @@ *(.text._ZNK6matrix6MatrixIfLj3ELj1EE5emultERKS1_) *(.text.mallinfo_handler) *(.text._ZN13land_detector23MulticopterLandDetector14_update_topicsEv) -*(.text._ZN24ManualVelocitySmoothingZC1Ev) +*(.text._ZN24ManualVelocitySmoothingZC1Ev) /* itcm-check-ignore */ *(.text._ZN3ADC6sampleEj) *(.text._ZNK3Ekf22isTerrainEstimateValidEv) -*(.text._ZN15EstimatorChecks23setModeRequirementFlagsERK7ContextbbRK24vehicle_local_position_sRK12sensor_gps_sR16failsafe_flags_sR6Report) +*(.text._ZN15EstimatorChecks23setModeRequirementFlagsERK7ContextbbbRK24vehicle_local_position_sRK12sensor_gps_sR16failsafe_flags_sR6Report) *(.text._ZN11ControlMath11addIfNotNanERff) *(.text._ZN9Commander21checkForMissionUpdateEv) *(.text._Z8set_tunei) -*(.text._ZN3Ekf13stopGpsFusionEv) *(.text._ZNK6matrix7Vector3IfE5crossERKNS_6MatrixIfLj3ELj1EEE) *(.text._ZN10FlightTask22_checkEkfResetCountersEv) *(.text._ZNK6matrix6MatrixIfLj3ELj1EE11isAllFiniteEv) @@ -516,7 +491,6 @@ *(.text.MEM_DataCopy2_2) *(.text._ZN10FlightTask8activateERK21trajectory_setpoint_s) *(.text.sock_file_poll) -*(.text._ZN3Ekf20controlHaglRngFusionEv) *(.text._ZN10Ringbuffer9pop_frontEPhj) *(.text.nx_write) *(.text._ZN9Commander18manualControlCheckEv) @@ -527,18 +501,15 @@ *(.text.sem_clockwait) *(.text.inet_poll) *(.text._ZN6BMP3887collectEv) -*(.text._ZN15ArchPX4IOSerial19_do_rx_dma_callbackEbi) -*(.text._ZN15ArchPX4IOSerial10_abort_dmaEv) *(.text._ZNK15PositionControl24getLocalPositionSetpointER33vehicle_local_position_setpoint_s) *(.text._ZN3Ekf16controlGpsFusionERKN9estimator9imuSampleE) *(.text._ZN23MavlinkStreamRCChannels8get_sizeEv) *(.text._ZN20MavlinkStreamESCInfo8get_sizeEv) *(.text._ZNK6matrix6VectorIfLj2EE4normEv) *(.text._Z15arm_auth_updateyb) -*(.text._ZN3LED5ioctlEP4fileim) +*(.text._ZN3LED5ioctlEP4fileim) /* itcm-check-ignore */ *(.text._ZNK3px46logger9LogWriter20had_file_write_errorEv) *(.text._ZN29MavlinkStreamLocalPositionNED4sendEv) -*(.text._ZN6matrix6MatrixIfLj2ELj1EEC1ILj3ELj1EEERKNS_5SliceIfLj2ELj1EXT_EXT0_EEE) *(.text._ZNK6matrix6VectorIfLj3EE3dotERKNS_6MatrixIfLj3ELj1EEE) *(.text.imxrt_lpi2c_setclock) *(.text._ZN6matrix12typeFunction9constrainIfEET_S2_S2_S2_.part.0) @@ -559,16 +530,13 @@ *(.text._ZN6BMP38815get_sensor_dataEhP9bmp3_data) *(.text._ZN18MavlinkRateLimiter5checkERKy) *(.text._ZThn24_N26MulticopterAttitudeControl3RunEv) -*(.text._ZN15ArchPX4IOSerial10_interruptEiPvS0_) *(.text.imxrt_periphclk_configure) -*(.text._ZN3Ekf8initHaglEv) *(.text._ZN4EKF218UpdateAuxVelSampleER17ekf2_timestamps_s) *(.text._ZN3RTL11on_inactiveEv) *(.text._ZN12FailsafeBase10modeCanRunERK16failsafe_flags_sh) *(.text._ZN4EKF216PublishEvPosBiasERKy) *(.text._ZN21MavlinkStreamAttitude8get_sizeEv) *(.text._ZThn16_N7sensors19VehicleAcceleration3RunEv) -*(.text._ZN3Ekf24controlRangeHeightFusionEv) *(.text._ZN33MavlinkStreamTimeEstimateToTarget4sendEv) *(.text._ZN6matrix6MatrixIfLj3ELj1EE6setAllEf) *(.text._ZN12ModuleParamsD1Ev) @@ -586,22 +554,19 @@ *(.text._ZN26MulticopterPositionControl3RunEv) *(.text._ZN8Failsafe21fromQuadchuteActParamEi) *(.text._ZN24VariableLengthRingbuffer9pop_frontEPhj) -*(.text._ZN7control15BlockDerivative6updateEf) -*(.text._ZN5PX4IO10io_reg_getEhh) +*(.text._ZN7control15BlockDerivative6updateEf) /* itcm-check-ignore */ *(.text._ZN9Commander18safetyButtonUpdateEv) *(.text._ZN13BatteryChecks14checkAndReportERK7ContextR6Report) *(.text._ZN18DataValidatorGroup16get_sensor_stateEj) *(.text.uart_xmitchars_done) *(.text._ZN4EKF225PublishYawEstimatorStatusERKy) *(.text.sin) -*(.text._ZN16PreFlightChecker27preFlightCheckVertVelFailedERK23estimator_innovations_sf) *(.text._ZN6Safety19safetyButtonHandlerEv) -*(.text._ZN3Ekf19controlAuxVelFusionEv) +*(.text._ZN3Ekf19controlAuxVelFusionERKN9estimator9imuSampleE) *(.text._ZNK6matrix6MatrixIfLj2ELj1EEplERKS1_) *(.text._ZThn24_N7Sensors3RunEv) *(.text._ZN6matrix6MatrixIfLj2ELj1EEC1ERKS1_) *(.text._ZN10FlightTask10reActivateEv) -*(.text._ZN5PX4IO17io_publish_raw_rcEv) *(.text._ZNK15PositionControl19getAttitudeSetpointER27vehicle_attitude_setpoint_s) *(.text._ZN4cdev4CDev4pollEP4fileP6pollfdb) *(.text._ZN9Commander20offboardControlCheckEv) @@ -613,7 +578,6 @@ *(.text._ZN8Failsafe17updateArmingStateERKybRK16failsafe_flags_s) *(.text.imxrt_lpi2c_modifyreg) *(.text.up_flush_dcache) -*(.text._ZN5PX4IO16io_handle_statusEt) *(.text._ZN15GyroCalibration3RunEv) *(.text.mavlink_start_uart_send) *(.text.MEM_DataCopy2) @@ -647,7 +611,6 @@ *(.text._ZN12FailsafeBase11updateDelayERKy) *(.text._ZN10FlightTask25_evaluateDistanceToGroundEv) *(.text._ZN4EKF218PublishGnssHgtBiasERKy) -*(.text._ZN3Ekf21controlHaglFlowFusionEv) *(.text._ZN6matrix6VectorIfLj3EE9normalizeEv) *(.text._ZThn16_N7sensors10VehicleIMU3RunEv) *(.text.__kernel_cos) @@ -659,22 +622,18 @@ *(.text._Z15blink_msg_statev) *(.text._ZN19AccelerometerChecks14checkAndReportERK7ContextR6Report) *(.text._ZN8Failsafe14fromGfActParamEi) -*(.text._ZN3Ekf27checkAndFixCovarianceUpdateERKN6matrix12SquareMatrixIfLj23EEE) *(.text._ZN3Ekf17controlBetaFusionERKN9estimator9imuSampleE) -*(.text._ZN36do_not_explicitly_use_this_namespace5ParamIfLN3px46paramsE919EEC1Ev) +*(.text._ZN36do_not_explicitly_use_this_namespace5ParamIfLN3px46paramsE919EEC1Ev) /* itcm-check-ignore */ *(.text._ZN22MavlinkStreamHeartbeat8get_sizeEv) *(.text._ZN6matrix6MatrixIfLj3ELj1EEdVEf) *(.text._ZN17FlightTaskDescendC1Ev) *(.text._ZN26MavlinkStreamCameraTrigger8get_sizeEv) *(.text.iob_navail) *(.text._ZN12FailsafeBase25removeNonActivatedActionsEv) -*(.text._ZN16PreFlightChecker28preFlightCheckHorizVelFailedERK23estimator_innovations_sf) *(.text._ZN15TakeoffHandling10updateRampEff) *(.text._Z7led_offi) -*(.text._ZN16PreFlightChecker22selectHeadingTestLimitEv) *(.text.led_off) *(.text.udp_wrbuffer_test) -*(.text._ZNK3Ekf34updateVerticalPositionAidSrcStatusERKyfffR24estimator_aid_source1d_s) *(.text._ZNK4math17WelfordMeanVectorIfLj3EE8varianceEv) *(.text._ZN27MavlinkStreamAttitudeTarget4sendEv) *(.text._ZN12MixingOutput19updateSubscriptionsEb) @@ -683,7 +642,6 @@ *(.text._ZN18MavlinkStreamDebug8get_sizeEv) *(.text._ZN12GPSDriverUBX7receiveEj) *(.text._ZN13BatteryStatus21parameter_update_pollEb) -*(.text._ZN3Ekf26checkYawAngleObservabilityEv) *(.text._ZN3RTL18updateDatamanCacheEv) *(.text.__ieee754_sqrtf) *(.text._ZThn24_N18mag_bias_estimator16MagBiasEstimator3RunEv) @@ -701,11 +659,9 @@ *(.text._ZN12SystemChecks14checkAndReportERK7ContextR6Report) *(.text._ZN6matrix6MatrixIfLj3ELj1EEC1EPKf) *(.text.imxrt_padmux_address) -*(.text._ZN3Ekf15setVelPosStatusEib) *(.text._ZN19MavlinkStreamVFRHUD8get_sizeEv) *(.text._ZN15EstimatorChecks15checkSensorBiasERK7ContextR6Report8NavModes) *(.text._ZN20ImuConsistencyChecks14checkAndReportERK7ContextR6Report) -*(.text._ZN17ObstacleAvoidanceD1Ev) *(.text._ZN28MavlinkStreamGpsGlobalOrigin8get_sizeEv) *(.text.MEM_DataCopy2_1) *(.text._ZN6BMP3887measureEv) @@ -713,7 +669,7 @@ *(.text._ZN36MavlinkStreamPositionTargetGlobalInt8get_sizeEv) *(.text._ZN28MavlinkStreamEstimatorStatus8get_sizeEv) *(.text.up_clean_dcache) -*(.text._ZThn56_N26MulticopterPositionControl3RunEv) +*(.text._ZThn24_N26MulticopterPositionControl3RunEv) *(.text._ZN16FlightTimeChecks14checkAndReportERK7ContextR6Report) *(.text._ZN13ManualControl12processInputEy) *(.text._ZN17CpuResourceChecks14checkAndReportERK7ContextR6Report) @@ -725,9 +681,8 @@ *(.text._ZN32MavlinkStreamNavControllerOutput8get_sizeEv) *(.text._ZN6matrix8wrap_2piIfEET_S1_) *(.text._ZN4uORB7Manager30orb_remove_internal_subscriberEPv) -*(.text._ZN10BMP388_I2C7get_regEh) +*(.text._ZN10BMP388_I2C7get_regEhPh) *(.text._ZN4math17WelfordMeanVectorIfLj3EE5resetEv) -*(.text._ZN30MavlinkStreamUTMGlobalPosition10const_rateEv) *(.text._ZN27MavlinkStreamScaledPressure8get_sizeEv) *(.text._ZN3RTL17parameters_updateEv) *(.text._ZN18EstimatorInterface11setBaroDataERKN9estimator10baroSampleE.part.0) @@ -741,7 +696,6 @@ *(.text._ZN4uORB10DeviceNode10poll_stateEP4file) *(.text._ZN4uORB7Manager8orb_copyEPK12orb_metadataiPv) *(.text._ZN27MavlinkStreamServoOutputRawILi0EE8get_sizeEv) -*(.text._ZN30MavlinkStreamUTMGlobalPosition8get_sizeEv) *(.text._ZN8Geofence3runEv) *(.text._ZN15EstimatorChecks25checkEstimatorStatusFlagsERK7ContextR6ReportRK18estimator_status_sRK24vehicle_local_position_s) *(.text._ZN18MagnetometerChecks14checkAndReportERK7ContextR6Report) @@ -752,7 +706,6 @@ *(.text.read) *(.text._ZN4uORB15PublicationBaseD1Ev) *(.text._ZN22MavlinkStreamDebugVect8get_sizeEv) -*(.text._ZN22MavlinkStreamCollision8get_sizeEv) *(.text._ZN7Mission11on_inactiveEv) *(.text._ZN7sensors19VehicleMagnetometer20UpdateMagCalibrationEv) *(.text._ZN11calibration27FindCurrentCalibrationIndexEPKcm) diff --git a/boards/nxp/tropic-community/nuttx-config/scripts/itcm_static_functions.ld b/boards/nxp/tropic-community/nuttx-config/scripts/itcm_static_functions.ld index 2f6259209a..a14521a6b5 100644 --- a/boards/nxp/tropic-community/nuttx-config/scripts/itcm_static_functions.ld +++ b/boards/nxp/tropic-community/nuttx-config/scripts/itcm_static_functions.ld @@ -3,7 +3,6 @@ *(.text.arm_doirq) *(.text.arm_svcall) *(.text.arm_switchcontext) -*(.text.board_autoled_on) *(.text.clock_timer) *(.text.exception_common) *(.text.flexio_irq_handler) @@ -20,7 +19,6 @@ *(.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_lpspi_exchange) @@ -105,13 +103,12 @@ *(.text.devif_event_trigger) *(.text.devif_poll_icmp) *(.text.icmp_poll) -*(.text.devif_packet_conversion) *(.text.arp_out) *(.text.arp_find) *(.text.arp_format) -*(.text.net_ipv4addr_hdrcmp) -*(.text.net_ipv4addr_copy) -*(.text.net_ipv4addr_broadcast) +*(.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.arp_arpin) *(.text.ipv4_input) diff --git a/boards/px4/fmu-v6xrt/nuttx-config/scripts/itcm_functions_includes.ld b/boards/px4/fmu-v6xrt/nuttx-config/scripts/itcm_functions_includes.ld index 0a4e0faa6a..a52a3b46b0 100644 --- a/boards/px4/fmu-v6xrt/nuttx-config/scripts/itcm_functions_includes.ld +++ b/boards/px4/fmu-v6xrt/nuttx-config/scripts/itcm_functions_includes.ld @@ -2,7 +2,7 @@ *(.text._ZN4uORB7Manager27orb_add_internal_subscriberE6ORB_IDhPj) *(.text._ZN13MavlinkStream6updateERKy) *(.text._ZN7Mavlink16update_rate_multEv) -*(.text._ZN3sym17PredictCovarianceIfEEN6matrix6MatrixIT_Lj23ELj23EEERKNS2_IS3_Lj24ELj1EEERKS4_RKNS2_IS3_Lj3ELj1EEES3_SC_SC_S3_S3_) +*(.text._ZN3sym17PredictCovarianceIfEEN6matrix6MatrixIT_Lj23ELj23EEERKNS2_IS3_Lj24ELj1EEERKS4_RKNS2_IS3_Lj3ELj1EEES3_SC_SC_S3_S3_) /* itcm-check-ignore */ *(.text._ZN13MavlinkStream12get_size_avgEv) *(.text._ZN16ControlAllocator3RunEv) *(.text._ZN22MulticopterRateControl3RunEv.part.0) @@ -57,7 +57,6 @@ *(.text._ZN3px49WorkQueue3AddEPNS_8WorkItemE) *(.text._ZN4EKF220PublishLocalPositionERKy) *(.text._mav_finalize_message_chan_send) -*(.text._ZN3Ekf19fixCovarianceErrorsEb) *(.text._ZN7sensors22VehicleAngularVelocity16ParametersUpdateEb) *(.text._ZN6events12SendProtocol6updateERKy) *(.text._ZN6device3SPI8transferEPhS1_j) @@ -68,7 +67,7 @@ *(.text.nx_poll) *(.text._ZN15MavlinkReceiver3runEv) *(.text._ZN9ICM42688P18ProcessTemperatureEPKN20InvenSense_ICM42688P4FIFO4DATAEh) -*(.text._ZN15OutputPredictor19correctOutputStatesEyRKN6matrix10QuaternionIfEERKNS0_7Vector3IfEES8_S8_S8_) +*(.text._ZN15OutputPredictor19correctOutputStatesEyRKN6matrix10QuaternionIfEERKNS0_7Vector3IfEERK9LatLonAltS8_S8_) *(.text._ZN3Ekf12predictStateERKN9estimator9imuSampleE) *(.text._ZN3px46logger6Logger3runEv) *(.text._ZN4uORB20SubscriptionInterval7updatedEv) @@ -122,7 +121,6 @@ *(.text._ZN22MulticopterRateControl28updateActuatorControlsStatusERK25vehicle_torque_setpoint_sf) *(.text._ZN11RateControl6updateERKN6matrix7Vector3IfEES4_S4_fb) *(.text._ZN39ControlAllocationSequentialDesaturation19desaturateActuatorsERN6matrix6VectorIfLj16EEERKS2_b) -*(.text._ZN22MavlinkStreamCollision4sendEv) *(.text.imxrt_lpi2c_transfer) *(.text.uart_putxmitchar) *(.text.clock_nanosleep) @@ -166,7 +164,7 @@ *(.text._ZN13land_detector23MulticopterLandDetector25_get_ground_contact_stateEv) *(.text.imxrt_dmach_start) *(.text._ZN3ADC19update_system_powerEy) -*(.text._ZNK3Ekf19get_ekf_soln_statusEPt) +*(.text._ZNK3Ekf19get_ekf_soln_statusEv) *(.text._ZN3px46logger15watchdog_updateERNS0_15watchdog_data_tEb) *(.text.imxrt_gpio_read) *(.text._ZN32MavlinkStreamNavControllerOutput4sendEv) @@ -193,11 +191,10 @@ *(.text._ZN22MavlinkStreamGPSStatus4sendEv) *(.text._ZN4EKF220UpdateAirspeedSampleER17ekf2_timestamps_s) *(.text._ZN23MavlinkStreamStatustext4sendEv) -*(.text._ZN3Ekf15constrainStatesEv) *(.text._ZN12PX4IO_serial4readEjPvj) *(.text.uart_poll) *(.text._ZN24MavlinkParametersManager4sendEv) -*(.text._ZN26MulticopterPositionControl18set_vehicle_statesERK24vehicle_local_position_s) +*(.text._ZN26MulticopterPositionControl18set_vehicle_statesERK24vehicle_local_position_sf) *(.text.file_poll) *(.text.hrt_elapsed_time) *(.text._ZN7Mavlink11send_finishEv) @@ -231,8 +228,7 @@ *(.text._ZN6matrix5EulerIfEC1ERKNS_10QuaternionIfEE) *(.text.imxrt_queuedtd) *(.text._ZN27MavlinkStreamDistanceSensor8get_sizeEv) -*(.text._ZN3Ekf16fuseVelPosHeightEffi) -*(.text._ZN3Ekf23controlBaroHeightFusionEv) +*(.text._ZN3Ekf23controlBaroHeightFusionERKN9estimator9imuSampleE) *(.text._ZN16PX4Accelerometer9set_scaleEf) *(.text._ZN11ControlMath11constrainXYERKN6matrix7Vector2IfEES4_RKf) *(.text._ZN22MavlinkStreamEfiStatus4sendEv) @@ -242,13 +238,11 @@ *(.text._ZN15PositionControl11_inputValidEv) *(.text._ZN7sensors14VehicleAirData3RunEv) *(.text.perf_count) -*(.text._ZN3Ekf16controlMagFusionEv) +*(.text._ZN3Ekf16controlMagFusionERKN9estimator9imuSampleE) *(.text.pthread_sem_give) *(.text._ZN7sensors10VehicleIMU16ParametersUpdateEb) -*(.text._ZN30MavlinkStreamUTMGlobalPosition4sendEv) *(.text._ZN4uORB20SubscriptionInterval4copyEPv) *(.text._ZN12I2CSPIDriverI9ICM42688PE3RunEv) -*(.text._ZN17ObstacleAvoidanceC1EP12ModuleParams) *(.text.imxrt_epcomplete.constprop.0) *(.text._ZNK6matrix6MatrixIfLj3ELj1EEmiERKS1_) *(.text._ZN9Commander30handleModeIntentionAndFailsafeEv) @@ -279,7 +273,7 @@ *(.text._ZN6matrix6MatrixIfLj3ELj1EEC1ERKS1_) *(.text.udp_pollsetup) *(.text._ZL14timer_callbackPv) -*(.text._ZN3Ekf4fuseERKN6matrix6VectorIfLj23EEEf) +*(.text._ZN3Ekf4fuseERKN6matrix6VectorIfLj24EEEf) *(.text._ZN13land_detector23MulticopterLandDetector22_set_hysteresis_factorEi) *(.text.nxsem_wait_irq) *(.text._ZN20MavlinkCommandSender4lockEv) @@ -298,7 +292,7 @@ *(.text._ZN25MavlinkStreamHomePosition4sendEv) *(.text._ZN24MavlinkParametersManager8send_oneEv) *(.text._ZN15OutputPredictor29applyCorrectionToOutputBufferERKN6matrix7Vector3IfEES4_) -*(.text._ZN21HealthAndArmingChecks6updateEb) +*(.text._ZN21HealthAndArmingChecks6updateEbb) *(.text._ZThn24_N22MulticopterRateControl3RunEv) *(.text._ZN26MavlinkStreamManualControl4sendEv) *(.text._ZN27MavlinkStreamOpticalFlowRad4sendEv) @@ -307,13 +301,11 @@ *(.text._ZN24MavlinkParametersManager18send_untransmittedEv) *(.text._ZN10MavlinkFTP4sendEv) *(.text._ZN15ArchPX4IOSerial13_do_interruptEv) -*(.text._ZN3Ekf27controlExternalVisionFusionEv) +*(.text._ZN3Ekf27controlExternalVisionFusionERKN9estimator9imuSampleE) *(.text.clock_gettime) *(.text._ZN3ADC17update_adc_reportEy) -*(.text._ZN3sym25ComputeYaw312InnovVarAndHIfEEvRKN6matrix6MatrixIT_Lj24ELj1EEERKNS2_IS3_Lj23ELj23EEES3_S3_PS3_PNS2_IS3_Lj23ELj1EEE) -*(.text._ZN3Ekf19runTerrainEstimatorERKN9estimator9imuSampleE) *(.text._ZN32MavlinkStreamGimbalManagerStatus4sendEv) -*(.text._ZN9LockGuardD1Ev) +*(.text._ZN9LockGuardD1Ev) /* itcm-check-ignore */ *(.text._ZN4EKF213PublishStatesERKy) *(.text._ZN3ADC3RunEv) *(.text._ZN6BMP38815compensate_dataEhPK16bmp3_uncomp_dataP9bmp3_data) @@ -348,7 +340,7 @@ *(.text._ZN15FailureDetector6updateERK16vehicle_status_sRK22vehicle_control_mode_s) *(.text._ZN7Mavlink10send_startEi) *(.text.imxrt_lpspi_setbits) -*(.text._ZN15OutputPredictor37applyCorrectionToVerticalOutputBufferEf) +*(.text._ZN15OutputPredictor37applyCorrectionToVerticalOutputBufferEff) *(.text._ZN4EKF222UpdateAccelCalibrationERKy) *(.text._ZN7sensors19VehicleMagnetometer3RunEv) *(.text._ZN29MavlinkStreamMountOrientation4sendEv) @@ -363,15 +355,13 @@ *(.text.poll) *(.text._ZN14FlightTaskAutoD1Ev) *(.text._ZN4uORB10DeviceNode22get_initial_generationEv) -*(.text._ZN3Ekf23controlGnssHeightFusionERKN9estimator9gpsSampleE) +*(.text._ZN3Ekf23controlGnssHeightFusionERKN9estimator10gnssSampleE) *(.text._ZN3Ekf40updateOnGroundMotionForOpticalFlowChecksEv) *(.text._ZN6matrix6MatrixIfLj3ELj1EEC1Ev) *(.text._ZN14ZeroGyroUpdate6updateER3EkfRKN9estimator9imuSampleE) *(.text._ZN30MavlinkStreamOpenDroneIdSystem4sendEv) *(.text._ZN22MavlinkStreamScaledIMU4sendEv) -*(.text._ZN46MavlinkStreamTrajectoryRepresentationWaypoints4sendEv) *(.text.imxrt_ioctl) -*(.text._ZN3Ekf25checkMagBiasObservabilityEv) *(.text._ZN36MavlinkStreamGimbalDeviceSetAttitude4sendEv) *(.text._ZN4math13expo_deadzoneIfEEKT_RS2_S3_S3_.isra.0) *(.text._ZN19StickAccelerationXYC1EP12ModuleParams) @@ -401,7 +391,7 @@ *(.text._ZN9Commander11updateTunesEv) *(.text._ZN4EKF215UpdateMagSampleER17ekf2_timestamps_s) *(.text._ZN18DataValidatorGroup3putEjyPKfmh) -*(.text._ZNK3Ekf19get_ekf_ctrl_limitsEPfS0_S0_S0_) +*(.text._ZNK3Ekf19get_ekf_ctrl_limitsEPfS0_S0_S0_S0_) *(.text._ZN12FailsafeBase13checkFailsafeEibbRKNS_13ActionOptionsE) *(.text._ZN17FlightTaskDescendD1Ev) *(.text._ZN30MavlinkStreamOpenDroneIdSystem8get_sizeEv) @@ -409,7 +399,6 @@ *(.text._ZN24FlightTaskManualAltitudeD1Ev) *(.text._Z35px4_indicate_external_reset_lockout16LockoutComponentb) *(.text.uart_pollnotify) -*(.text._ZN3Ekf11predictHaglERKN9estimator9imuSampleE) *(.text._ZN4EKF215PublishBaroBiasERKy) *(.text._ZN4EKF221UpdateGyroCalibrationERKy) *(.text._ZN6matrix9constrainIfLj3ELj1EEENS_6MatrixIT_XT0_EXT1_EEERKS3_S2_S2_) @@ -440,7 +429,7 @@ *(.text.clock_systime_timespec) *(.text._ZN4uORB10DeviceNode26remove_internal_subscriberEv) *(.text._ZThn16_N4EKF23RunEv) -*(.text._ZNK3Ekf22computeYawInnovVarAndHEfRfRN6matrix6VectorIfLj23EEE) +*(.text._ZNK3Ekf22computeYawInnovVarAndHEfRfRN6matrix6VectorIfLj24EEE) *(.text._ZN12ActuatorTest6updateEif) *(.text._ZN17VelocitySmoothingC1Efff) *(.text._ZN13AnalogBattery19get_voltage_channelEv) @@ -458,7 +447,7 @@ *(.text.imxrt_config_gpio) *(.text.nxsig_timeout) *(.text._ZN11RateControl19setSaturationStatusERKN6matrix7Vector3IbEES4_) -*(.text._ZN3Ekf17measurementUpdateERN6matrix6VectorIfLj23EEEff) +*(.text._ZN3Ekf17measurementUpdateERN6matrix6VectorIfLj24EEERKS2_ff) *(.text.dq_addlast) *(.text._ZN19MavlinkStreamVFRHUD4sendEv) *(.text.hrt_call_reschedule) @@ -482,14 +471,13 @@ *(.text._ZNK6matrix6MatrixIfLj3ELj1EE5emultERKS1_) *(.text.mallinfo_handler) *(.text._ZN13land_detector23MulticopterLandDetector14_update_topicsEv) -*(.text._ZN24ManualVelocitySmoothingZC1Ev) +*(.text._ZN24ManualVelocitySmoothingZC1Ev) /* itcm-check-ignore */ *(.text._ZN3ADC6sampleEj) *(.text._ZNK3Ekf22isTerrainEstimateValidEv) -*(.text._ZN15EstimatorChecks23setModeRequirementFlagsERK7ContextbbRK24vehicle_local_position_sRK12sensor_gps_sR16failsafe_flags_sR6Report) +*(.text._ZN15EstimatorChecks23setModeRequirementFlagsERK7ContextbbbRK24vehicle_local_position_sRK12sensor_gps_sR16failsafe_flags_sR6Report) *(.text._ZN11ControlMath11addIfNotNanERff) *(.text._ZN9Commander21checkForMissionUpdateEv) *(.text._Z8set_tunei) -*(.text._ZN3Ekf13stopGpsFusionEv) *(.text._ZNK6matrix7Vector3IfE5crossERKNS_6MatrixIfLj3ELj1EEE) *(.text._ZN10FlightTask22_checkEkfResetCountersEv) *(.text._ZNK6matrix6MatrixIfLj3ELj1EE11isAllFiniteEv) @@ -511,7 +499,6 @@ *(.text.MEM_DataCopy2_2) *(.text._ZN10FlightTask8activateERK21trajectory_setpoint_s) *(.text.sock_file_poll) -*(.text._ZN3Ekf20controlHaglRngFusionEv) *(.text._ZN10Ringbuffer9pop_frontEPhj) *(.text.nx_write) *(.text._ZN9Commander18manualControlCheckEv) @@ -533,7 +520,6 @@ *(.text._ZN3LED5ioctlEP4fileim) *(.text._ZNK3px46logger9LogWriter20had_file_write_errorEv) *(.text._ZN29MavlinkStreamLocalPositionNED4sendEv) -*(.text._ZN6matrix6MatrixIfLj2ELj1EEC1ILj3ELj1EEERKNS_5SliceIfLj2ELj1EXT_EXT0_EEE) *(.text._ZNK6matrix6VectorIfLj3EE3dotERKNS_6MatrixIfLj3ELj1EEE) *(.text.imxrt_lpi2c_setclock) *(.text._ZN6matrix12typeFunction9constrainIfEET_S2_S2_S2_.part.0) @@ -556,14 +542,12 @@ *(.text._ZThn24_N26MulticopterAttitudeControl3RunEv) *(.text._ZN15ArchPX4IOSerial10_interruptEiPvS0_) *(.text.imxrt_periphclk_configure) -*(.text._ZN3Ekf8initHaglEv) *(.text._ZN4EKF218UpdateAuxVelSampleER17ekf2_timestamps_s) *(.text._ZN3RTL11on_inactiveEv) *(.text._ZN12FailsafeBase10modeCanRunERK16failsafe_flags_sh) *(.text._ZN4EKF216PublishEvPosBiasERKy) *(.text._ZN21MavlinkStreamAttitude8get_sizeEv) *(.text._ZThn16_N7sensors19VehicleAcceleration3RunEv) -*(.text._ZN3Ekf24controlRangeHeightFusionEv) *(.text._ZN33MavlinkStreamTimeEstimateToTarget4sendEv) *(.text._ZN6matrix6MatrixIfLj3ELj1EE6setAllEf) *(.text._ZN12ModuleParamsD1Ev) @@ -581,7 +565,7 @@ *(.text._ZN26MulticopterPositionControl3RunEv) *(.text._ZN8Failsafe21fromQuadchuteActParamEi) *(.text._ZN24VariableLengthRingbuffer9pop_frontEPhj) -*(.text._ZN7control15BlockDerivative6updateEf) +*(.text._ZN7control15BlockDerivative6updateEf) /* itcm-check-ignore */ *(.text._ZN5PX4IO10io_reg_getEhh) *(.text._ZN9Commander18safetyButtonUpdateEv) *(.text._ZN13BatteryChecks14checkAndReportERK7ContextR6Report) @@ -590,7 +574,7 @@ *(.text._ZN4EKF225PublishYawEstimatorStatusERKy) *(.text.sin) *(.text._ZN6Safety19safetyButtonHandlerEv) -*(.text._ZN3Ekf19controlAuxVelFusionEv) +*(.text._ZN3Ekf19controlAuxVelFusionERKN9estimator9imuSampleE) *(.text._ZNK6matrix6MatrixIfLj2ELj1EEplERKS1_) *(.text._ZThn24_N7Sensors3RunEv) *(.text._ZN6matrix6MatrixIfLj2ELj1EEC1ERKS1_) @@ -641,7 +625,6 @@ *(.text._ZN12FailsafeBase11updateDelayERKy) *(.text._ZN10FlightTask25_evaluateDistanceToGroundEv) *(.text._ZN4EKF218PublishGnssHgtBiasERKy) -*(.text._ZN3Ekf21controlHaglFlowFusionEv) *(.text._ZN6matrix6VectorIfLj3EE9normalizeEv) *(.text._ZThn16_N7sensors10VehicleIMU3RunEv) *(.text.__kernel_cos) @@ -653,9 +636,8 @@ *(.text._Z15blink_msg_statev) *(.text._ZN19AccelerometerChecks14checkAndReportERK7ContextR6Report) *(.text._ZN8Failsafe14fromGfActParamEi) -*(.text._ZN3Ekf27checkAndFixCovarianceUpdateERKN6matrix12SquareMatrixIfLj23EEE) *(.text._ZN3Ekf17controlBetaFusionERKN9estimator9imuSampleE) -*(.text._ZN36do_not_explicitly_use_this_namespace5ParamIfLN3px46paramsE919EEC1Ev) +*(.text._ZN36do_not_explicitly_use_this_namespace5ParamIfLN3px46paramsE919EEC1Ev) /* itcm-check-ignore */ *(.text._ZN22MavlinkStreamHeartbeat8get_sizeEv) *(.text._ZN6matrix6MatrixIfLj3ELj1EEdVEf) *(.text._ZN17FlightTaskDescendC1Ev) @@ -666,7 +648,6 @@ *(.text._Z7led_offi) *(.text.led_off) *(.text.udp_wrbuffer_test) -*(.text._ZNK3Ekf34updateVerticalPositionAidSrcStatusERKyfffR24estimator_aid_source1d_s) *(.text._ZNK4math17WelfordMeanVectorIfLj3EE8varianceEv) *(.text._ZN27MavlinkStreamAttitudeTarget4sendEv) *(.text._ZN12MixingOutput19updateSubscriptionsEb) @@ -692,11 +673,9 @@ *(.text._ZN12SystemChecks14checkAndReportERK7ContextR6Report) *(.text._ZN6matrix6MatrixIfLj3ELj1EEC1EPKf) *(.text.imxrt_padmux_address) -*(.text._ZN3Ekf15setVelPosStatusEib) *(.text._ZN19MavlinkStreamVFRHUD8get_sizeEv) *(.text._ZN15EstimatorChecks15checkSensorBiasERK7ContextR6Report8NavModes) *(.text._ZN20ImuConsistencyChecks14checkAndReportERK7ContextR6Report) -*(.text._ZN17ObstacleAvoidanceD1Ev) *(.text._ZN28MavlinkStreamGpsGlobalOrigin8get_sizeEv) *(.text.MEM_DataCopy2_1) *(.text._ZN6BMP3887measureEv) @@ -704,7 +683,7 @@ *(.text._ZN36MavlinkStreamPositionTargetGlobalInt8get_sizeEv) *(.text._ZN28MavlinkStreamEstimatorStatus8get_sizeEv) *(.text.up_clean_dcache) -*(.text._ZThn56_N26MulticopterPositionControl3RunEv) +*(.text._ZThn24_N26MulticopterPositionControl3RunEv) *(.text._ZN16FlightTimeChecks14checkAndReportERK7ContextR6Report) *(.text._ZN13ManualControl12processInputEy) *(.text._ZN17CpuResourceChecks14checkAndReportERK7ContextR6Report) @@ -716,9 +695,8 @@ *(.text._ZN32MavlinkStreamNavControllerOutput8get_sizeEv) *(.text._ZN6matrix8wrap_2piIfEET_S1_) *(.text._ZN4uORB7Manager30orb_remove_internal_subscriberEPv) -*(.text._ZN10BMP388_I2C7get_regEh) +*(.text._ZN10BMP388_I2C7get_regEhPh) *(.text._ZN4math17WelfordMeanVectorIfLj3EE5resetEv) -*(.text._ZN30MavlinkStreamUTMGlobalPosition10const_rateEv) *(.text._ZN27MavlinkStreamScaledPressure8get_sizeEv) *(.text._ZN3RTL17parameters_updateEv) *(.text._ZN18EstimatorInterface11setBaroDataERKN9estimator10baroSampleE.part.0) @@ -732,7 +710,6 @@ *(.text._ZN4uORB10DeviceNode10poll_stateEP4file) *(.text._ZN4uORB7Manager8orb_copyEPK12orb_metadataiPv) *(.text._ZN27MavlinkStreamServoOutputRawILi0EE8get_sizeEv) -*(.text._ZN30MavlinkStreamUTMGlobalPosition8get_sizeEv) *(.text._ZN8Geofence3runEv) *(.text._ZN15EstimatorChecks25checkEstimatorStatusFlagsERK7ContextR6ReportRK18estimator_status_sRK24vehicle_local_position_s) *(.text._ZN18MagnetometerChecks14checkAndReportERK7ContextR6Report) @@ -743,7 +720,6 @@ *(.text.read) *(.text._ZN4uORB15PublicationBaseD1Ev) *(.text._ZN22MavlinkStreamDebugVect8get_sizeEv) -*(.text._ZN22MavlinkStreamCollision8get_sizeEv) *(.text._ZN7Mission11on_inactiveEv) *(.text._ZN7sensors19VehicleMagnetometer20UpdateMagCalibrationEv) *(.text._ZN11calibration27FindCurrentCalibrationIndexEPKcm)