diff --git a/AntennaTracker/Parameters.cpp b/AntennaTracker/Parameters.cpp index 51de25efab..0e9095ad1f 100644 --- a/AntennaTracker/Parameters.cpp +++ b/AntennaTracker/Parameters.cpp @@ -477,6 +477,14 @@ const AP_Param::Info Tracker::var_info[] = { // @Path: ../libraries/AP_Stats/AP_Stats.cpp GOBJECT(stats, "STAT", AP_Stats), + // @Param: AUTO_OPTIONS + // @DisplayName: Auto mode options + // @Description: 1: Scan for unknown target + // @User: Standard + // @Values: 0:None, 1: Scan for unknown target in auto mode + // @Bitmask: 0:Scan for unknown target + GSCALAR(auto_opts, "AUTO_OPTIONS", 0), + // @Group: // @Path: ../libraries/AP_Vehicle/AP_Vehicle.cpp { AP_PARAM_GROUP, "", Parameters::k_param_vehicle, (const void *)&tracker, {group_info : AP_Vehicle::var_info} }, diff --git a/AntennaTracker/Parameters.h b/AntennaTracker/Parameters.h index 5c6a22e040..3fffa5b3ec 100644 --- a/AntennaTracker/Parameters.h +++ b/AntennaTracker/Parameters.h @@ -124,6 +124,8 @@ public: k_param_initial_mode, k_param_disarm_pwm, + k_param_auto_opts, + k_param_logger = 253, // 253 - Logging Group k_param_vehicle = 257, // vehicle common block of parameters @@ -164,6 +166,7 @@ public: AP_Int16 gcs_pid_mask; AP_Int8 initial_mode; AP_Int8 disarm_pwm; + AP_Int8 auto_opts; // Waypoints // diff --git a/AntennaTracker/mode_auto.cpp b/AntennaTracker/mode_auto.cpp index d947776977..1ef9940dca 100644 --- a/AntennaTracker/mode_auto.cpp +++ b/AntennaTracker/mode_auto.cpp @@ -6,7 +6,7 @@ void ModeAuto::update() { if (tracker.vehicle.location_valid) { update_auto(); - } else if (tracker.target_set) { + } else if (tracker.target_set || (tracker.g.auto_opts.get() & (1 << 0)) != 0) { update_scan(); } }