diff --git a/Tools/scripts/build_options.py b/Tools/scripts/build_options.py index 53b62179de..e6dde1f892 100644 --- a/Tools/scripts/build_options.py +++ b/Tools/scripts/build_options.py @@ -287,6 +287,7 @@ BUILD_OPTIONS = [ Feature('Other', 'BOOTLOADER_FLASHING', 'AP_BOOTLOADER_FLASHING_ENABLED', 'Enable Bootloader flashing', 0, "FILESYSTEM_ROMFS"), # noqa Feature('Other', 'SCRIPTING', 'AP_SCRIPTING_ENABLED', 'Enable LUA Scripting', 0, None), Feature('Other', 'SLCAN', 'AP_CAN_SLCAN_ENABLED', 'Enable SLCAN serial protocol', 0, None), + Feature('Other', 'FENCEPOINT_PROTOCOL', 'AC_POLYFENCE_FENCE_POINT_PROTOCOL_SUPPORT', 'Enable old MAVLink FencePoint protocol', 0, None), # noqa Feature('Developer', 'KILL_IMU', 'AP_INERTIALSENSOR_KILL_IMU_ENABLED', 'Allow IMUs to be disabled at runtime', 0, None), Feature('Developer', 'CRASHCATCHER', 'AP_CRASHDUMP_ENABLED', 'Enable CrashCatcher', 0, None), diff --git a/Tools/scripts/extract_features.py b/Tools/scripts/extract_features.py index f9f6439005..2a5a0e17df 100755 --- a/Tools/scripts/extract_features.py +++ b/Tools/scripts/extract_features.py @@ -200,6 +200,7 @@ class ExtractFeatures(object): ('AP_INERTIALSENSOR_KILL_IMU_ENABLED', r'AP_InertialSensor::kill_imu'), ('AP_CRASHDUMP_ENABLED', 'CrashCatcher_DumpMemory'), ('AP_CAN_SLCAN_ENABLED', 'SLCAN::CANIface::var_info'), + ('AC_POLYFENCE_FENCE_POINT_PROTOCOL_SUPPORT', 'AC_PolyFence_loader::handle_msg_fetch_fence_point'), ] def progress(self, msg):