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

AP_Stats: update flight time on disarm #25778

Merged
merged 1 commit into from
Apr 5, 2024

Conversation

tatsuy
Copy link
Contributor

@tatsuy tatsuy commented Dec 15, 2023

This PR fixes an issue where flight time was not being updated if the power was shut down immediately after flight.
Since the update occurs in 30-second cycles, turning off the power before the update process means the last flight time is not added.

I have modified update function so that the flight time updates upon disarming, in addition to the regular updates every 30 seconds.

I have confirmed that the flight time is updated immediately after disarming in SITL.

@IamPete1
Copy link
Member

Why not add the flush to the set_flying call? That is when the flight time will stop counting up so there should be no change in value. The key thing it needs is the flush to save the value to eeprom.

I think you could just add flush() in there, also updating last_flush_ms.

update_flighttime();
_flying_ms = 0;

It just seems a little odd to trigger the save on arming when the stat is based on flying.

@tatsuy
Copy link
Contributor Author

tatsuy commented Dec 16, 2023

@IamPete1 Thank you for your suggestion.

I think you could just add flush() in there, also updating last_flush_ms.
In this case, runtime will no longer be updated because update_runtime() is no longer called during disarm

If we add update_runtime() and flush() in there, also updating last_flush_ms, runtime is updated whenever the drone is not flying. It could lead to frequent updates of the runtime value.

I thought it would be better to update once only when disarming.

@IamPete1
Copy link
Member

If we add update_runtime() and flush() in there, also updating last_flush_ms, runtime is updated whenever the drone is not flying. It could lead to frequent updates of the runtime value.

Right, you would have to check _flying_ms

if (_flying_ms) {
    flush();
    last_flush_ms = now;
}

Having broken out the millis fetch from the other branch of the if to populate "now".

@muramura
Copy link
Contributor

muramura commented Dec 17, 2023

This method adds up to less than 30 seconds.

The notification to GCS is in 30-second increments.
The GCS displays the event as 30 seconds short.

I think that by executing flush() in this method, we can update the flash memory and repair the 30 seconds short of the GCS.

void AP_Stats::set_flying(const bool is_flying)
{
if (is_flying) {
if (!_flying_ms) {
_flying_ms = AP_HAL::millis();
}
} else {
update_flighttime();
_flying_ms = 0;
flush(); ★ To GCS
}
}

@peterbarker
Copy link
Contributor

Concur with Peter and Muramura here; move the update of last_flash_ms into the flush method itself, however, rather than setting it after calling flush

@tatsuy tatsuy force-pushed the pr-stat-update-disarm branch from 0934587 to 1d66653 Compare December 18, 2023 01:42
@tatsuy
Copy link
Contributor Author

tatsuy commented Dec 18, 2023

Thank you for the reviews.
I added the flush to the set_flying call and moved the update of last_flash_ms into the flush method.
Additionally, I've called not only update_flighttime but also update_runtime to maintain consistency.

For the test:
Twice, I repeated the process of letting SITL fly and then immediately terminating SITL after disarming.
This PR:
image
It works.

In case of no update_runtime():
image
STAT_FLTTIME >STAT_RUNTIME and it is not consistent.

@tatsuy tatsuy force-pushed the pr-stat-update-disarm branch from 1d66653 to b8967a7 Compare February 2, 2024 02:02
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 f1d37fc into ArduPilot:master Apr 5, 2024
92 checks passed
@peterbarker
Copy link
Contributor

Merged, thanks!

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

4 participants