mirror of https://github.com/ArduPilot/ardupilot
AP_OSD: support for main rotor rpm
displays main rotor rpm in OSD
This commit is contained in:
parent
67537b1806
commit
d5918c5205
|
@ -28,6 +28,7 @@
|
||||||
#include <AP_OLC/AP_OLC.h>
|
#include <AP_OLC/AP_OLC.h>
|
||||||
#include <AP_MSP/msp.h>
|
#include <AP_MSP/msp.h>
|
||||||
#include <AP_Baro/AP_Baro.h>
|
#include <AP_Baro/AP_Baro.h>
|
||||||
|
#include <AP_RPM/AP_RPM_config.h>
|
||||||
#if HAL_GCS_ENABLED
|
#if HAL_GCS_ENABLED
|
||||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||||
#endif
|
#endif
|
||||||
|
@ -185,6 +186,9 @@ private:
|
||||||
AP_OSD_Setting aspd1;
|
AP_OSD_Setting aspd1;
|
||||||
AP_OSD_Setting aspd2;
|
AP_OSD_Setting aspd2;
|
||||||
AP_OSD_Setting vspeed{true, 24, 9};
|
AP_OSD_Setting vspeed{true, 24, 9};
|
||||||
|
#if AP_RPM_ENABLED
|
||||||
|
AP_OSD_Setting rrpm{false, 2, 2};
|
||||||
|
#endif
|
||||||
#if HAL_WITH_ESC_TELEM
|
#if HAL_WITH_ESC_TELEM
|
||||||
AP_OSD_Setting esc_temp {false, 24, 13};
|
AP_OSD_Setting esc_temp {false, 24, 13};
|
||||||
AP_OSD_Setting esc_rpm{false, 22, 12};
|
AP_OSD_Setting esc_rpm{false, 22, 12};
|
||||||
|
@ -256,6 +260,9 @@ private:
|
||||||
void draw_home(uint8_t x, uint8_t y);
|
void draw_home(uint8_t x, uint8_t y);
|
||||||
void draw_throttle(uint8_t x, uint8_t y);
|
void draw_throttle(uint8_t x, uint8_t y);
|
||||||
void draw_heading(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
|
#ifdef HAL_OSD_SIDEBAR_ENABLE
|
||||||
void draw_sidebars(uint8_t x, uint8_t y);
|
void draw_sidebars(uint8_t x, uint8_t y);
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -40,6 +40,7 @@
|
||||||
#include <AP_Terrain/AP_Terrain.h>
|
#include <AP_Terrain/AP_Terrain.h>
|
||||||
#include <AP_RangeFinder/AP_RangeFinder.h>
|
#include <AP_RangeFinder/AP_RangeFinder.h>
|
||||||
#include <AP_Vehicle/AP_Vehicle.h>
|
#include <AP_Vehicle/AP_Vehicle.h>
|
||||||
|
#include <AP_RPM/AP_RPM.h>
|
||||||
#if APM_BUILD_TYPE(APM_BUILD_Rover)
|
#if APM_BUILD_TYPE(APM_BUILD_Rover)
|
||||||
#include <AP_WindVane/AP_WindVane.h>
|
#include <AP_WindVane/AP_WindVane.h>
|
||||||
#endif
|
#endif
|
||||||
|
@ -1017,6 +1018,24 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = {
|
||||||
// @Range: 0 15
|
// @Range: 0 15
|
||||||
AP_SUBGROUPINFO(avgcellrestvolt, "ACRVOLT", 61, AP_OSD_Screen, AP_OSD_Setting),
|
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
|
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));
|
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<int>(_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)
|
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));
|
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(heading);
|
||||||
DRAW_SETTING(wind);
|
DRAW_SETTING(wind);
|
||||||
DRAW_SETTING(home);
|
DRAW_SETTING(home);
|
||||||
|
#if AP_RPM_ENABLED
|
||||||
|
DRAW_SETTING(rrpm);
|
||||||
|
#endif
|
||||||
#if AP_FENCE_ENABLED
|
#if AP_FENCE_ENABLED
|
||||||
DRAW_SETTING(fence);
|
DRAW_SETTING(fence);
|
||||||
#endif
|
#endif
|
||||||
|
|
Loading…
Reference in New Issue