Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Sub: make gcs failsafe timeout a parameter #27503

Merged
merged 1 commit into from
Jul 31, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 8 additions & 0 deletions ArduSub/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -78,6 +78,14 @@ const AP_Param::Info Sub::var_info[] = {
// @User: Standard
GSCALAR(failsafe_gcs, "FS_GCS_ENABLE", FS_GCS_DISARM),

// @Param: FS_GCS_TIMEOUT
// @DisplayName: GCS failsafe timeout
// @Description: Timeout before triggering the GCS failsafe
// @Units: s
// @Increment: 1
// @User: Standard
GSCALAR(failsafe_gcs_timeout, "FS_GCS_TIMEOUT", FS_GCS_TIMEOUT_S),

// @Param: FS_LEAK_ENABLE
// @DisplayName: Leak Failsafe Enable
// @Description: Controls what action to take if a leak is detected.
Expand Down
2 changes: 2 additions & 0 deletions ArduSub/Parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -185,6 +185,7 @@ class Parameters {
k_param_fs_batt_voltage, // unused - moved to AP_BattMonitor
k_param_failsafe_pilot_input,
k_param_failsafe_pilot_input_timeout,
k_param_failsafe_gcs_timeout,


// Misc Sub settings
Expand Down Expand Up @@ -257,6 +258,7 @@ class Parameters {
AP_Int8 failsafe_terrain;
AP_Int8 failsafe_pilot_input; // pilot input failsafe behavior
AP_Float failsafe_pilot_input_timeout;
AP_Float failsafe_gcs_timeout; // ground station failsafe timeout (seconds)

AP_Int8 xtrack_angle_limit;

Expand Down
4 changes: 2 additions & 2 deletions ArduSub/defines.h
Original file line number Diff line number Diff line change
Expand Up @@ -79,8 +79,8 @@ enum LoggingParameters {
#ifndef FS_GCS
# define FS_GCS DISABLED
#endif
#ifndef FS_GCS_TIMEOUT_MS
# define FS_GCS_TIMEOUT_MS 2500 // gcs failsafe triggers after this number of milliseconds with no GCS heartbeat
#ifndef FS_GCS_TIMEOUT_S
# define FS_GCS_TIMEOUT_S 5.0 // gcs failsafe triggers after this number of seconds with no GCS heartbeat
#endif

// missing terrain data failsafe
Expand Down
3 changes: 2 additions & 1 deletion ArduSub/failsafe.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -321,7 +321,8 @@ void Sub::failsafe_gcs_check()
uint32_t tnow = AP_HAL::millis();

// Check if we have gotten a GCS heartbeat recently (GCS sysid must match SYSID_MYGCS parameter)
if (tnow - gcs_last_seen_ms < FS_GCS_TIMEOUT_MS) {
const uint32_t gcs_timeout_ms = uint32_t(constrain_float(g.failsafe_gcs_timeout * 1000.0f, 0.0f, UINT32_MAX));
if (tnow - gcs_last_seen_ms < gcs_timeout_ms) {
// Log event if we are recovering from previous gcs failsafe
if (failsafe.gcs) {
LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_GCS, LogErrorCode::FAILSAFE_RESOLVED);
Expand Down
Loading