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_OSD: support for main rotor rpm #23711

Merged
merged 2 commits into from May 13, 2023
Merged

Conversation

Ferruccio1984
Copy link
Contributor

displays main rotor rpm in OSD

rpm_osd

Copy link
Contributor

@tridge tridge left a comment

Choose a reason for hiding this comment

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

thanks!
main thing this needs is #if for RPM support

@@ -1638,6 +1654,22 @@ void AP_OSD_Screen::draw_heading(uint8_t x, uint8_t y)
backend->write(x, y, false, "%3d%c", yaw, SYMBOL(SYM_DEGR));
}

void AP_OSD_Screen::draw_rrpm(uint8_t x, uint8_t y)
{
Copy link
Contributor

Choose a reason for hiding this comment

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

we need to check for #if AP_RPM_ENABLED and include AP_RPM/AP_RPM_config.h

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Hi Andrew thank you so much for the recommendations: I have pushed mods in the "fix" commit below, don't know if there's better way to do it though.

// No RPM because pointer is null
_rrpm = -1;
}
backend->write(x, y, false, "%4.0f%c", (double)_rrpm, SYMBOL(SYM_RPM));
Copy link
Contributor

Choose a reason for hiding this comment

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

it is a little more efficient to cast to an integer than double

Copy link
Contributor

@tridge tridge left a comment

Choose a reason for hiding this comment

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

The #if really should be around the variables and parameters too, so there is zero flash cost for boards without RPM, and it doesn't show parameters that can't be used

@tridge tridge added the OSD On screen display label May 10, 2023
@@ -2251,6 +2290,7 @@ void AP_OSD_Screen::draw(void)
DRAW_SETTING(heading);
DRAW_SETTING(wind);
DRAW_SETTING(home);
DRAW_SETTING(rrpm);
Copy link
Contributor

Choose a reason for hiding this comment

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

i'm surprised this compiles with RPM disabled? It will call a non-existant function

libraries/AP_OSD/AP_OSD_Screen.cpp Show resolved Hide resolved
Copy link
Contributor

@tridge tridge left a comment

Choose a reason for hiding this comment

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

looks good! just needs the commits squashed (I can do that if you are not familiar with it)

@tridge tridge changed the base branch from Copter-4.4 to master May 12, 2023 23:10
Copy link
Contributor

@tridge tridge left a comment

Choose a reason for hiding this comment

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

thanks!

displays main rotor rpm in OSD
@Ferruccio1984
Copy link
Contributor Author

Thank you!
Video of testing in sim:

https://youtu.be/Gub8uTVLJHw

.... otherwise include chain on bootloaders can try to include mavlink
@peterbarker
Copy link
Contributor

I've pushed up a patch to resolve the compilation problem this was having in CI

@tridge tridge merged commit 1452dc0 into ArduPilot:master May 13, 2023
81 checks passed
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
MergeOnCIPass OSD On screen display
Projects
None yet
Development

Successfully merging this pull request may close these issues.

None yet

3 participants