Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/Tools/scripts/extract_features.py
Views: 1798
#!/usr/bin/env python12"""3script to determine what features have been built into an ArduPilot binary45AP_FLAKE8_CLEAN6"""7import argparse8import os9import re10import string11import subprocess12import sys13import time14import build_options15import select161718if sys.version_info[0] < 3:19running_python3 = False20else:21running_python3 = True222324class ExtractFeatures(object):2526class FindString(object):27def __init__(self, string):28self.string = string2930def __init__(self, filename, nm="arm-none-eabi-nm", strings="strings"):31self.filename = filename32self.nm = nm33self.strings = strings3435# feature_name should match the equivalent feature in36# build_options.py ('FEATURE_NAME', 'EXPECTED_SYMBOL').37# EXPECTED_SYMBOL is a regular expression which will be matched38# against "define" in build_options's feature list, and39# FEATURE_NAME will have substitutions made from the match.40# the substitutions will be upper-cased41self.features = [42('AP_ADVANCEDFAILSAFE_ENABLED', r'AP_AdvancedFailsafe::heartbeat\b',),43('AP_BOOTLOADER_FLASHING_ENABLED', 'ChibiOS::Util::flash_bootloader',),44('AP_AIRSPEED_ENABLED', 'AP_Airspeed::AP_Airspeed',),45('AP_AIRSPEED_{type}_ENABLED', r'AP_Airspeed_(?P<type>.*)::init',),4647('AC_PRECLAND_ENABLED', 'AC_PrecLand::AC_PrecLand',),48('AC_PRECLAND_ENABLED', 'AC_PrecLand::AC_PrecLand',),49('AC_PRECLAND_{type}_ENABLED', 'AC_PrecLand_(?P<type>.*)::update',),5051('HAL_ADSB_ENABLED', 'AP_ADSB::AP_ADSB',),52('HAL_ADSB_{type}_ENABLED', r'AP_ADSB_(?P<type>.*)::update',),53('HAL_ADSB_UCP_ENABLED', 'AP_ADSB_uAvionix_UCP::update',),5455('AP_COMPASS_{type}_ENABLED', r'AP_Compass_(?P<type>.*)::read\b',),56('AP_COMPASS_ICM20948_ENABLED', r'AP_Compass_AK09916::probe_ICM20948',),57('AP_COMPASS_DRONECAN_HIRES_ENABLED', r'AP_Compass_DroneCAN::handle_magnetic_field_hires',),5859('AP_AIS_ENABLED', 'AP_AIS::AP_AIS',),6061('HAL_EFI_ENABLED', 'AP_EFI::AP_EFI',),62('AP_EFI_{type}_ENABLED', 'AP_EFI_(?P<type>.*)::update',),6364('AP_EXTENDED_ESC_TELEM_ENABLED', r'AP_DroneCAN::handle_esc_ext_status\b',),6566('AP_TEMPERATURE_SENSOR_ENABLED', 'AP_TemperatureSensor::AP_TemperatureSensor',),67('AP_TEMPERATURE_SENSOR_{type}_ENABLED', 'AP_TemperatureSensor_(?P<type>.*)::update',),6869('AP_BEACON_ENABLED', 'AP_Beacon::AP_Beacon',),70('HAL_TORQEEDO_ENABLED', 'AP_Torqeedo::AP_Torqeedo'),7172('HAL_NAVEKF3_AVAILABLE', 'NavEKF3::NavEKF3',),73('HAL_NAVEKF2_AVAILABLE', 'NavEKF2::NavEKF2',),74('HAL_EXTERNAL_AHRS_ENABLED', r'AP_ExternalAHRS::init\b',),75('AP_EXTERNAL_AHRS_{type}_ENABLED', r'AP_ExternalAHRS_(?P<type>.*)::healthy\b',),76('HAL_INS_TEMPERATURE_CAL_ENABLE', 'AP_InertialSensor_TCal::Learn::save_calibration',),77('HAL_VISUALODOM_ENABLED', 'AP_VisualOdom::init',),7879('AP_RANGEFINDER_ENABLED', 'RangeFinder::RangeFinder',),80('AP_RANGEFINDER_{type}_ENABLED', r'AP_RangeFinder_(?P<type>.*)::update\b',),81('AP_RANGEFINDER_{type}_ENABLED', r'AP_RangeFinder_(?P<type>.*)::get_reading\b',),82('AP_RANGEFINDER_{type}_ENABLED', r'AP_RangeFinder_(?P<type>.*)::model_dist_max_cm\b',),83('AP_RANGEFINDER_{type}_ENABLED', r'AP_RangeFinder_(?P<type>.*)::handle_frame\b',),84('AP_RANGEFINDER_LIGHTWARE_SERIAL_ENABLED', r'AP_RangeFinder_LightWareSerial::get_reading\b',),85('AP_RANGEFINDER_LWI2C_ENABLED', r'AP_RangeFinder_LightWareI2C::update\b',),86('AP_RANGEFINDER_MAXBOTIX_SERIAL_ENABLED', r'AP_RangeFinder_MaxsonarSerialLV::get_reading\b',),87('AP_RANGEFINDER_TRI2C_ENABLED', r'AP_RangeFinder_TeraRangerI2C::update\b',),88('AP_RANGEFINDER_JRE_SERIAL_ENABLED', r'AP_RangeFinder_JRE_Serial::get_reading\b',),89('AP_RANGEFINDER_RDS02UF_ENABLED', r'AP_RangeFinder_RDS02UF::get_reading\b',),9091('AP_GPS_NMEA_UNICORE_ENABLED', r'AP_GPS_NMEA::parse_agrica_field',),92('AP_GPS_{type}_ENABLED', r'AP_GPS_(?P<type>.*)::read\b',),9394('AP_OPTICALFLOW_ENABLED', 'AP_OpticalFlow::AP_OpticalFlow',),95('AP_OPTICALFLOW_{type}_ENABLED', r'AP_OpticalFlow_(?P<type>.*)::update\b',),9697('AP_BARO_{type}_ENABLED', r'AP_Baro_(?P<type>.*)::update\b',),9899('AP_MOTORS_FRAME_{type}_ENABLED', r'AP_MotorsMatrix::setup_(?P<type>.*)_matrix\b',),100101('HAL_MSP_ENABLED', r'AP_MSP::init\b',),102('HAL_MSP_{type}_ENABLED', r'AP_(?P<type>.*)_MSP::update\b',),103('HAL_MSP_{type}_ENABLED', r'AP_(?P<type>.*)_MSP::read\b',),104('HAL_WITH_MSP_DISPLAYPORT', r'AP_OSD_MSP_DisplayPort::init\b',),105106107('AP_BATTERY_{type}_ENABLED', r'AP_BattMonitor_(?P<type>.*)::init\b',),108('AP_BATTERY_ESC_TELEM_OUTBOUND_ENABLED', r'AP_BattMonitor_Backend::update_esc_telem_outbound\b',),109('AP_BATTERY_WATT_MAX_ENABLED', 'Plane::throttle_watt_limiter',),110111('HAL_MOUNT_ENABLED', 'AP_Mount::AP_Mount',),112('HAL_MOUNT_{type}_ENABLED', r'AP_Mount_(?P<type>.*)::update\b',),113('HAL_SOLO_GIMBAL_ENABLED', 'AP_Mount_SoloGimbal::init',),114('HAL_MOUNT_STORM32SERIAL_ENABLED', 'AP_Mount_SToRM32_serial::update',),115('HAL_MOUNT_STORM32MAVLINK_ENABLED', 'AP_Mount_SToRM32::update',),116117('HAL_SPEKTRUM_TELEM_ENABLED', r'AP::spektrum_telem',),118('HAL_{type}_TELEM_ENABLED', r'AP_(?P<type>.*)_Telem::init',),119('AP_{type}_TELEM_ENABLED', r'AP_(?P<type>.*)_Telem::init',),120('HAL_CRSF_TELEM_TEXT_SELECTION_ENABLED', 'AP_CRSF_Telem::calc_text_selection',),121('AP_LTM_TELEM_ENABLED', 'AP_LTM_Telem::init',),122('HAL_HIGH_LATENCY2_ENABLED', 'GCS_MAVLINK::handle_control_high_latency',),123124('AP_FRSKY_TELEM_ENABLED', 'AP::frsky_telem',),125('AP_FRSKY_D_TELEM_ENABLED', 'AP_Frsky_D::send',),126('AP_FRSKY_SPORT_TELEM_ENABLED', 'AP_Frsky_SPort::send_sport_frame',),127('AP_FRSKY_SPORT_PASSTHROUGH_ENABLED', 'AP_Frsky_SPort_Passthrough::process_packet',),128('HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL', 'AP_Frsky_SPort_Passthrough::set_telem_data'),129130('AP_IBUS_TELEM_ENABLED', 'AP_IBus_Telem::init',),131132('MODE_AUTOLAND_ENABLED', 'ModeAutoLand::update'),133('MODE_{type}_ENABLED', r'Mode(?P<type>.+)::init',),134('MODE_GUIDED_NOGPS_ENABLED', r'ModeGuidedNoGPS::init',),135136('AP_CAMERA_ENABLED', 'AP_Camera::var_info',),137('AP_CAMERA_{type}_ENABLED', 'AP_Camera_(?P<type>.*)::trigger_pic',),138('AP_CAMERA_SEND_FOV_STATUS_ENABLED', 'AP_Camera::send_camera_fov_status'),139('AP_CAMERA_SEND_THERMAL_RANGE_ENABLED', 'AP_Camera::send_camera_thermal_range'),140('AP_CAMERA_INFO_FROM_SCRIPT_ENABLED', 'AP_Camera_Backend::set_camera_information'),141('AP_CAMERA_RUNCAM_ENABLED', 'AP_RunCam::AP_RunCam',),142143('HAL_PROXIMITY_ENABLED', 'AP_Proximity::AP_Proximity',),144('AP_PROXIMITY_{type}_ENABLED', 'AP_Proximity_(?P<type>.*)::update',),145('AP_PROXIMITY_CYGBOT_ENABLED', 'AP_Proximity_Cygbot_D1::update',),146('AP_PROXIMITY_LIGHTWARE_{type}_ENABLED', 'AP_Proximity_LightWare(?P<type>.*)::update',),147148('HAL_PARACHUTE_ENABLED', 'AP_Parachute::update',),149('AP_FENCE_ENABLED', r'AC_Fence::check\b',),150('HAL_RALLY_ENABLED', 'AP_Rally::find_nearest_rally_point',),151('AP_AVOIDANCE_ENABLED', 'AC_Avoid::AC_Avoid',),152('AP_OAPATHPLANNER_ENABLED', 'AP_OAPathPlanner::AP_OAPathPlanner',),153('AC_PAYLOAD_PLACE_ENABLED', 'PayloadPlace::start_descent'),154('AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED', ExtractFeatures.FindString('PayloadPlace')),155('AP_ICENGINE_ENABLED', 'AP_ICEngine::AP_ICEngine',),156('HAL_EFI_ENABLED', 'AP_RPM_EFI::AP_RPM_EFI',),157('AP_EFI_NWPWU_ENABLED', r'AP_EFI_NWPMU::update\b',),158('AP_EFI_CURRAWONG_ECU_ENABLED', r'AP_EFI_Currawong_ECU::update\b',),159('AP_EFI_SERIAL_HIRTH_ENABLED', r'AP_EFI_Serial_Hirth::update\b',),160('HAL_GENERATOR_ENABLED', 'AP_Generator::AP_Generator',),161('AP_GENERATOR_{type}_ENABLED', r'AP_Generator_(?P<type>.*)::init',),162163('OSD_ENABLED', 'AP_OSD::update_osd',),164('HAL_PLUSCODE_ENABLE', 'AP_OSD_Screen::draw_pluscode',),165('OSD_PARAM_ENABLED', 'AP_OSD_ParamScreen::AP_OSD_ParamScreen',),166('HAL_OSD_SIDEBAR_ENABLE', 'AP_OSD_Screen::draw_sidebars',),167168('AP_VIDEOTX_ENABLED', 'AP_VideoTX::AP_VideoTX',),169('AP_SMARTAUDIO_ENABLED', 'AP_SmartAudio::AP_SmartAudio',),170('AP_TRAMP_ENABLED', 'AP_Tramp::AP_Tramp',),171172('AP_CHECK_FIRMWARE_ENABLED', 'AP_CheckFirmware::check_signed_bootloader',),173174('HAL_QUADPLANE_ENABLED', 'QuadPlane::QuadPlane',),175('AP_PLANE_GLIDER_PULLUP_ENABLED', 'GliderPullup::in_pullup',),176('QAUTOTUNE_ENABLED', 'ModeQAutotune::_enter',),177('HAL_SOARING_ENABLED', 'SoaringController::var_info',),178('HAL_LANDING_DEEPSTALL_ENABLED', r'AP_Landing_Deepstall::override_servos',),179180('AP_GRIPPER_ENABLED', r'AP_Gripper::init\b',),181('HAL_SPRAYER_ENABLED', 'AC_Sprayer::AC_Sprayer',),182('AP_LANDINGGEAR_ENABLED', r'AP_LandingGear::init\b',),183('AP_WINCH_ENABLED', 'AP_Winch::AP_Winch',),184('AP_WINCH_{type}_ENABLED', r'AP_Winch_(?P<type>.*)::update\b',),185('AP_RELAY_ENABLED', 'AP_Relay::init',),186('AP_SERVORELAYEVENTS_ENABLED', 'AP_ServoRelayEvents::update_events',),187188('AP_RCPROTOCOL_ENABLED', r'AP_RCProtocol::init\b',),189('AP_RCPROTOCOL_MAVLINK_RADIO_ENABLED', r'AP_RCProtocol_MAVLinkRadio::update_radio_rc_channels',),190('AP_RCPROTOCOL_{type}_ENABLED', r'AP_RCProtocol_(?P<type>.*)::_process_byte\b',),191('AP_RCPROTOCOL_{type}_ENABLED', r'AP_RCProtocol_(?P<type>.*)::process_pulse\b',),192193('AP_SERVO_TELEM_ENABLED', r'AP_Servo_Telem::update\b',),194('AP_VOLZ_ENABLED', r'AP_Volz_Protocol::init\b',),195('AP_DRONECAN_VOLZ_FEEDBACK_ENABLED', r'AP_DroneCAN::handle_actuator_status_Volz\b',),196('AP_ROBOTISSERVO_ENABLED', r'AP_RobotisServo::init\b',),197('AP_FETTEC_ONEWIRE_ENABLED', r'AP_FETtecOneWire::init\b',),198('AP_SBUSOUTPUT_ENABLED', 'AP_SBusOut::sbus_format_frame',),199('AP_KDECAN_ENABLED', r'AP_KDECAN::update\b',),200201('AP_RPM_ENABLED', 'AP_RPM::AP_RPM',),202('AP_RPM_{type}_ENABLED', r'AP_RPM_(?P<type>.*)::update',),203204('AP_OPENDRONEID_ENABLED', 'AP_OpenDroneID::update',),205206('GPS_MOVING_BASELINE', r'MovingBase::var_info',),207('AP_DRONECAN_SEND_GPS', r'AP_GPS_DroneCAN::instance_exists\b',),208('AP_GPS_BLENDED_ENABLED', r'AP_GPS::calc_blend_weights\b',),209210('HAL_WITH_DSP', r'AP_HAL::DSP::find_peaks\b',),211('AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED', r'AP_InertialSensor::HarmonicNotch::update_params\b',),212('AP_INERTIALSENSOR_BATCHSAMPLER_ENABLED', r'AP_InertialSensor::BatchSampler::init'),213('AP_INERTIALSENSOR_FAST_SAMPLE_WINDOW_ENABLED', r'FastRateBuffer::get_next_gyro_sample\b',),214('HAL_GYROFFT_ENABLED', r'AP_GyroFFT::AP_GyroFFT\b',),215('HAL_DISPLAY_ENABLED', r'Display::init\b',),216('HAL_NMEA_OUTPUT_ENABLED', r'AP_NMEA_Output::update\b',),217('HAL_BARO_WIND_COMP_ENABLED', r'AP_Baro::wind_pressure_correction\b',),218('AP_TEMPCALIBRATION_ENABLED', r'AP_TempCalibration::apply_calibration',),219220('HAL_PICCOLO_CAN_ENABLE', r'AP_PiccoloCAN::update',),221('EK3_FEATURE_EXTERNAL_NAV', r'NavEKF3_core::CorrectExtNavVelForSensorOffset'),222('EK3_FEATURE_DRAG_FUSION', r'NavEKF3_core::FuseDragForces'),223('EK3_FEATURE_OPTFLOW_FUSION', r'NavEKF3_core::FuseOptFlow'),224225('AP_RC_CHANNEL_AUX_FUNCTION_STRINGS_ENABLED', r'RC_Channel::lookuptable',),226('AP_SCRIPTING_ENABLED', r'AP_Scripting::init',),227('AP_SCRIPTING_SERIALDEVICE_ENABLED', r'AP_Scripting_SerialDevice::init',),228229('AP_NOTIFY_TONEALARM_ENABLED', r'AP_ToneAlarm::init'),230('AP_NOTIFY_MAVLINK_PLAY_TUNE_SUPPORT_ENABLED', r'AP_Notify::handle_play_tune'),231('AP_NOTIFY_MAVLINK_LED_CONTROL_SUPPORT_ENABLED', r'AP_Notify::handle_led_control'),232('AP_NOTIFY_NCP5623_ENABLED', r'NCP5623::write'),233('AP_NOTIFY_PROFILED_ENABLED', r'ProfiLED::init_ports'),234('AP_NOTIFY_PROFILED_SPI_ENABLED', r'ProfiLED_SPI::rgb_set_id'),235('AP_NOTIFY_NEOPIXEL_ENABLED', r'NeoPixel::init_ports'),236('AP_FILESYSTEM_FORMAT_ENABLED', r'AP_Filesystem::format'),237238('AP_FILESYSTEM_{type}_ENABLED', r'AP_Filesystem_(?P<type>.*)::open'),239240('AP_INERTIALSENSOR_KILL_IMU_ENABLED', r'AP_InertialSensor::kill_imu'),241('AP_CRASHDUMP_ENABLED', 'CrashCatcher_DumpMemory'),242('AP_CAN_SLCAN_ENABLED', 'SLCAN::CANIface::var_info'),243('AC_POLYFENCE_FENCE_POINT_PROTOCOL_SUPPORT', 'AC_PolyFence_loader::handle_msg_fetch_fence_point'),244('AP_MAVLINK_RALLY_POINT_PROTOCOL_ENABLED', 'GCS_MAVLINK::handle_common_rally_message'),245246('AP_SDCARD_STORAGE_ENABLED', 'StorageAccess::attach_file'),247('AP_MAVLINK_AUTOPILOT_VERSION_REQUEST_ENABLED', 'GCS_MAVLINK::handle_send_autopilot_version'),248('AP_MAVLINK_MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES_ENABLED', 'GCS_MAVLINK::handle_command_request_autopilot_capabilities'), # noqa249('AP_MAVLINK_MSG_RELAY_STATUS_ENABLED', 'GCS_MAVLINK::send_relay_status'),250('AP_MAVLINK_MSG_DEVICE_OP_ENABLED', 'GCS_MAVLINK::handle_device_op_write'),251('AP_MAVLINK_SERVO_RELAY_ENABLED', 'GCS_MAVLINK::handle_servorelay_message'),252('AP_MAVLINK_MSG_SERIAL_CONTROL_ENABLED', 'GCS_MAVLINK::handle_serial_control'),253('AP_MAVLINK_MSG_MISSION_REQUEST_ENABLED', r'GCS_MAVLINK::handle_mission_request\b'),254('AP_MAVLINK_MSG_RC_CHANNELS_RAW_ENABLED', r'GCS_MAVLINK::send_rc_channels_raw\b'),255('AP_MAVLINK_FTP_ENABLED', 'GCS_MAVLINK::ftp_worker'),256('AP_MAVLINK_MAV_CMD_SET_HAGL_ENABLED', 'Plane::handle_external_hagl'),257('AP_MAVLINK_MSG_VIDEO_STREAM_INFORMATION_ENABLED', 'AP_Camera::send_video_stream_information'),258259('AP_DRONECAN_HIMARK_SERVO_SUPPORT', 'AP_DroneCAN::SRV_send_himark'),260('AP_DRONECAN_HOBBYWING_ESC_SUPPORT', 'AP_DroneCAN::hobbywing_ESC_update'),261('COMPASS_CAL_ENABLED', 'CompassCalibrator::stop'),262('AP_TUNING_ENABLED', 'AP_Tuning::check_input'),263('AP_DRONECAN_SERIAL_ENABLED', 'AP_DroneCAN_Serial::update'),264('AP_SERIALMANAGER_IMUOUT_ENABLED', 'AP_InertialSensor::send_uart_data'),265('AP_NETWORKING_BACKEND_PPP', 'AP_Networking_PPP::init'),266('AP_NETWORKING_CAN_MCAST_ENABLED', 'AP_Networking_CAN::start'),267('FORCE_APJ_DEFAULT_PARAMETERS', 'AP_Param::param_defaults_data'),268('HAL_BUTTON_ENABLED', 'AP_Button::update'),269('HAL_LOGGING_ENABLED', 'AP_Logger::init'),270('AP_COMPASS_CALIBRATION_FIXED_YAW_ENABLED', 'Compass::mag_cal_fixed_yaw'),271('COMPASS_LEARN_ENABLED', 'CompassLearn::update'),272('AP_CUSTOMROTATIONS_ENABLED', 'AP_CustomRotations::init'),273('AP_OSD_LINK_STATS_EXTENSIONS_ENABLED', r'AP_OSD_Screen::draw_rc_tx_power'),274('HAL_ENABLE_DRONECAN_DRIVERS', r'AP_DroneCAN::init'),275('AP_BARO_PROBE_EXTERNAL_I2C_BUSES', r'AP_Baro::_probe_i2c_barometers'),276('AP_RSSI_ENABLED', r'AP_RSSI::init'),277278('AP_ROVER_ADVANCED_FAILSAFE_ENABLED', r'Rover::afs_fs_check'),279('AP_COPTER_ADVANCED_FAILSAFE_ENABLED', r'Copter::afs_fs_check'),280281('AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED', r'GCS_MAVLINK_Plane::handle_command_int_guided_slew_commands'),282('AP_SERIALMANAGER_REGISTER_ENABLED', r'AP_SerialManager::register_port'),283('AP_QUICKTUNE_ENABLED', r'AP_Quicktune::update'),284('AP_FILTER_ENABLED', r'AP_Filters::update'),285('AP_CAN_LOGGING_ENABLED', r'AP_CANManager::can_logging_callback'),286]287288def progress(self, msg):289"""Pretty-print progress."""290print("EF: %s" % msg)291292def validate_features_list(self):293'''ensures that every define present in build_options.py could be294found by in our features list'''295# a list of problematic defines we don't have fixes for ATM:296whitelist = frozenset([297'HAL_PERIPH_SUPPORT_LONG_CAN_PRINTF', # this define changes single method body, hard to detect?298'AP_PLANE_BLACKBOX_LOGGING', # no visible signature299])300for option in build_options.BUILD_OPTIONS:301if option.define in whitelist:302continue303matched = False304for (define, _) in self.features:305# replace {type} with "match any number of word characters'''306define_re = "^" + re.sub(r"{type}", "\\\\w+", define) + "$"307# print("define re is (%s)" % define_re)308if re.match(define_re, option.define):309matched = True310break311if not matched:312raise ValueError("feature (%s) is not matched in extract_features" %313(option.define))314315def run_program(self, prefix, cmd_list, show_output=True, env=None):316"""Swiped from build_binaries.py."""317if show_output:318self.progress("Running (%s)" % " ".join(cmd_list))319p = subprocess.Popen(320cmd_list,321stdin=None,322stdout=subprocess.PIPE,323close_fds=True,324stderr=subprocess.PIPE,325env=env)326stderr = bytearray()327output = ""328while True:329# read all of stderr:330while True:331(rin, _, _) = select.select([p.stderr.fileno()], [], [], 0)332if p.stderr.fileno() not in rin:333break334new = p.stderr.read()335if len(new) == 0:336break337stderr += new338339x = p.stdout.readline()340if len(x) == 0:341(rin, _, _) = select.select([p.stderr.fileno()], [], [], 0)342if p.stderr.fileno() in rin:343stderr += p.stderr.read()344345returncode = os.waitpid(p.pid, 0)346if returncode:347break348# select not available on Windows... probably...349time.sleep(0.1)350continue351if running_python3:352x = bytearray(x)353x = filter(lambda x: chr(x) in string.printable, x)354x = "".join([chr(c) for c in x])355output += x356x = x.rstrip()357if show_output:358print("%s: %s" % (prefix, x))359(_, status) = returncode360if status != 0:361stderr = stderr.decode('utf-8')362self.progress("Process failed (%s) (%s)" %363(str(returncode), stderr))364raise subprocess.CalledProcessError(365status, cmd_list, output=str(output), stderr=str(stderr))366return output367368class Symbols(object):369def __init__(self):370self.symbols = dict()371self.symbols_without_arguments = dict()372373def add(self, key, attributes):374self.symbols[key] = attributes375376# also keep around the same symbol name without arguments.377# if the key is already present then the attributes become378# None as there are multiple possible answers...379m = re.match("^([^(]+).*", key)380if m is None:381extracted_symbol_name = key382else:383extracted_symbol_name = m.group(1)384# print("Adding (%s)" % str(extracted_symbol_name))385if extracted_symbol_name in self.symbols_without_arguments:386self.symbols_without_arguments[extracted_symbol_name] = None387else:388self.symbols_without_arguments[extracted_symbol_name] = attributes389390def dict_for_symbol(self, symbol):391if '(' not in symbol:392some_dict = self.symbols_without_arguments393else:394some_dict = self.symbols395return some_dict396397def extract_symbols_from_elf(self, filename):398"""Parses ELF in filename, returns dict of symbols=>attributes."""399text_output = self.run_program('EF', [400self.nm,401'--demangle',402'--print-size',403filename404], show_output=False)405ret = ExtractFeatures.Symbols()406for line in text_output.split("\n"):407m = re.match("^([^ ]+) ([^ ]+) ([^ ]) (.*)", line.rstrip())408if m is None:409m = re.match("^([^ ]+) ([^ ]) (.*)", line.rstrip())410if m is None:411# raise ValueError("Did not match (%s)" % line)412# e.g. Did not match ( U _errno)413continue414(offset, symbol_type, symbol_name) = m.groups()415size = "0"416else:417(offset, size, symbol_type, symbol_name) = m.groups()418size = int(size, 16)419# print("symbol (%s) size %u" % (str(symbol_name), size))420ret.add(symbol_name, {421"size": size,422})423424return ret425426def extract_strings_from_elf(self, filename):427"""Runs strings on filename, returns as a list"""428text_output = self.run_program('EF', [429self.strings,430filename431], show_output=False)432return text_output.split("\n")433434def extract(self):435'''returns two sets - compiled_in and not_compiled_in'''436437build_options_defines = set([x.define for x in build_options.BUILD_OPTIONS])438439symbols = self.extract_symbols_from_elf(self.filename)440strings = self.extract_strings_from_elf(self.filename)441442remaining_build_options_defines = build_options_defines443compiled_in_feature_defines = []444for (feature_define, symbol) in self.features:445if isinstance(symbol, ExtractFeatures.FindString):446if symbol.string in strings:447some_define = feature_define448if some_define not in build_options_defines:449continue450compiled_in_feature_defines.append(some_define)451remaining_build_options_defines.discard(some_define)452else:453some_dict = symbols.dict_for_symbol(symbol)454# look for symbols without arguments455# print("Looking for (%s)" % str(name))456for s in some_dict.keys():457m = re.match(symbol, s)458# print("matching %s with %s" % (symbol, s))459if m is None:460continue461d = m.groupdict()462for key in d.keys():463d[key] = d[key].upper()464# filter to just the defines present in465# build_options.py - otherwise we end up with (e.g.)466# AP_AIRSPEED_BACKEND_ENABLED, even 'though that467# doesn't exist in the ArduPilot codebase.468some_define = feature_define.format(**d)469if some_define not in build_options_defines:470continue471compiled_in_feature_defines.append(some_define)472remaining_build_options_defines.discard(some_define)473return (compiled_in_feature_defines, remaining_build_options_defines)474475def create_string(self):476'''returns a string with compiled in and not compiled-in features'''477478(compiled_in_feature_defines, not_compiled_in_feature_defines) = self.extract()479480ret = ""481482combined = {}483for define in sorted(compiled_in_feature_defines):484combined[define] = True485for define in sorted(not_compiled_in_feature_defines):486combined[define] = False487488def squash_hal_to_ap(a):489return re.sub("^HAL_", "AP_", a)490491for define in sorted(combined.keys(), key=squash_hal_to_ap):492bang = ""493if not combined[define]:494bang = "!"495ret += bang + define + "\n"496return ret497498def run(self):499self.validate_features_list()500print(self.create_string())501502503if __name__ == '__main__':504505parser = argparse.ArgumentParser(prog='extract_features.py', description='Extract ArduPilot features from binaries')506parser.add_argument('firmware_file', help='firmware binary')507parser.add_argument('-nm', type=str, default="arm-none-eabi-nm", help='nm binary to use.')508args = parser.parse_args()509# print(args.firmware_file, args.nm)510511ef = ExtractFeatures(args.firmware_file, args.nm)512ef.run()513514515