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

Conversation

Williangalvani
Copy link
Contributor

No description provided.

@Williangalvani Williangalvani added this to the Sub-4.5 milestone Jul 9, 2024
@Williangalvani Williangalvani changed the title Sub: make gcs failsafe a parameter Sub: make gcs failsafe timeout a parameter Jul 9, 2024
@Williangalvani Williangalvani force-pushed the gcs_timeout branch 4 times, most recently from f807f5a to d094268 Compare July 9, 2024 23:00
@Williangalvani Williangalvani marked this pull request as ready for review July 9, 2024 23:07
#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 milliseconds with no GCS heartbeat
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
# define FS_GCS_TIMEOUT_S 5.0 // gcs failsafe triggers after this number of milliseconds with no GCS heartbeat
# define FS_GCS_TIMEOUT_S 5.0 // gcs failsafe triggers after this number of seconds with no GCS heartbeat

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

fixed, thanks!

@@ -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 float validated_timeout = constrain_float(g.failsafe_gcs_timeout, 2.0, 120);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I really have my reservations about these constraints - particularly the lower one.

This is magic stuff happening in the code, there's nothing the user can know about this from the parameter description.

I don't think it's unreasonable for the user to set outside the bounds you've put in here.

Are you sure you want to bound things here?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I agree with you.
I though I had seen that somewhere else but I cant find it anywhere...
Anyway. code updated, thanks for the review

Copy link
Contributor

@peterbarker peterbarker left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

LGTM

@peterbarker peterbarker merged commit 9e0fd1c into ArduPilot:master Jul 31, 2024
58 checks passed
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

Successfully merging this pull request may close these issues.

2 participants