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

Add flights counter to stats #10020

Open
wants to merge 3 commits into
base: master
Choose a base branch
from

Conversation

TransientTetra
Copy link

I'm proposing a new field to be added to stats, flight counter, i.e. number of flights. I used an assumption that a flight counts once the craft is armed and disarmed and a certain time passes between the two (same as other fields); but only once per each battery pack. I also used uint32 for the field, which I feel is a bit excessive; for uint16 max number of flights would be 32768, I'm leaning on your judgement on that matter.

@MrD-RC
Copy link
Collaborator

MrD-RC commented May 12, 2024

I think uint16_t would be plenty to be honest. That's enough for 1 flight a day for 179 years 🤣

@MrD-RC
Copy link
Collaborator

MrD-RC commented May 12, 2024

I'm wondering if it needs better detection for incrementing the number of flights. Just relying on the arm/disarm action can provide false positives.

#ifdef USE_ADC
.stats_total_energy = SETTING_STATS_TOTAL_ENERGY_DEFAULT
#endif
);

static uint32_t arm_millis;
static uint32_t arm_distance_cm;
static uint32_t prev_flight_count;
Copy link
Collaborator

Choose a reason for hiding this comment

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

I don't think this variable is needed. You can just use the value in statsConfig and statsConfigMutable.

Copy link
Collaborator

Choose a reason for hiding this comment

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

Resolved, but please update to uint16_t 👍🏻

@@ -55,6 +62,7 @@ void statsOnDisarm(void)
if (statsConfig()->stats_enabled) {
uint32_t dt = (millis() - arm_millis) / 1000;
if (dt >= MIN_FLIGHT_TIME_TO_RECORD_STATS_S) {
statsConfigMutable()->stats_flight_count = prev_flight_count + 1; // only increment once per power on
Copy link
Collaborator

Choose a reason for hiding this comment

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

This would just need to be statsConfigMutable()->stats_flight_count++;

Copy link
Author

Choose a reason for hiding this comment

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

If we do it like you said we'd get a flight count increment each time a craft is disarmed and armed; by the definition of a flight that I'm going by we should only get one increment per battery pack (if it was flown longer than MIN_FLIGHT_TIME_TO_RECORD_STATS_S). As far as I can tell that's the most commonly used definition for a flight, and necessitates the function and variable I added. For reference, that's the heuristic behind a popular plugin for flight counting by Offer Shmuely https://github.com/offer-shmuely/edgetx-x10-widgets/tree/master.

Copy link
Collaborator

Choose a reason for hiding this comment

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

I'm not convinced that is the best way to define a flight. We can arm and disarm on a workbench, then remove the battery. That would then be classed as a flight.

We can do things better than EdgeTX. We know that we have moved. Maybe a threshold of x metres away from home would be acceptable to say this is a legitimate flight.

But I do see the point of keeping the previous count 👍🏻

Copy link
Author

Choose a reason for hiding this comment

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

That is a fair point, my goal was to allow flight counting even for simple models that only use inav for stab w/o a gps, but I can see that it'd be more foolproof with a lapsed distance check as you suggested while abandoning a small % of userbase.
The problem you described does apply to power used as well though, doesn't it? Arm on workbench, throttle for longer then the MIN_FLIGHT_TIME, disarm, used mah gets added to stats. Just a thought.
What do you think an agreeable distance threshold would be, eg 10m?

Copy link
Collaborator

Choose a reason for hiding this comment

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

There is already code to detect if the craft is flying ... related to the landing detection stuff. This could be used to make this more reliable if a GPS is available. If a GPS isn't used then just use Arming as the trigger instead.

Copy link
Collaborator

Choose a reason for hiding this comment

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

There's isFlightDetected() in navigation.c that is used to detect when flight has started. It's the best way of knowing if a fixed wing is actually flying. For multirotor the in flight checks are limited but it's as good as you're going to get given a multirotor flight could just be hovering slightly above the ground.

You just need to remember isFlightDetected will be true at some point in the flight, usually immediately after launch, but now necessarily throughout the whole flight.

GPS availability ... sensors(SENSOR_GPS).

Copy link
Author

Choose a reason for hiding this comment

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

With isFlightDetected() I'd need to keep track if it was true at anytime from arm to disarm, and I think it'd be simpler and wouldn't require keeping track of realtime state to just use the trip distance flown and compare it to a threshold. It'd still guard against false positive flight count increments, lemme know which way sounds better.

Copy link
Author

Choose a reason for hiding this comment

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

@breadoven forgot to tag you, pls check out my last comment :)

Copy link
Contributor

@OptimusTi OptimusTi May 23, 2024

Choose a reason for hiding this comment

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

Quick question, isn't there an odometer already in INAV? Why not just check if there's a change in that number?
Just thinking out loud.

Copy link
Author

Choose a reason for hiding this comment

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

Quick question, isn't there an odometer already in INAV? Why not just check if there's a change in that number? Just thinking out loud.

Yea that's more or less what I was thinking, maybe with a threshold set so that moving a meter for example doesn't register as a flight

src/main/fc/stats.c Show resolved Hide resolved
src/main/fc/stats.h Show resolved Hide resolved
src/main/fc/stats.h Outdated Show resolved Hide resolved
src/main/fc/fc_init.c Show resolved Hide resolved
- name: stats_flight_count
description: "Total number of flights. The value is updated on every disarm when \"stats\" are enabled."
default_value: 0
max: INT32_MAX
Copy link
Collaborator

Choose a reason for hiding this comment

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

Make this UNIT16_MAX

@@ -5,18 +5,21 @@
typedef struct statsConfig_s {
uint32_t stats_total_time; // [Seconds]
uint32_t stats_total_dist; // [Metres]
uint32_t stats_flight_count;
Copy link
Collaborator

Choose a reason for hiding this comment

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

I think uint16_t is plenty 👍🏻

Copy link
Author

Choose a reason for hiding this comment

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

Agreed, will do

Copy link
Collaborator

@stronnag stronnag left a comment

Choose a reason for hiding this comment

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

Please update the PG Template version as you've added a field;

PG_REGISTER_WITH_RESET_TEMPLATE(statsConfig_t, statsConfig, PG_STATS_CONFIG, 1);

i.e. from 1 to 2

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.

None yet

5 participants