From 083f9f81396f514e92b66a9f15ec28997766ac1a Mon Sep 17 00:00:00 2001 From: James O'Shannessy <12959316+joshanne@users.noreply.github.com> Date: Fri, 9 Aug 2024 11:42:24 +1000 Subject: [PATCH] scripts: Fixed extract_features.py not extracting ExternalAHRS or INS Temp Cal properly --- Tools/scripts/extract_features.py | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/Tools/scripts/extract_features.py b/Tools/scripts/extract_features.py index b52f9ed6eea4a..c5f96ac26acf2 100755 --- a/Tools/scripts/extract_features.py +++ b/Tools/scripts/extract_features.py @@ -73,14 +73,15 @@ def __init__(self, filename, nm="arm-none-eabi-nm", strings="strings"): ('HAL_NAVEKF3_AVAILABLE', 'NavEKF3::NavEKF3',), ('HAL_NAVEKF2_AVAILABLE', 'NavEKF2::NavEKF2',), ('HAL_EXTERNAL_AHRS_ENABLED', r'AP_ExternalAHRS::init\b',), - ('AP_EXTERNAL_AHRS_{type}_ENABLED', r'AP_ExternalAHRS_{type}::healthy\b',), - ('HAL_INS_TEMPERATURE_CAL_ENABLE', 'AP_InertialSensor::TCal::Learn::save_calibration',), + ('AP_EXTERNAL_AHRS_{type}_ENABLED', r'AP_ExternalAHRS_(?P<type>.*)::healthy\b',), + ('HAL_INS_TEMPERATURE_CAL_ENABLE', 'AP_InertialSensor_TCal::Learn::save_calibration',), ('HAL_VISUALODOM_ENABLED', 'AP_VisualOdom::init',), ('AP_RANGEFINDER_ENABLED', 'RangeFinder::RangeFinder',), ('AP_RANGEFINDER_{type}_ENABLED', r'AP_RangeFinder_(?P<type>.*)::update\b',), ('AP_RANGEFINDER_{type}_ENABLED', r'AP_RangeFinder_(?P<type>.*)::get_reading\b',), ('AP_RANGEFINDER_{type}_ENABLED', r'AP_RangeFinder_(?P<type>.*)::model_dist_max_cm\b',), + ('AP_RANGEFINDER_{type}_ENABLED', r'AP_RangeFinder_(?P<type>.*)::handle_frame\b',), ('AP_RANGEFINDER_LIGHTWARE_SERIAL_ENABLED', r'AP_RangeFinder_LightWareSerial::get_reading\b',), ('AP_RANGEFINDER_LWI2C_ENABLED', r'AP_RangeFinder_LightWareI2C::update\b',), ('AP_RANGEFINDER_MAXBOTIX_SERIAL_ENABLED', r'AP_RangeFinder_MaxsonarSerialLV::get_reading\b',), @@ -142,7 +143,7 @@ def __init__(self, filename, nm="arm-none-eabi-nm", strings="strings"): ('HAL_PARACHUTE_ENABLED', 'AP_Parachute::update',), ('AP_FENCE_ENABLED', r'AC_Fence::check\b',), - ('HAL_RALLY_ENABLED', r'AP_Rally::get_rally_max\b',), + ('HAL_RALLY_ENABLED', 'AP_Rally::find_nearest_rally_point',), ('AP_AVOIDANCE_ENABLED', 'AC_Avoid::AC_Avoid',), ('AP_OAPATHPLANNER_ENABLED', 'AP_OAPathPlanner::AP_OAPathPlanner',), ('AC_PAYLOAD_PLACE_ENABLED', 'PayloadPlace::start_descent'), @@ -257,7 +258,7 @@ def __init__(self, filename, nm="arm-none-eabi-nm", strings="strings"): ('FORCE_APJ_DEFAULT_PARAMETERS', 'AP_Param::param_defaults_data'), ('HAL_BUTTON_ENABLED', 'AP_Button::update'), ('HAL_LOGGING_ENABLED', 'AP_Logger::init'), - ('AP_COMPASS_CALIBRATION_FIXED_YAW_ENABLED', 'AP_Compass::mag_cal_fixed_yaw'), + ('AP_COMPASS_CALIBRATION_FIXED_YAW_ENABLED', 'Compass::mag_cal_fixed_yaw'), ('COMPASS_LEARN_ENABLED', 'CompassLearn::update'), ('AP_CUSTOMROTATIONS_ENABLED', 'AP_CustomRotation::init'), ('AP_OSD_LINK_STATS_EXTENSIONS_ENABLED', r'AP_OSD_Screen::draw_rc_tx_power'),