From 54a6344bd3190247afd18786ef898fb2b48a8919 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 5 Aug 2024 11:00:49 +1000 Subject: [PATCH] Tool: build_options.py: add AP_ROVER_ADVANCED_FAILSAFE_ENABLED --- Rover/afs_rover.cpp | 4 ++-- Tools/scripts/build_options.py | 2 ++ Tools/scripts/extract_features.py | 2 ++ 3 files changed, 6 insertions(+), 2 deletions(-) diff --git a/Rover/afs_rover.cpp b/Rover/afs_rover.cpp index 60625ed8de..29e1f12da1 100644 --- a/Rover/afs_rover.cpp +++ b/Rover/afs_rover.cpp @@ -32,6 +32,6 @@ AP_AdvancedFailsafe::control_mode AP_AdvancedFailsafe_Rover::afs_mode(void) //to force entering auto mode when datalink loss void AP_AdvancedFailsafe_Rover::set_mode_auto(void) { - over.set_mode(rover.mode_auto,ModeReason::GCS_FAILSAFE); + rover.set_mode(rover.mode_auto,ModeReason::GCS_FAILSAFE); } -#endif // ADVANCED_FAILSAFE +#endif // AP_ROVER_ADVANCED_FAILSAFE_ENABLED diff --git a/Tools/scripts/build_options.py b/Tools/scripts/build_options.py index c6cd5267d1..dacff7b61b 100644 --- a/Tools/scripts/build_options.py +++ b/Tools/scripts/build_options.py @@ -145,6 +145,8 @@ BUILD_OPTIONS = [ Feature('Copter', 'MODE_FLIP', 'MODE_FLIP_ENABLED', 'Enable Mode Flip', 0, None), Feature('Copter', 'MODE_BRAKE', 'MODE_BRAKE_ENABLED', 'Enable Mode Brake', 0, None), + Feature('Rover', 'ROVER_ADVANCED_FAILSAFE', 'AP_ROVER_ADVANCED_FAILSAFE_ENABLED', 'Enable Advanced Failsafe', 0, None), + Feature('Mission', 'MISSION_NAV_PAYLOAD_PLACE', 'AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED', 'Enable handling of NAV_PAYLOAD_PLACE mission items', 0, None), # noqa Feature('Copter', 'AC_PAYLOAD_PLACE_ENABLED', 'AC_PAYLOAD_PLACE_ENABLED', 'Enable Payload Place flight behaviour', 0, 'MISSION_NAV_PAYLOAD_PLACE'), # noqa diff --git a/Tools/scripts/extract_features.py b/Tools/scripts/extract_features.py index 49e8ed719c..c39359602b 100755 --- a/Tools/scripts/extract_features.py +++ b/Tools/scripts/extract_features.py @@ -261,6 +261,8 @@ class ExtractFeatures(object): ('AP_MAVLINK_MSG_HIL_GPS_ENABLED', r'mavlink_msg_hil_gps_decode'), ('AP_BARO_PROBE_EXTERNAL_I2C_BUSES', r'AP_Compass::_probe_external_i2c_compasses'), ('AP_RSSI_ENABLED', r'AP_RSSI::init'), + + ('AP_ROVER_ADVANCED_FAILSAFE_ENABLED', r'Rover::afs_fs_check'), ] def progress(self, msg):