From d5918c52059df7c6f4c1c51cf0a72a2950089c75 Mon Sep 17 00:00:00 2001 From: Ferruccio Vicari Date: Sat, 6 May 2023 17:30:43 +0000 Subject: [PATCH] AP_OSD: support for main rotor rpm displays main rotor rpm in OSD --- libraries/AP_OSD/AP_OSD.h | 7 +++++ libraries/AP_OSD/AP_OSD_Screen.cpp | 41 ++++++++++++++++++++++++++++++ 2 files changed, 48 insertions(+) diff --git a/libraries/AP_OSD/AP_OSD.h b/libraries/AP_OSD/AP_OSD.h index 9dcc8b1fc8..617609b85f 100644 --- a/libraries/AP_OSD/AP_OSD.h +++ b/libraries/AP_OSD/AP_OSD.h @@ -28,6 +28,7 @@ #include #include #include +#include #if HAL_GCS_ENABLED #include #endif @@ -185,6 +186,9 @@ private: AP_OSD_Setting aspd1; AP_OSD_Setting aspd2; AP_OSD_Setting vspeed{true, 24, 9}; +#if AP_RPM_ENABLED + AP_OSD_Setting rrpm{false, 2, 2}; +#endif #if HAL_WITH_ESC_TELEM AP_OSD_Setting esc_temp {false, 24, 13}; AP_OSD_Setting esc_rpm{false, 22, 12}; @@ -256,6 +260,9 @@ private: void draw_home(uint8_t x, uint8_t y); void draw_throttle(uint8_t x, uint8_t y); void draw_heading(uint8_t x, uint8_t y); +#if AP_RPM_ENABLED + void draw_rrpm(uint8_t x, uint8_t y); +#endif #ifdef HAL_OSD_SIDEBAR_ENABLE void draw_sidebars(uint8_t x, uint8_t y); #endif diff --git a/libraries/AP_OSD/AP_OSD_Screen.cpp b/libraries/AP_OSD/AP_OSD_Screen.cpp index 64285146b4..0f5e00a53b 100644 --- a/libraries/AP_OSD/AP_OSD_Screen.cpp +++ b/libraries/AP_OSD/AP_OSD_Screen.cpp @@ -40,6 +40,7 @@ #include #include #include +#include #if APM_BUILD_TYPE(APM_BUILD_Rover) #include #endif @@ -1017,6 +1018,24 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Range: 0 15 AP_SUBGROUPINFO(avgcellrestvolt, "ACRVOLT", 61, AP_OSD_Screen, AP_OSD_Setting), +#if AP_RPM_ENABLED + // @Param: RPM_EN + // @DisplayName: RPM_EN + // @Description: Displays main rotor revs/min + // @Values: 0:Disabled,1:Enabled + + // @Param: RPM_X + // @DisplayName: RPM_X + // @Description: Horizontal position on screen + // @Range: 0 29 + + // @Param: RPM_Y + // @DisplayName: RPM_Y + // @Description: Vertical position on screen + // @Range: 0 15 + AP_SUBGROUPINFO(rrpm, "RPM", 62, AP_OSD_Screen, AP_OSD_Setting), +#endif + AP_GROUPEND }; @@ -1646,6 +1665,25 @@ void AP_OSD_Screen::draw_heading(uint8_t x, uint8_t y) backend->write(x, y, false, "%3d%c", yaw, SYMBOL(SYM_DEGR)); } +#if AP_RPM_ENABLED +void AP_OSD_Screen::draw_rrpm(uint8_t x, uint8_t y) +{ + float _rrpm; + const AP_RPM *rpm = AP_RPM::get_singleton(); + if (rpm != nullptr) { + if (!rpm->get_rpm(0, _rrpm)) { + // No valid RPM data + _rrpm = -1; + } + } else { + // No RPM because pointer is null + _rrpm = -1; + } + int r_rpm = static_cast(_rrpm); + backend->write(x, y, false, "%4d%c", (int)r_rpm, SYMBOL(SYM_RPM)); +} +#endif + void AP_OSD_Screen::draw_throttle(uint8_t x, uint8_t y) { backend->write(x, y, false, "%3d%c", gcs().get_hud_throttle(), SYMBOL(SYM_PCNT)); @@ -2257,6 +2295,9 @@ void AP_OSD_Screen::draw(void) DRAW_SETTING(heading); DRAW_SETTING(wind); DRAW_SETTING(home); +#if AP_RPM_ENABLED + DRAW_SETTING(rrpm); +#endif #if AP_FENCE_ENABLED DRAW_SETTING(fence); #endif