Path: blob/master/Tools/scripts/extract_features.py
9383 views
#!/usr/bin/env python312"""3script to determine what features have been built into an ArduPilot binary45AP_FLAKE8_CLEAN6"""7import argparse8import re9import build_options10from build_script_base import BuildScriptBase111213class ExtractFeatures(BuildScriptBase):1415class FindString(object):16def __init__(self, string):17self.string = string1819def __init__(self, filename, nm="arm-none-eabi-nm", strings="strings"):20super().__init__()21self.filename = filename22self.nm = nm23self.strings = strings2425# feature_name should match the equivalent feature in26# build_options.py ('FEATURE_NAME', 'EXPECTED_SYMBOL').27# EXPECTED_SYMBOL is a regular expression which will be matched28# against "define" in build_options's feature list, and29# FEATURE_NAME will have substitutions made from the match.30# the substitutions will be upper-cased31self.features = [32('AP_ADVANCEDFAILSAFE_ENABLED', r'AP_AdvancedFailsafe::heartbeat\b',),33('AP_BOOTLOADER_FLASHING_ENABLED', 'ChibiOS::Util::flash_bootloader',),34('AP_AIRSPEED_ENABLED', 'AP_Airspeed::AP_Airspeed',),35('AP_AIRSPEED_{type}_ENABLED', r'AP_Airspeed_(?P<type>.*)::init',),3637('AC_PRECLAND_ENABLED', 'AC_PrecLand::AC_PrecLand',),38('AC_PRECLAND_ENABLED', 'AC_PrecLand::AC_PrecLand',),39('AC_PRECLAND_{type}_ENABLED', 'AC_PrecLand_(?P<type>.*)::update',),4041('HAL_ADSB_ENABLED', 'AP_ADSB::AP_ADSB',),42('HAL_ADSB_{type}_ENABLED', r'AP_ADSB_(?P<type>.*)::update',),43('HAL_ADSB_UCP_ENABLED', 'AP_ADSB_uAvionix_UCP::update',),4445('AP_COMPASS_{type}_ENABLED', r'AP_Compass_(?P<type>.*)::read\b',),46('AP_COMPASS_ICM20948_ENABLED', r'AP_Compass_AK09916::probe_ICM20948',),47('AP_COMPASS_DRONECAN_HIRES_ENABLED', r'AP_Compass_DroneCAN::handle_magnetic_field_hires',),4849('AP_AIS_ENABLED', 'AP_AIS::decode_position_report',),5051('HAL_EFI_ENABLED', 'AP_EFI::AP_EFI',),52('AP_EFI_{type}_ENABLED', 'AP_EFI_(?P<type>.*)::update',),5354('AP_EXTENDED_ESC_TELEM_ENABLED', r'AP_DroneCAN::handle_esc_ext_status\b',),5556('AP_TEMPERATURE_SENSOR_ENABLED', 'AP_TemperatureSensor::AP_TemperatureSensor',),57('AP_TEMPERATURE_SENSOR_{type}_ENABLED', 'AP_TemperatureSensor_(?P<type>.*)::update',),5859('AP_BEACON_ENABLED', 'AP_Beacon::AP_Beacon',),60('HAL_TORQEEDO_ENABLED', 'AP_Torqeedo::AP_Torqeedo'),6162('HAL_NAVEKF3_AVAILABLE', 'NavEKF3::NavEKF3',),63('HAL_NAVEKF2_AVAILABLE', 'NavEKF2::NavEKF2',),64('AP_EXTERNAL_AHRS_ENABLED', r'AP_ExternalAHRS::init\b',),65('AP_EXTERNAL_AHRS_{type}_ENABLED', r'AP_ExternalAHRS_(?P<type>.*)::healthy\b',),66('HAL_INS_TEMPERATURE_CAL_ENABLE', 'AP_InertialSensor_TCal::Learn::save_calibration',),67('HAL_VISUALODOM_ENABLED', 'AP_VisualOdom::init',),6869('AP_RANGEFINDER_ENABLED', 'RangeFinder::RangeFinder',),70('AP_RANGEFINDER_{type}_ENABLED', r'AP_RangeFinder_(?P<type>.*)::update\b',),71('AP_RANGEFINDER_{type}_ENABLED', r'AP_RangeFinder_(?P<type>.*)::get_reading\b',),72('AP_RANGEFINDER_{type}_ENABLED', r'AP_RangeFinder_(?P<type>.*)::model_dist_max_cm\b',),73('AP_RANGEFINDER_{type}_ENABLED', r'AP_RangeFinder_(?P<type>.*)::handle_frame\b',),74('AP_RANGEFINDER_LIGHTWARE_SERIAL_ENABLED', r'AP_RangeFinder_LightWareSerial::get_reading\b',),75('AP_RANGEFINDER_LWI2C_ENABLED', r'AP_RangeFinder_LightWareI2C::update\b',),76('AP_RANGEFINDER_MAXBOTIX_SERIAL_ENABLED', r'AP_RangeFinder_MaxsonarSerialLV::get_reading\b',),77('AP_RANGEFINDER_TRI2C_ENABLED', r'AP_RangeFinder_TeraRangerI2C::update\b',),78('AP_RANGEFINDER_JRE_SERIAL_ENABLED', r'AP_RangeFinder_JRE_Serial::get_reading\b',),79('AP_RANGEFINDER_RDS02UF_ENABLED', r'AP_RangeFinder_RDS02UF::get_reading\b',),80('AP_RANGEFINDER_HEXSOONRADAR_ENABLED', r'AP_RangeFinder_NRA24_CAN::handle_frame'),81('AP_RANGEFINDER_LIGHTWARE_GRF_ENABLED', 'AP_RangeFinder_LightWareGRF::get_reading'),8283('AP_GPS_NMEA_UNICORE_ENABLED', r'AP_GPS_NMEA::parse_agrica_field',),84('AP_GPS_{type}_ENABLED', r'AP_GPS_(?P<type>.*)::read\b',),8586('AP_OPTICALFLOW_ENABLED', 'AP_OpticalFlow::AP_OpticalFlow',),87('AP_OPTICALFLOW_{type}_ENABLED', r'AP_OpticalFlow_(?P<type>.*)::update\b',),8889('AP_BARO_{type}_ENABLED', r'AP_Baro_(?P<type>.*)::(_calculate|update)\b',),9091('AP_MOTORS_TRI_ENABLED', 'AP_MotorsTri::set_frame_class_and_type'),92('AP_MOTORS_FRAME_{type}_ENABLED', r'AP_MotorsMatrix::setup_(?P<type>.*)_matrix\b',),9394('HAL_MSP_ENABLED', r'AP_MSP::init\b',),95('HAL_MSP_{type}_ENABLED', r'AP_(?P<type>.*)_MSP::update\b',),96('HAL_MSP_{type}_ENABLED', r'AP_(?P<type>.*)_MSP::read\b',),97('HAL_WITH_MSP_DISPLAYPORT', r'AP_OSD_MSP_DisplayPort::init\b',),98('AP_MSP_INAV_FONTS_ENABLED', r'AP_OSD_MSP_DisplayPort::write_INAV\b',),99100101('AP_BATTERY_{type}_ENABLED', r'AP_BattMonitor_(?P<type>.*)::init\b',),102('AP_BATTERY_ESC_TELEM_OUTBOUND_ENABLED', r'AP_BattMonitor_Backend::update_esc_telem_outbound\b',),103('AP_BATTERY_WATT_MAX_ENABLED', 'Plane::throttle_watt_limiter',),104105('HAL_MOUNT_ENABLED', 'AP_Mount::AP_Mount',),106('HAL_MOUNT_{type}_ENABLED', r'AP_Mount_(?P<type>.*)::update\b',),107('HAL_SOLO_GIMBAL_ENABLED', 'AP_Mount_SoloGimbal::init',),108('HAL_MOUNT_STORM32SERIAL_ENABLED', 'AP_Mount_SToRM32_serial::update',),109('HAL_MOUNT_STORM32MAVLINK_ENABLED', 'AP_Mount_SToRM32::update',),110('AP_MOUNT_POI_LOCK_ENABLED', 'AP_Mount::set_poi_lock'),111112('HAL_SPEKTRUM_TELEM_ENABLED', r'AP::spektrum_telem',),113('HAL_{type}_TELEM_ENABLED', r'AP_(?P<type>.*)_Telem::init',),114('AP_{type}_TELEM_ENABLED', r'AP_(?P<type>.*)_Telem::init',),115('HAL_CRSF_TELEM_TEXT_SELECTION_ENABLED', 'AP_CRSF_Telem::calc_text_selection',),116('AP_CRSF_SCRIPTING_ENABLED', 'AP_CRSF_Telem::get_menu_event',),117('AP_LTM_TELEM_ENABLED', 'AP_LTM_Telem::init',),118('HAL_HIGH_LATENCY2_ENABLED', 'GCS_MAVLINK::handle_control_high_latency',),119120('AP_FRSKY_TELEM_ENABLED', 'AP::frsky_telem',),121('AP_FRSKY_D_TELEM_ENABLED', 'AP_Frsky_D::send',),122('AP_FRSKY_SPORT_TELEM_ENABLED', 'AP_Frsky_SPort::send_sport_frame',),123('AP_FRSKY_SPORT_PASSTHROUGH_ENABLED', 'AP_Frsky_SPort_Passthrough::process_packet',),124('HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL', 'AP_Frsky_SPort_Passthrough::set_telem_data'),125126('AP_IBUS_TELEM_ENABLED', 'AP_IBus_Telem::init',),127128('MODE_AUTOLAND_ENABLED', 'ModeAutoLand::update'),129('MODE_{type}_ENABLED', r'Mode(?P<type>.+)::init',),130('MODE_GUIDED_NOGPS_ENABLED', r'ModeGuidedNoGPS::init',),131132('AP_CAMERA_ENABLED', 'AP_Camera::var_info',),133('AP_CAMERA_{type}_ENABLED', 'AP_Camera_(?P<type>.*)::trigger_pic',),134('AP_CAMERA_SEND_FOV_STATUS_ENABLED', 'AP_Camera::send_camera_fov_status'),135('AP_CAMERA_SEND_THERMAL_RANGE_ENABLED', 'AP_Camera::send_camera_thermal_range'),136('AP_CAMERA_INFO_FROM_SCRIPT_ENABLED', 'AP_Camera_Backend::set_camera_information'),137('AP_CAMERA_RUNCAM_ENABLED', 'AP_RunCam::AP_RunCam',),138139('HAL_PROXIMITY_ENABLED', 'AP_Proximity::AP_Proximity',),140('AP_PROXIMITY_{type}_ENABLED', 'AP_Proximity_(?P<type>.*)::update',),141('AP_PROXIMITY_CYGBOT_ENABLED', 'AP_Proximity_Cygbot_D1::update',),142('AP_PROXIMITY_LIGHTWARE_{type}_ENABLED', 'AP_Proximity_LightWare(?P<type>.*)::update',),143('AP_PROXIMITY_HEXSOONRADAR_ENABLED', 'AP_Proximity_MR72_CAN::update',),144('AP_PROXIMITY_MR72_ENABLED', 'AP_Proximity_MR72_CAN::update',),145146('HAL_PARACHUTE_ENABLED', 'AP_Parachute::update',),147('AP_FENCE_ENABLED', r'AC_Fence::check\b',),148('HAL_RALLY_ENABLED', 'AP_Rally::find_nearest_rally_point',),149('AP_AVOIDANCE_ENABLED', 'AC_Avoid::AC_Avoid',),150('AP_OAPATHPLANNER_ENABLED', 'AP_OAPathPlanner::AP_OAPathPlanner',),151('AC_PAYLOAD_PLACE_ENABLED', 'PayloadPlace::start_descent'),152('AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED', ExtractFeatures.FindString('PayloadPlace')),153('AP_ICENGINE_ENABLED', 'AP_ICEngine::AP_ICEngine',),154('HAL_EFI_ENABLED', 'AP_RPM_EFI::AP_RPM_EFI',),155('AP_EFI_NWPWU_ENABLED', r'AP_EFI_NWPMU::update\b',),156('AP_EFI_CURRAWONG_ECU_ENABLED', r'AP_EFI_Currawong_ECU::update\b',),157('AP_EFI_SERIAL_HIRTH_ENABLED', r'AP_EFI_Serial_Hirth::update\b',),158('HAL_GENERATOR_ENABLED', 'AP_Generator::AP_Generator',),159('AP_GENERATOR_{type}_ENABLED', r'AP_Generator_(?P<type>.*)::init',),160161('OSD_ENABLED', 'AP_OSD::update_osd',),162('HAL_PLUSCODE_ENABLE', 'AP_OSD_Screen::draw_pluscode',),163('OSD_PARAM_ENABLED', 'AP_OSD_ParamScreen::AP_OSD_ParamScreen',),164('HAL_OSD_SIDEBAR_ENABLE', 'AP_OSD_Screen::draw_sidebars',),165166('AP_VIDEOTX_ENABLED', 'AP_VideoTX::AP_VideoTX',),167('AP_SMARTAUDIO_ENABLED', 'AP_SmartAudio::AP_SmartAudio',),168('AP_TRAMP_ENABLED', 'AP_Tramp::AP_Tramp',),169170('AP_CHECK_FIRMWARE_ENABLED', 'AP_CheckFirmware::check_signed_bootloader',),171172('HAL_QUADPLANE_ENABLED', 'QuadPlane::QuadPlane',),173('AP_PLANE_GLIDER_PULLUP_ENABLED', 'GliderPullup::in_pullup',),174('QAUTOTUNE_ENABLED', 'ModeQAutotune::_enter',),175('HAL_SOARING_ENABLED', 'SoaringController::var_info',),176('HAL_LANDING_DEEPSTALL_ENABLED', r'AP_Landing_Deepstall::override_servos',),177178('AP_GRIPPER_ENABLED', r'AP_Gripper::init\b',),179('HAL_SPRAYER_ENABLED', 'AC_Sprayer::AC_Sprayer',),180('AP_LANDINGGEAR_ENABLED', r'AP_LandingGear::init\b',),181('AP_WINCH_ENABLED', 'AP_Winch::AP_Winch',),182('AP_WINCH_{type}_ENABLED', r'AP_Winch_(?P<type>.*)::update\b',),183('AP_RELAY_ENABLED', 'AP_Relay::init',),184('AP_SERVORELAYEVENTS_ENABLED', 'AP_ServoRelayEvents::update_events',),185186('AP_RCPROTOCOL_ENABLED', r'AP_RCProtocol::init\b',),187('AP_RCPROTOCOL_MAVLINK_RADIO_ENABLED', r'AP_RCProtocol_MAVLinkRadio::update_radio_rc_channels',),188('AP_RCPROTOCOL_{type}_ENABLED', r'AP_RCProtocol_(?P<type>.*)::_process_byte\b',),189('AP_RCPROTOCOL_{type}_ENABLED', r'AP_RCProtocol_(?P<type>.*)::process_pulse\b',),190191('AP_SERVO_TELEM_ENABLED', r'AP_Servo_Telem::update\b',),192('AP_VOLZ_ENABLED', r'AP_Volz_Protocol::init\b',),193('AP_DRONECAN_VOLZ_FEEDBACK_ENABLED', r'AP_DroneCAN::handle_actuator_status_Volz\b',),194('AP_ROBOTISSERVO_ENABLED', r'AP_RobotisServo::init\b',),195('AP_FETTEC_ONEWIRE_ENABLED', r'AP_FETtecOneWire::init\b',),196('AP_SBUSOUTPUT_ENABLED', 'AP_SBusOut::sbus_format_frame',),197('AP_KDECAN_ENABLED', r'AP_KDECAN::update\b',),198199('AP_RPM_ENABLED', 'AP_RPM::AP_RPM',),200('AP_RPM_{type}_ENABLED', r'AP_RPM_(?P<type>.*)::update',),201202('AP_OPENDRONEID_ENABLED', 'AP_OpenDroneID::update',),203204('GPS_MOVING_BASELINE', r'MovingBase::var_info',),205('AP_DRONECAN_SEND_GPS', r'AP_GPS_DroneCAN::instance_exists\b',),206('AP_GPS_BLENDED_ENABLED', r'AP_GPS::calc_blend_weights\b',),207('AP_GPS_DEBUG_LOGGING_ENABLED', 'AP_GPS_Backend::log_data',),208209('HAL_WITH_DSP', r'AP_HAL::DSP::find_peaks\b',),210('AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED', r'AP_InertialSensor::HarmonicNotch::update_params\b',),211('AP_INERTIALSENSOR_BATCHSAMPLER_ENABLED', r'AP_InertialSensor::BatchSampler::init'),212('AP_INERTIALSENSOR_FAST_SAMPLE_WINDOW_ENABLED', r'FastRateBuffer::get_next_gyro_sample\b',),213('HAL_GYROFFT_ENABLED', r'AP_GyroFFT::AP_GyroFFT\b',),214('HAL_DISPLAY_ENABLED', r'Display::init\b',),215('HAL_NMEA_OUTPUT_ENABLED', r'AP_NMEA_Output::update\b',),216('HAL_BARO_WIND_COMP_ENABLED', r'AP_Baro::wind_pressure_correction\b',),217('AP_BARO_THST_COMP_ENABLED', r'AP_Baro::thrust_pressure_correction\b',),218('AP_TEMPCALIBRATION_ENABLED', r'AP_TempCalibration::apply_calibration',),219220('AP_PICCOLOCAN_ENABLED', 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'),224('EK3_FEATURE_OPTFLOW_SRTM', r'NavEKF3_core::writeTerrainData'),225226('AP_RC_CHANNEL_AUX_FUNCTION_STRINGS_ENABLED', r'RC_Channel::lookuptable',),227('AP_SCRIPTING_ENABLED', r'AP_Scripting::init',),228('AP_SCRIPTING_SERIALDEVICE_ENABLED', r'AP_Scripting_SerialDevice::init',),229230('AP_NOTIFY_TONEALARM_ENABLED', r'AP_ToneAlarm::init'),231('AP_NOTIFY_MAVLINK_PLAY_TUNE_SUPPORT_ENABLED', r'AP_Notify::handle_play_tune'),232('AP_NOTIFY_MAVLINK_LED_CONTROL_SUPPORT_ENABLED', r'AP_Notify::handle_led_control'),233('AP_NOTIFY_NCP5623_ENABLED', r'NCP5623::write'),234('AP_NOTIFY_PROFILED_ENABLED', r'ProfiLED::init_ports'),235('AP_NOTIFY_PROFILED_SPI_ENABLED', r'ProfiLED_SPI::rgb_set_id'),236('AP_NOTIFY_NEOPIXEL_ENABLED', r'NeoPixel::init_ports'),237('AP_FILESYSTEM_FORMAT_ENABLED', r'AP_Filesystem::format'),238239('AP_FILESYSTEM_{type}_ENABLED', r'AP_Filesystem_(?P<type>.*)::open'),240241('AP_INERTIALSENSOR_KILL_IMU_ENABLED', r'AP_InertialSensor::kill_imu'),242('AP_CRASHDUMP_ENABLED', 'CrashCatcher_DumpMemory'),243('AP_CAN_SLCAN_ENABLED', 'SLCAN::CANIface::var_info'),244('AC_POLYFENCE_FENCE_POINT_PROTOCOL_SUPPORT', 'AC_PolyFence_loader::handle_msg_fetch_fence_point'),245('AP_MAVLINK_RALLY_POINT_PROTOCOL_ENABLED', 'GCS_MAVLINK::handle_common_rally_message'),246('AP_ADSB_AVOIDANCE_ENABLED', 'AP_Avoidance::init'),247248('AP_SDCARD_STORAGE_ENABLED', 'StorageAccess::attach_file'),249('AP_MAVLINK_AUTOPILOT_VERSION_REQUEST_ENABLED', 'GCS_MAVLINK::handle_send_autopilot_version'),250('AP_MAVLINK_MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES_ENABLED', 'GCS_MAVLINK::handle_command_request_autopilot_capabilities'), # noqa251('AP_MAVLINK_MSG_RELAY_STATUS_ENABLED', 'GCS_MAVLINK::send_relay_status'),252('AP_MAVLINK_MSG_DEVICE_OP_ENABLED', 'GCS_MAVLINK::handle_device_op_write'),253('AP_MAVLINK_SERVO_RELAY_ENABLED', 'GCS_MAVLINK::handle_servorelay_message'),254('AP_MAVLINK_MSG_SERIAL_CONTROL_ENABLED', 'GCS_MAVLINK::handle_serial_control'),255('AP_MAVLINK_MSG_MISSION_REQUEST_ENABLED', r'GCS_MAVLINK::handle_mission_request\b'),256('AP_MAVLINK_MSG_RC_CHANNELS_RAW_ENABLED', r'GCS_MAVLINK::send_rc_channels_raw\b'),257('AP_MAVLINK_FTP_ENABLED', 'GCS_FTP::init'),258('AP_MAVLINK_MAV_CMD_SET_HAGL_ENABLED', 'Plane::handle_external_hagl'),259('AP_MAVLINK_MSG_VIDEO_STREAM_INFORMATION_ENABLED', 'AP_Camera::send_video_stream_information'),260('AP_MAVLINK_MSG_FLIGHT_INFORMATION_ENABLED', 'GCS_MAVLINK::send_flight_information'),261('AP_MAVLINK_MSG_RANGEFINDER_SENDING_ENABLED', r'GCS_MAVLINK::send_rangefinder'),262('AP_MAVLINK_SIGNING_ENABLED', r'GCS_MAVLINK::load_signing_key'),263264('AP_DRONECAN_HIMARK_SERVO_SUPPORT', 'AP_DroneCAN::SRV_send_himark'),265('AP_DRONECAN_HOBBYWING_ESC_SUPPORT', 'AP_DroneCAN::hobbywing_ESC_update'),266('COMPASS_CAL_ENABLED', 'CompassCalibrator::stop'),267('AP_TUNING_ENABLED', 'AP_Tuning::check_input'),268('AP_DRONECAN_SERIAL_ENABLED', 'AP_DroneCAN_Serial::update'),269('AP_SERIALMANAGER_IMUOUT_ENABLED', 'AP_InertialSensor::send_uart_data'),270('AP_NETWORKING_ENABLED', 'AP_Networking::init'),271('AP_NETWORKING_BACKEND_PPP', 'AP_Networking_PPP::init'),272('AP_NETWORKING_CAN_MCAST_ENABLED', 'AP_Networking_CAN::start'),273('AP_NETWORKING_CAPTURE_ENABLED', 'AP_Networking_Backend::capture_pbuf'),274275('FORCE_APJ_DEFAULT_PARAMETERS', 'AP_Param::param_defaults_data'),276('HAL_BUTTON_ENABLED', 'AP_Button::update'),277('HAL_LOGGING_ENABLED', 'AP_Logger::init'),278('AP_COMPASS_CALIBRATION_FIXED_YAW_ENABLED', 'Compass::mag_cal_fixed_yaw'),279('COMPASS_LEARN_ENABLED', 'CompassLearn::update'),280('AP_CUSTOMROTATIONS_ENABLED', 'AP_CustomRotations::init'),281('AP_OSD_LINK_STATS_EXTENSIONS_ENABLED', r'AP_OSD_Screen::draw_rc_tx_power'),282('HAL_ENABLE_DRONECAN_DRIVERS', r'AP_DroneCAN::init'),283('AP_BARO_PROBE_EXTERNAL_I2C_BUSES', r'AP_Baro::_probe_i2c_barometers'),284('AP_RSSI_ENABLED', r'AP_RSSI::init'),285('AP_FOLLOW_ENABLED', 'AP_Follow::AP_Follow'),286287('AP_ROVER_ADVANCED_FAILSAFE_ENABLED', r'Rover::afs_fs_check'),288('AP_ROVER_AUTO_ARM_ONCE_ENABLED', r'Rover::handle_auto_arm_once'),289('AP_COPTER_ADVANCED_FAILSAFE_ENABLED', r'Copter::afs_fs_check'),290('AP_COPTER_AHRS_AUTO_TRIM_ENABLED', r'RC_Channels_Copter::auto_trim_run'),291292('AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED', r'GCS_MAVLINK_Plane::handle_command_int_guided_slew_commands'),293('AP_SERIALMANAGER_REGISTER_ENABLED', r'AP_SerialManager::register_port'),294('AP_QUICKTUNE_ENABLED', r'AP_Quicktune::update'),295('AP_FILTER_ENABLED', r'AP_Filters::update'),296('AP_CAN_LOGGING_ENABLED', r'AP_CANManager::can_logging_callback'),297('AP_PLANE_SYSTEMID_ENABLED', r'AP_SystemID::start'),298('AP_DDS_ENABLED', r'AP_DDS_Client::start'),299('AP_RC_TRANSMITTER_TUNING_ENABLED', r'Copter::tuning'),300('AP_CPU_IDLE_STATS_ENABLED', r'AP_BoardConfig::use_idle_stats'),301302('AP_PERIPH_DEVICE_TEMPERATURE_ENABLED', r'AP_Periph_FW::temperature_sensor_update'),303('AP_PERIPH_MSP_ENABLED', r'AP_Periph_FW::msp_init'),304('AP_PERIPH_NOTIFY_ENABLED', r'AP_Periph_FW::handle_notify_state'),305('AP_PERIPH_SERIAL_OPTIONS_ENABLED', r'SerialOptions::init'),306('AP_PERIPH_BATTERY_ENABLED', r'AP_Periph_FW::can_battery_update'),307('AP_PERIPH_RELAY_ENABLED', r'AP_Periph_FW::handle_hardpoint_command'),308('AP_PERIPH_BATTERY_BALANCE_ENABLED', r'AP_Periph_FW::batt_balance_update'),309('AP_PERIPH_BATTERY_TAG_ENABLED', r'BatteryTag::update'),310('AP_PERIPH_BATTERY_BMS_ENABLED', r'BatteryBMS::update'),311('AP_PERIPH_PROXIMITY_ENABLED', r'AP_Periph_FW::can_proximity_update'),312('AP_PERIPH_GPS_ENABLED', r'AP_Periph_FW::can_gps_update'),313('AP_PERIPH_ADSB_ENABLED', r'AP_Periph_FW::adsb_update'),314('AP_PERIPH_MAG_ENABLED', r'AP_Periph_FW::can_mag_update'),315('AP_PERIPH_BARO_ENABLED', r'AP_Periph_FW::can_baro_update'),316('AP_PERIPH_RANGEFINDER_ENABLED', r'AP_Periph_FW::can_rangefinder_update'),317('AP_PERIPH_IMU_ENABLED', r'AP_Periph_FW::can_imu_update'),318('AP_PERIPH_RC_OUT_ENABLED', r'AP_Periph_FW::sim_update_actuator'),319('AP_PERIPH_EFI_ENABLED', r'AP_Periph_FW::can_efi_update'),320('AP_PERIPH_RCIN_ENABLED', r'AP_Periph_FW::rcin_update'),321('AP_PERIPH_RPM_ENABLED', r'AP_Periph_FW::rpm_sensor_send'),322('AP_PERIPH_AIRSPEED_ENABLED', r'AP_Periph_FW::can_airspeed_update'),323324('AP_SCRIPTING_BINDING_VEHICLE_ENABLED', 'AP_Vehicle_index'),325('AP_SCRIPTING_BINDING_MOTORS_ENABLED', 'AP__motors___index'),326]327328def progress_prefix(self):329"""Return prefix for progress messages."""330return 'EF'331332def validate_features_list(self):333'''ensures that every define present in build_options.py could be334found by in our features list'''335# a list of problematic defines we don't have fixes for ATM:336whitelist = frozenset([337'HAL_PERIPH_SUPPORT_LONG_CAN_PRINTF', # this define changes single method body, hard to detect?338'AP_PLANE_BLACKBOX_LOGGING', # no visible signature339'AC_POLYFENCE_CIRCLE_INT_SUPPORT_ENABLED', # no visible signature340])341for option in build_options.BUILD_OPTIONS:342if option.define in whitelist:343continue344matched = False345for (define, _) in self.features:346# replace {type} with "match any number of word characters'''347define_re = "^" + re.sub(r"{type}", "\\\\w+", define) + "$"348# print("define re is (%s)" % define_re)349if re.match(define_re, option.define):350matched = True351break352if not matched:353raise ValueError("feature (%s) is not matched in extract_features" %354(option.define))355356class Symbols(object):357def __init__(self):358self.symbols = dict()359self.symbols_without_arguments = dict()360361def add(self, key, attributes):362self.symbols[key] = attributes363364# also keep around the same symbol name without arguments.365# if the key is already present then the attributes become366# None as there are multiple possible answers...367m = re.match("^([^(]+).*", key)368if m is None:369extracted_symbol_name = key370else:371extracted_symbol_name = m.group(1)372# print("Adding (%s)" % str(extracted_symbol_name))373if extracted_symbol_name in self.symbols_without_arguments:374self.symbols_without_arguments[extracted_symbol_name] = None375else:376self.symbols_without_arguments[extracted_symbol_name] = attributes377378def dict_for_symbol(self, symbol):379if '(' not in symbol:380some_dict = self.symbols_without_arguments381else:382some_dict = self.symbols383return some_dict384385def extract_symbols_from_elf(self, filename):386"""Parses ELF in filename, returns dict of symbols=>attributes."""387text_output = self.run_program('EF', [388self.nm,389'--demangle',390'--print-size',391filename392], show_output=False, show_command=False)393ret = ExtractFeatures.Symbols()394for line in text_output.split("\n"):395m = re.match("^([^ ]+) ([^ ]+) ([^ ]) (.*)", line.rstrip())396if m is None:397m = re.match("^([^ ]+) ([^ ]) (.*)", line.rstrip())398if m is None:399# raise ValueError("Did not match (%s)" % line)400# e.g. Did not match ( U _errno)401continue402(offset, symbol_type, symbol_name) = m.groups()403size = "0"404else:405(offset, size, symbol_type, symbol_name) = m.groups()406size = int(size, 16)407# print("symbol (%s) size %u" % (str(symbol_name), size))408ret.add(symbol_name, {409"size": size,410})411412return ret413414def extract_strings_from_elf(self, filename):415"""Runs strings on filename, returns as a list"""416text_output = self.run_program('EF', [417self.strings,418filename419], show_output=False, show_command=False)420return text_output.split("\n")421422def extract(self):423'''returns two sets - compiled_in and not_compiled_in'''424425build_options_defines = set([x.define for x in build_options.BUILD_OPTIONS])426427symbols = self.extract_symbols_from_elf(self.filename)428strings = self.extract_strings_from_elf(self.filename)429430remaining_build_options_defines = build_options_defines431compiled_in_feature_defines = []432for (feature_define, symbol) in self.features:433if isinstance(symbol, ExtractFeatures.FindString):434if symbol.string in strings:435some_define = feature_define436if some_define not in build_options_defines:437continue438compiled_in_feature_defines.append(some_define)439remaining_build_options_defines.discard(some_define)440else:441some_dict = symbols.dict_for_symbol(symbol)442# look for symbols without arguments443# print("Looking for (%s)" % str(name))444for s in some_dict.keys():445m = re.match(symbol, s)446# print("matching %s with %s" % (symbol, s))447if m is None:448continue449d = m.groupdict()450for key in d.keys():451d[key] = d[key].upper()452# filter to just the defines present in453# build_options.py - otherwise we end up with (e.g.)454# AP_AIRSPEED_BACKEND_ENABLED, even 'though that455# doesn't exist in the ArduPilot codebase.456some_define = feature_define.format(**d)457if some_define not in build_options_defines:458continue459compiled_in_feature_defines.append(some_define)460remaining_build_options_defines.discard(some_define)461return (compiled_in_feature_defines, remaining_build_options_defines)462463def create_string(self):464'''returns a string with compiled in and not compiled-in features'''465466(compiled_in_feature_defines, not_compiled_in_feature_defines) = self.extract()467468ret = ""469470combined = {}471for define in sorted(compiled_in_feature_defines):472combined[define] = True473for define in sorted(not_compiled_in_feature_defines):474combined[define] = False475476def squash_hal_to_ap(a):477return re.sub("^HAL_", "AP_", a)478479for define in sorted(combined.keys(), key=squash_hal_to_ap):480bang = ""481if not combined[define]:482bang = "!"483ret += bang + define + "\n"484return ret485486def run(self):487self.validate_features_list()488print(self.create_string())489490491if __name__ == '__main__':492493parser = argparse.ArgumentParser(prog='extract_features.py', description='Extract ArduPilot features from binaries')494parser.add_argument('firmware_file', help='firmware binary')495parser.add_argument('--nm', type=str, default="arm-none-eabi-nm", help='nm binary to use.')496args = parser.parse_args()497# print(args.firmware_file, args.nm)498499ef = ExtractFeatures(args.firmware_file, args.nm)500ef.run()501502503