CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/Tools/scripts/extract_features.py
Views: 1798
1
#!/usr/bin/env python
2
3
"""
4
script to determine what features have been built into an ArduPilot binary
5
6
AP_FLAKE8_CLEAN
7
"""
8
import argparse
9
import os
10
import re
11
import string
12
import subprocess
13
import sys
14
import time
15
import build_options
16
import select
17
18
19
if sys.version_info[0] < 3:
20
running_python3 = False
21
else:
22
running_python3 = True
23
24
25
class ExtractFeatures(object):
26
27
class FindString(object):
28
def __init__(self, string):
29
self.string = string
30
31
def __init__(self, filename, nm="arm-none-eabi-nm", strings="strings"):
32
self.filename = filename
33
self.nm = nm
34
self.strings = strings
35
36
# feature_name should match the equivalent feature in
37
# build_options.py ('FEATURE_NAME', 'EXPECTED_SYMBOL').
38
# EXPECTED_SYMBOL is a regular expression which will be matched
39
# against "define" in build_options's feature list, and
40
# FEATURE_NAME will have substitutions made from the match.
41
# the substitutions will be upper-cased
42
self.features = [
43
('AP_ADVANCEDFAILSAFE_ENABLED', r'AP_AdvancedFailsafe::heartbeat\b',),
44
('AP_BOOTLOADER_FLASHING_ENABLED', 'ChibiOS::Util::flash_bootloader',),
45
('AP_AIRSPEED_ENABLED', 'AP_Airspeed::AP_Airspeed',),
46
('AP_AIRSPEED_{type}_ENABLED', r'AP_Airspeed_(?P<type>.*)::init',),
47
48
('AC_PRECLAND_ENABLED', 'AC_PrecLand::AC_PrecLand',),
49
('AC_PRECLAND_ENABLED', 'AC_PrecLand::AC_PrecLand',),
50
('AC_PRECLAND_{type}_ENABLED', 'AC_PrecLand_(?P<type>.*)::update',),
51
52
('HAL_ADSB_ENABLED', 'AP_ADSB::AP_ADSB',),
53
('HAL_ADSB_{type}_ENABLED', r'AP_ADSB_(?P<type>.*)::update',),
54
('HAL_ADSB_UCP_ENABLED', 'AP_ADSB_uAvionix_UCP::update',),
55
56
('AP_COMPASS_{type}_ENABLED', r'AP_Compass_(?P<type>.*)::read\b',),
57
('AP_COMPASS_ICM20948_ENABLED', r'AP_Compass_AK09916::probe_ICM20948',),
58
('AP_COMPASS_DRONECAN_HIRES_ENABLED', r'AP_Compass_DroneCAN::handle_magnetic_field_hires',),
59
60
('AP_AIS_ENABLED', 'AP_AIS::AP_AIS',),
61
62
('HAL_EFI_ENABLED', 'AP_EFI::AP_EFI',),
63
('AP_EFI_{type}_ENABLED', 'AP_EFI_(?P<type>.*)::update',),
64
65
('AP_EXTENDED_ESC_TELEM_ENABLED', r'AP_DroneCAN::handle_esc_ext_status\b',),
66
67
('AP_TEMPERATURE_SENSOR_ENABLED', 'AP_TemperatureSensor::AP_TemperatureSensor',),
68
('AP_TEMPERATURE_SENSOR_{type}_ENABLED', 'AP_TemperatureSensor_(?P<type>.*)::update',),
69
70
('AP_BEACON_ENABLED', 'AP_Beacon::AP_Beacon',),
71
('HAL_TORQEEDO_ENABLED', 'AP_Torqeedo::AP_Torqeedo'),
72
73
('HAL_NAVEKF3_AVAILABLE', 'NavEKF3::NavEKF3',),
74
('HAL_NAVEKF2_AVAILABLE', 'NavEKF2::NavEKF2',),
75
('HAL_EXTERNAL_AHRS_ENABLED', r'AP_ExternalAHRS::init\b',),
76
('AP_EXTERNAL_AHRS_{type}_ENABLED', r'AP_ExternalAHRS_(?P<type>.*)::healthy\b',),
77
('HAL_INS_TEMPERATURE_CAL_ENABLE', 'AP_InertialSensor_TCal::Learn::save_calibration',),
78
('HAL_VISUALODOM_ENABLED', 'AP_VisualOdom::init',),
79
80
('AP_RANGEFINDER_ENABLED', 'RangeFinder::RangeFinder',),
81
('AP_RANGEFINDER_{type}_ENABLED', r'AP_RangeFinder_(?P<type>.*)::update\b',),
82
('AP_RANGEFINDER_{type}_ENABLED', r'AP_RangeFinder_(?P<type>.*)::get_reading\b',),
83
('AP_RANGEFINDER_{type}_ENABLED', r'AP_RangeFinder_(?P<type>.*)::model_dist_max_cm\b',),
84
('AP_RANGEFINDER_{type}_ENABLED', r'AP_RangeFinder_(?P<type>.*)::handle_frame\b',),
85
('AP_RANGEFINDER_LIGHTWARE_SERIAL_ENABLED', r'AP_RangeFinder_LightWareSerial::get_reading\b',),
86
('AP_RANGEFINDER_LWI2C_ENABLED', r'AP_RangeFinder_LightWareI2C::update\b',),
87
('AP_RANGEFINDER_MAXBOTIX_SERIAL_ENABLED', r'AP_RangeFinder_MaxsonarSerialLV::get_reading\b',),
88
('AP_RANGEFINDER_TRI2C_ENABLED', r'AP_RangeFinder_TeraRangerI2C::update\b',),
89
('AP_RANGEFINDER_JRE_SERIAL_ENABLED', r'AP_RangeFinder_JRE_Serial::get_reading\b',),
90
('AP_RANGEFINDER_RDS02UF_ENABLED', r'AP_RangeFinder_RDS02UF::get_reading\b',),
91
92
('AP_GPS_NMEA_UNICORE_ENABLED', r'AP_GPS_NMEA::parse_agrica_field',),
93
('AP_GPS_{type}_ENABLED', r'AP_GPS_(?P<type>.*)::read\b',),
94
95
('AP_OPTICALFLOW_ENABLED', 'AP_OpticalFlow::AP_OpticalFlow',),
96
('AP_OPTICALFLOW_{type}_ENABLED', r'AP_OpticalFlow_(?P<type>.*)::update\b',),
97
98
('AP_BARO_{type}_ENABLED', r'AP_Baro_(?P<type>.*)::update\b',),
99
100
('AP_MOTORS_FRAME_{type}_ENABLED', r'AP_MotorsMatrix::setup_(?P<type>.*)_matrix\b',),
101
102
('HAL_MSP_ENABLED', r'AP_MSP::init\b',),
103
('HAL_MSP_{type}_ENABLED', r'AP_(?P<type>.*)_MSP::update\b',),
104
('HAL_MSP_{type}_ENABLED', r'AP_(?P<type>.*)_MSP::read\b',),
105
('HAL_WITH_MSP_DISPLAYPORT', r'AP_OSD_MSP_DisplayPort::init\b',),
106
107
108
('AP_BATTERY_{type}_ENABLED', r'AP_BattMonitor_(?P<type>.*)::init\b',),
109
('AP_BATTERY_ESC_TELEM_OUTBOUND_ENABLED', r'AP_BattMonitor_Backend::update_esc_telem_outbound\b',),
110
('AP_BATTERY_WATT_MAX_ENABLED', 'Plane::throttle_watt_limiter',),
111
112
('HAL_MOUNT_ENABLED', 'AP_Mount::AP_Mount',),
113
('HAL_MOUNT_{type}_ENABLED', r'AP_Mount_(?P<type>.*)::update\b',),
114
('HAL_SOLO_GIMBAL_ENABLED', 'AP_Mount_SoloGimbal::init',),
115
('HAL_MOUNT_STORM32SERIAL_ENABLED', 'AP_Mount_SToRM32_serial::update',),
116
('HAL_MOUNT_STORM32MAVLINK_ENABLED', 'AP_Mount_SToRM32::update',),
117
118
('HAL_SPEKTRUM_TELEM_ENABLED', r'AP::spektrum_telem',),
119
('HAL_{type}_TELEM_ENABLED', r'AP_(?P<type>.*)_Telem::init',),
120
('AP_{type}_TELEM_ENABLED', r'AP_(?P<type>.*)_Telem::init',),
121
('HAL_CRSF_TELEM_TEXT_SELECTION_ENABLED', 'AP_CRSF_Telem::calc_text_selection',),
122
('AP_LTM_TELEM_ENABLED', 'AP_LTM_Telem::init',),
123
('HAL_HIGH_LATENCY2_ENABLED', 'GCS_MAVLINK::handle_control_high_latency',),
124
125
('AP_FRSKY_TELEM_ENABLED', 'AP::frsky_telem',),
126
('AP_FRSKY_D_TELEM_ENABLED', 'AP_Frsky_D::send',),
127
('AP_FRSKY_SPORT_TELEM_ENABLED', 'AP_Frsky_SPort::send_sport_frame',),
128
('AP_FRSKY_SPORT_PASSTHROUGH_ENABLED', 'AP_Frsky_SPort_Passthrough::process_packet',),
129
('HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL', 'AP_Frsky_SPort_Passthrough::set_telem_data'),
130
131
('AP_IBUS_TELEM_ENABLED', 'AP_IBus_Telem::init',),
132
133
('MODE_AUTOLAND_ENABLED', 'ModeAutoLand::update'),
134
('MODE_{type}_ENABLED', r'Mode(?P<type>.+)::init',),
135
('MODE_GUIDED_NOGPS_ENABLED', r'ModeGuidedNoGPS::init',),
136
137
('AP_CAMERA_ENABLED', 'AP_Camera::var_info',),
138
('AP_CAMERA_{type}_ENABLED', 'AP_Camera_(?P<type>.*)::trigger_pic',),
139
('AP_CAMERA_SEND_FOV_STATUS_ENABLED', 'AP_Camera::send_camera_fov_status'),
140
('AP_CAMERA_SEND_THERMAL_RANGE_ENABLED', 'AP_Camera::send_camera_thermal_range'),
141
('AP_CAMERA_INFO_FROM_SCRIPT_ENABLED', 'AP_Camera_Backend::set_camera_information'),
142
('AP_CAMERA_RUNCAM_ENABLED', 'AP_RunCam::AP_RunCam',),
143
144
('HAL_PROXIMITY_ENABLED', 'AP_Proximity::AP_Proximity',),
145
('AP_PROXIMITY_{type}_ENABLED', 'AP_Proximity_(?P<type>.*)::update',),
146
('AP_PROXIMITY_CYGBOT_ENABLED', 'AP_Proximity_Cygbot_D1::update',),
147
('AP_PROXIMITY_LIGHTWARE_{type}_ENABLED', 'AP_Proximity_LightWare(?P<type>.*)::update',),
148
149
('HAL_PARACHUTE_ENABLED', 'AP_Parachute::update',),
150
('AP_FENCE_ENABLED', r'AC_Fence::check\b',),
151
('HAL_RALLY_ENABLED', 'AP_Rally::find_nearest_rally_point',),
152
('AP_AVOIDANCE_ENABLED', 'AC_Avoid::AC_Avoid',),
153
('AP_OAPATHPLANNER_ENABLED', 'AP_OAPathPlanner::AP_OAPathPlanner',),
154
('AC_PAYLOAD_PLACE_ENABLED', 'PayloadPlace::start_descent'),
155
('AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED', ExtractFeatures.FindString('PayloadPlace')),
156
('AP_ICENGINE_ENABLED', 'AP_ICEngine::AP_ICEngine',),
157
('HAL_EFI_ENABLED', 'AP_RPM_EFI::AP_RPM_EFI',),
158
('AP_EFI_NWPWU_ENABLED', r'AP_EFI_NWPMU::update\b',),
159
('AP_EFI_CURRAWONG_ECU_ENABLED', r'AP_EFI_Currawong_ECU::update\b',),
160
('AP_EFI_SERIAL_HIRTH_ENABLED', r'AP_EFI_Serial_Hirth::update\b',),
161
('HAL_GENERATOR_ENABLED', 'AP_Generator::AP_Generator',),
162
('AP_GENERATOR_{type}_ENABLED', r'AP_Generator_(?P<type>.*)::init',),
163
164
('OSD_ENABLED', 'AP_OSD::update_osd',),
165
('HAL_PLUSCODE_ENABLE', 'AP_OSD_Screen::draw_pluscode',),
166
('OSD_PARAM_ENABLED', 'AP_OSD_ParamScreen::AP_OSD_ParamScreen',),
167
('HAL_OSD_SIDEBAR_ENABLE', 'AP_OSD_Screen::draw_sidebars',),
168
169
('AP_VIDEOTX_ENABLED', 'AP_VideoTX::AP_VideoTX',),
170
('AP_SMARTAUDIO_ENABLED', 'AP_SmartAudio::AP_SmartAudio',),
171
('AP_TRAMP_ENABLED', 'AP_Tramp::AP_Tramp',),
172
173
('AP_CHECK_FIRMWARE_ENABLED', 'AP_CheckFirmware::check_signed_bootloader',),
174
175
('HAL_QUADPLANE_ENABLED', 'QuadPlane::QuadPlane',),
176
('AP_PLANE_GLIDER_PULLUP_ENABLED', 'GliderPullup::in_pullup',),
177
('QAUTOTUNE_ENABLED', 'ModeQAutotune::_enter',),
178
('HAL_SOARING_ENABLED', 'SoaringController::var_info',),
179
('HAL_LANDING_DEEPSTALL_ENABLED', r'AP_Landing_Deepstall::override_servos',),
180
181
('AP_GRIPPER_ENABLED', r'AP_Gripper::init\b',),
182
('HAL_SPRAYER_ENABLED', 'AC_Sprayer::AC_Sprayer',),
183
('AP_LANDINGGEAR_ENABLED', r'AP_LandingGear::init\b',),
184
('AP_WINCH_ENABLED', 'AP_Winch::AP_Winch',),
185
('AP_WINCH_{type}_ENABLED', r'AP_Winch_(?P<type>.*)::update\b',),
186
('AP_RELAY_ENABLED', 'AP_Relay::init',),
187
('AP_SERVORELAYEVENTS_ENABLED', 'AP_ServoRelayEvents::update_events',),
188
189
('AP_RCPROTOCOL_ENABLED', r'AP_RCProtocol::init\b',),
190
('AP_RCPROTOCOL_MAVLINK_RADIO_ENABLED', r'AP_RCProtocol_MAVLinkRadio::update_radio_rc_channels',),
191
('AP_RCPROTOCOL_{type}_ENABLED', r'AP_RCProtocol_(?P<type>.*)::_process_byte\b',),
192
('AP_RCPROTOCOL_{type}_ENABLED', r'AP_RCProtocol_(?P<type>.*)::process_pulse\b',),
193
194
('AP_SERVO_TELEM_ENABLED', r'AP_Servo_Telem::update\b',),
195
('AP_VOLZ_ENABLED', r'AP_Volz_Protocol::init\b',),
196
('AP_DRONECAN_VOLZ_FEEDBACK_ENABLED', r'AP_DroneCAN::handle_actuator_status_Volz\b',),
197
('AP_ROBOTISSERVO_ENABLED', r'AP_RobotisServo::init\b',),
198
('AP_FETTEC_ONEWIRE_ENABLED', r'AP_FETtecOneWire::init\b',),
199
('AP_SBUSOUTPUT_ENABLED', 'AP_SBusOut::sbus_format_frame',),
200
('AP_KDECAN_ENABLED', r'AP_KDECAN::update\b',),
201
202
('AP_RPM_ENABLED', 'AP_RPM::AP_RPM',),
203
('AP_RPM_{type}_ENABLED', r'AP_RPM_(?P<type>.*)::update',),
204
205
('AP_OPENDRONEID_ENABLED', 'AP_OpenDroneID::update',),
206
207
('GPS_MOVING_BASELINE', r'MovingBase::var_info',),
208
('AP_DRONECAN_SEND_GPS', r'AP_GPS_DroneCAN::instance_exists\b',),
209
('AP_GPS_BLENDED_ENABLED', r'AP_GPS::calc_blend_weights\b',),
210
211
('HAL_WITH_DSP', r'AP_HAL::DSP::find_peaks\b',),
212
('AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED', r'AP_InertialSensor::HarmonicNotch::update_params\b',),
213
('AP_INERTIALSENSOR_BATCHSAMPLER_ENABLED', r'AP_InertialSensor::BatchSampler::init'),
214
('AP_INERTIALSENSOR_FAST_SAMPLE_WINDOW_ENABLED', r'FastRateBuffer::get_next_gyro_sample\b',),
215
('HAL_GYROFFT_ENABLED', r'AP_GyroFFT::AP_GyroFFT\b',),
216
('HAL_DISPLAY_ENABLED', r'Display::init\b',),
217
('HAL_NMEA_OUTPUT_ENABLED', r'AP_NMEA_Output::update\b',),
218
('HAL_BARO_WIND_COMP_ENABLED', r'AP_Baro::wind_pressure_correction\b',),
219
('AP_TEMPCALIBRATION_ENABLED', r'AP_TempCalibration::apply_calibration',),
220
221
('HAL_PICCOLO_CAN_ENABLE', r'AP_PiccoloCAN::update',),
222
('EK3_FEATURE_EXTERNAL_NAV', r'NavEKF3_core::CorrectExtNavVelForSensorOffset'),
223
('EK3_FEATURE_DRAG_FUSION', r'NavEKF3_core::FuseDragForces'),
224
('EK3_FEATURE_OPTFLOW_FUSION', r'NavEKF3_core::FuseOptFlow'),
225
226
('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',),
229
230
('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'),
238
239
('AP_FILESYSTEM_{type}_ENABLED', r'AP_Filesystem_(?P<type>.*)::open'),
240
241
('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
247
('AP_SDCARD_STORAGE_ENABLED', 'StorageAccess::attach_file'),
248
('AP_MAVLINK_AUTOPILOT_VERSION_REQUEST_ENABLED', 'GCS_MAVLINK::handle_send_autopilot_version'),
249
('AP_MAVLINK_MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES_ENABLED', 'GCS_MAVLINK::handle_command_request_autopilot_capabilities'), # noqa
250
('AP_MAVLINK_MSG_RELAY_STATUS_ENABLED', 'GCS_MAVLINK::send_relay_status'),
251
('AP_MAVLINK_MSG_DEVICE_OP_ENABLED', 'GCS_MAVLINK::handle_device_op_write'),
252
('AP_MAVLINK_SERVO_RELAY_ENABLED', 'GCS_MAVLINK::handle_servorelay_message'),
253
('AP_MAVLINK_MSG_SERIAL_CONTROL_ENABLED', 'GCS_MAVLINK::handle_serial_control'),
254
('AP_MAVLINK_MSG_MISSION_REQUEST_ENABLED', r'GCS_MAVLINK::handle_mission_request\b'),
255
('AP_MAVLINK_MSG_RC_CHANNELS_RAW_ENABLED', r'GCS_MAVLINK::send_rc_channels_raw\b'),
256
('AP_MAVLINK_FTP_ENABLED', 'GCS_MAVLINK::ftp_worker'),
257
('AP_MAVLINK_MAV_CMD_SET_HAGL_ENABLED', 'Plane::handle_external_hagl'),
258
('AP_MAVLINK_MSG_VIDEO_STREAM_INFORMATION_ENABLED', 'AP_Camera::send_video_stream_information'),
259
260
('AP_DRONECAN_HIMARK_SERVO_SUPPORT', 'AP_DroneCAN::SRV_send_himark'),
261
('AP_DRONECAN_HOBBYWING_ESC_SUPPORT', 'AP_DroneCAN::hobbywing_ESC_update'),
262
('COMPASS_CAL_ENABLED', 'CompassCalibrator::stop'),
263
('AP_TUNING_ENABLED', 'AP_Tuning::check_input'),
264
('AP_DRONECAN_SERIAL_ENABLED', 'AP_DroneCAN_Serial::update'),
265
('AP_SERIALMANAGER_IMUOUT_ENABLED', 'AP_InertialSensor::send_uart_data'),
266
('AP_NETWORKING_BACKEND_PPP', 'AP_Networking_PPP::init'),
267
('AP_NETWORKING_CAN_MCAST_ENABLED', 'AP_Networking_CAN::start'),
268
('FORCE_APJ_DEFAULT_PARAMETERS', 'AP_Param::param_defaults_data'),
269
('HAL_BUTTON_ENABLED', 'AP_Button::update'),
270
('HAL_LOGGING_ENABLED', 'AP_Logger::init'),
271
('AP_COMPASS_CALIBRATION_FIXED_YAW_ENABLED', 'Compass::mag_cal_fixed_yaw'),
272
('COMPASS_LEARN_ENABLED', 'CompassLearn::update'),
273
('AP_CUSTOMROTATIONS_ENABLED', 'AP_CustomRotations::init'),
274
('AP_OSD_LINK_STATS_EXTENSIONS_ENABLED', r'AP_OSD_Screen::draw_rc_tx_power'),
275
('HAL_ENABLE_DRONECAN_DRIVERS', r'AP_DroneCAN::init'),
276
('AP_BARO_PROBE_EXTERNAL_I2C_BUSES', r'AP_Baro::_probe_i2c_barometers'),
277
('AP_RSSI_ENABLED', r'AP_RSSI::init'),
278
279
('AP_ROVER_ADVANCED_FAILSAFE_ENABLED', r'Rover::afs_fs_check'),
280
('AP_COPTER_ADVANCED_FAILSAFE_ENABLED', r'Copter::afs_fs_check'),
281
282
('AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED', r'GCS_MAVLINK_Plane::handle_command_int_guided_slew_commands'),
283
('AP_SERIALMANAGER_REGISTER_ENABLED', r'AP_SerialManager::register_port'),
284
('AP_QUICKTUNE_ENABLED', r'AP_Quicktune::update'),
285
('AP_FILTER_ENABLED', r'AP_Filters::update'),
286
('AP_CAN_LOGGING_ENABLED', r'AP_CANManager::can_logging_callback'),
287
]
288
289
def progress(self, msg):
290
"""Pretty-print progress."""
291
print("EF: %s" % msg)
292
293
def validate_features_list(self):
294
'''ensures that every define present in build_options.py could be
295
found by in our features list'''
296
# a list of problematic defines we don't have fixes for ATM:
297
whitelist = frozenset([
298
'HAL_PERIPH_SUPPORT_LONG_CAN_PRINTF', # this define changes single method body, hard to detect?
299
'AP_PLANE_BLACKBOX_LOGGING', # no visible signature
300
])
301
for option in build_options.BUILD_OPTIONS:
302
if option.define in whitelist:
303
continue
304
matched = False
305
for (define, _) in self.features:
306
# replace {type} with "match any number of word characters'''
307
define_re = "^" + re.sub(r"{type}", "\\\\w+", define) + "$"
308
# print("define re is (%s)" % define_re)
309
if re.match(define_re, option.define):
310
matched = True
311
break
312
if not matched:
313
raise ValueError("feature (%s) is not matched in extract_features" %
314
(option.define))
315
316
def run_program(self, prefix, cmd_list, show_output=True, env=None):
317
"""Swiped from build_binaries.py."""
318
if show_output:
319
self.progress("Running (%s)" % " ".join(cmd_list))
320
p = subprocess.Popen(
321
cmd_list,
322
stdin=None,
323
stdout=subprocess.PIPE,
324
close_fds=True,
325
stderr=subprocess.PIPE,
326
env=env)
327
stderr = bytearray()
328
output = ""
329
while True:
330
# read all of stderr:
331
while True:
332
(rin, _, _) = select.select([p.stderr.fileno()], [], [], 0)
333
if p.stderr.fileno() not in rin:
334
break
335
new = p.stderr.read()
336
if len(new) == 0:
337
break
338
stderr += new
339
340
x = p.stdout.readline()
341
if len(x) == 0:
342
(rin, _, _) = select.select([p.stderr.fileno()], [], [], 0)
343
if p.stderr.fileno() in rin:
344
stderr += p.stderr.read()
345
346
returncode = os.waitpid(p.pid, 0)
347
if returncode:
348
break
349
# select not available on Windows... probably...
350
time.sleep(0.1)
351
continue
352
if running_python3:
353
x = bytearray(x)
354
x = filter(lambda x: chr(x) in string.printable, x)
355
x = "".join([chr(c) for c in x])
356
output += x
357
x = x.rstrip()
358
if show_output:
359
print("%s: %s" % (prefix, x))
360
(_, status) = returncode
361
if status != 0:
362
stderr = stderr.decode('utf-8')
363
self.progress("Process failed (%s) (%s)" %
364
(str(returncode), stderr))
365
raise subprocess.CalledProcessError(
366
status, cmd_list, output=str(output), stderr=str(stderr))
367
return output
368
369
class Symbols(object):
370
def __init__(self):
371
self.symbols = dict()
372
self.symbols_without_arguments = dict()
373
374
def add(self, key, attributes):
375
self.symbols[key] = attributes
376
377
# also keep around the same symbol name without arguments.
378
# if the key is already present then the attributes become
379
# None as there are multiple possible answers...
380
m = re.match("^([^(]+).*", key)
381
if m is None:
382
extracted_symbol_name = key
383
else:
384
extracted_symbol_name = m.group(1)
385
# print("Adding (%s)" % str(extracted_symbol_name))
386
if extracted_symbol_name in self.symbols_without_arguments:
387
self.symbols_without_arguments[extracted_symbol_name] = None
388
else:
389
self.symbols_without_arguments[extracted_symbol_name] = attributes
390
391
def dict_for_symbol(self, symbol):
392
if '(' not in symbol:
393
some_dict = self.symbols_without_arguments
394
else:
395
some_dict = self.symbols
396
return some_dict
397
398
def extract_symbols_from_elf(self, filename):
399
"""Parses ELF in filename, returns dict of symbols=>attributes."""
400
text_output = self.run_program('EF', [
401
self.nm,
402
'--demangle',
403
'--print-size',
404
filename
405
], show_output=False)
406
ret = ExtractFeatures.Symbols()
407
for line in text_output.split("\n"):
408
m = re.match("^([^ ]+) ([^ ]+) ([^ ]) (.*)", line.rstrip())
409
if m is None:
410
m = re.match("^([^ ]+) ([^ ]) (.*)", line.rstrip())
411
if m is None:
412
# raise ValueError("Did not match (%s)" % line)
413
# e.g. Did not match ( U _errno)
414
continue
415
(offset, symbol_type, symbol_name) = m.groups()
416
size = "0"
417
else:
418
(offset, size, symbol_type, symbol_name) = m.groups()
419
size = int(size, 16)
420
# print("symbol (%s) size %u" % (str(symbol_name), size))
421
ret.add(symbol_name, {
422
"size": size,
423
})
424
425
return ret
426
427
def extract_strings_from_elf(self, filename):
428
"""Runs strings on filename, returns as a list"""
429
text_output = self.run_program('EF', [
430
self.strings,
431
filename
432
], show_output=False)
433
return text_output.split("\n")
434
435
def extract(self):
436
'''returns two sets - compiled_in and not_compiled_in'''
437
438
build_options_defines = set([x.define for x in build_options.BUILD_OPTIONS])
439
440
symbols = self.extract_symbols_from_elf(self.filename)
441
strings = self.extract_strings_from_elf(self.filename)
442
443
remaining_build_options_defines = build_options_defines
444
compiled_in_feature_defines = []
445
for (feature_define, symbol) in self.features:
446
if isinstance(symbol, ExtractFeatures.FindString):
447
if symbol.string in strings:
448
some_define = feature_define
449
if some_define not in build_options_defines:
450
continue
451
compiled_in_feature_defines.append(some_define)
452
remaining_build_options_defines.discard(some_define)
453
else:
454
some_dict = symbols.dict_for_symbol(symbol)
455
# look for symbols without arguments
456
# print("Looking for (%s)" % str(name))
457
for s in some_dict.keys():
458
m = re.match(symbol, s)
459
# print("matching %s with %s" % (symbol, s))
460
if m is None:
461
continue
462
d = m.groupdict()
463
for key in d.keys():
464
d[key] = d[key].upper()
465
# filter to just the defines present in
466
# build_options.py - otherwise we end up with (e.g.)
467
# AP_AIRSPEED_BACKEND_ENABLED, even 'though that
468
# doesn't exist in the ArduPilot codebase.
469
some_define = feature_define.format(**d)
470
if some_define not in build_options_defines:
471
continue
472
compiled_in_feature_defines.append(some_define)
473
remaining_build_options_defines.discard(some_define)
474
return (compiled_in_feature_defines, remaining_build_options_defines)
475
476
def create_string(self):
477
'''returns a string with compiled in and not compiled-in features'''
478
479
(compiled_in_feature_defines, not_compiled_in_feature_defines) = self.extract()
480
481
ret = ""
482
483
combined = {}
484
for define in sorted(compiled_in_feature_defines):
485
combined[define] = True
486
for define in sorted(not_compiled_in_feature_defines):
487
combined[define] = False
488
489
def squash_hal_to_ap(a):
490
return re.sub("^HAL_", "AP_", a)
491
492
for define in sorted(combined.keys(), key=squash_hal_to_ap):
493
bang = ""
494
if not combined[define]:
495
bang = "!"
496
ret += bang + define + "\n"
497
return ret
498
499
def run(self):
500
self.validate_features_list()
501
print(self.create_string())
502
503
504
if __name__ == '__main__':
505
506
parser = argparse.ArgumentParser(prog='extract_features.py', description='Extract ArduPilot features from binaries')
507
parser.add_argument('firmware_file', help='firmware binary')
508
parser.add_argument('-nm', type=str, default="arm-none-eabi-nm", help='nm binary to use.')
509
args = parser.parse_args()
510
# print(args.firmware_file, args.nm)
511
512
ef = ExtractFeatures(args.firmware_file, args.nm)
513
ef.run()
514
515