mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 05:58:30 -04:00
AP_OSD: add two new methods to switch osd screen
This commit is contained in:
parent
d0571f55ed
commit
1949166dde
@ -58,6 +58,15 @@ const AP_Param::GroupInfo AP_OSD::var_info[] = {
|
|||||||
// @Path: AP_OSD_Screen.cpp
|
// @Path: AP_OSD_Screen.cpp
|
||||||
AP_SUBGROUPINFO(screen[3], "4_", 6, AP_OSD, AP_OSD_Screen),
|
AP_SUBGROUPINFO(screen[3], "4_", 6, AP_OSD, AP_OSD_Screen),
|
||||||
|
|
||||||
|
// @Param: _SW_METHOD
|
||||||
|
// @DisplayName: Screen switch method
|
||||||
|
// @Description: This sets the method used to switch different OSD screens.
|
||||||
|
// @Values: 0: switch to next screen if channel value was changed,
|
||||||
|
// 1: select screen based on pwm ranges specified for each screen,
|
||||||
|
// 2: switch to next screen every 2s if channel value is high
|
||||||
|
// @User: Standard
|
||||||
|
AP_GROUPINFO("_SW_METHOD", 7, AP_OSD, sw_method, AP_OSD::TOGGLE),
|
||||||
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
||||||
@ -126,11 +135,55 @@ void AP_OSD::update_current_screen()
|
|||||||
}
|
}
|
||||||
|
|
||||||
int16_t channel_value = channel->get_radio_in();
|
int16_t channel_value = channel->get_radio_in();
|
||||||
for (uint8_t i=0; i<AP_OSD_NUM_SCREENS; i++) {
|
switch (sw_method) {
|
||||||
|
//switch to next screen if channel value was changed
|
||||||
|
default:
|
||||||
|
case TOGGLE:
|
||||||
|
if (abs(channel_value-previous_channel_value) > 200) {
|
||||||
|
if (switch_debouncer) {
|
||||||
|
next_screen();
|
||||||
|
previous_channel_value = channel_value;
|
||||||
|
} else {
|
||||||
|
switch_debouncer = true;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
//select screen based on pwm ranges specified
|
||||||
|
case PWM_RANGE:
|
||||||
|
for (int i=0; i<AP_OSD_NUM_SCREENS; i++) {
|
||||||
if (screen[i].enabled && screen[i].channel_min <= channel_value && screen[i].channel_max > channel_value) {
|
if (screen[i].enabled && screen[i].channel_min <= channel_value && screen[i].channel_max > channel_value) {
|
||||||
current_screen = i;
|
current_screen = i;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
break;
|
||||||
|
//switch to next screen every 2s if channel value more than trim value
|
||||||
|
case AUTO_SWITCH:
|
||||||
|
if (channel_value > channel->get_radio_trim()) {
|
||||||
|
if (switch_debouncer) {
|
||||||
|
uint32_t now = AP_HAL::millis();
|
||||||
|
if (now - last_switch_ms > 2000) {
|
||||||
|
next_screen();
|
||||||
|
last_switch_ms = now;
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
switch_debouncer = true;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
switch_debouncer = false;
|
||||||
|
}
|
||||||
|
|
||||||
|
//select next avaliable screen, do nothing if all screens disabled
|
||||||
|
void AP_OSD::next_screen()
|
||||||
|
{
|
||||||
|
uint8_t t = current_screen;
|
||||||
|
do {
|
||||||
|
t = (t + 1)%AP_OSD_NUM_SCREENS;
|
||||||
|
} while (t != current_screen && !screen[t].enabled);
|
||||||
|
current_screen = t;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -17,6 +17,7 @@
|
|||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include <AP_Param/AP_Param.h>
|
#include <AP_Param/AP_Param.h>
|
||||||
|
#include <AP_Math/AP_Math.h>
|
||||||
|
|
||||||
class AP_OSD_Backend;
|
class AP_OSD_Backend;
|
||||||
|
|
||||||
@ -63,6 +64,16 @@ public:
|
|||||||
private:
|
private:
|
||||||
AP_OSD_Backend *backend;
|
AP_OSD_Backend *backend;
|
||||||
|
|
||||||
|
static const uint16_t message_show_time_ms = 20000;
|
||||||
|
static const uint8_t message_visible_width = 26;
|
||||||
|
static const uint8_t message_scroll_time_ms = 200;
|
||||||
|
static const uint8_t message_scroll_delay = 5;
|
||||||
|
|
||||||
|
static constexpr float ah_max_roll = DEG_TO_RAD * 40;
|
||||||
|
static constexpr float ah_max_pitch = DEG_TO_RAD * 20;
|
||||||
|
//typical fpv camera has 80deg vertical field of view, 16 row of chars
|
||||||
|
static constexpr float ah_pitch_rad_to_char = 16.0f/(DEG_TO_RAD * 80);
|
||||||
|
|
||||||
AP_OSD_Setting altitude{true, 1, 1};
|
AP_OSD_Setting altitude{true, 1, 1};
|
||||||
AP_OSD_Setting bat_volt{true, 9, 1};
|
AP_OSD_Setting bat_volt{true, 9, 1};
|
||||||
AP_OSD_Setting rssi{false, 0, 0};
|
AP_OSD_Setting rssi{false, 0, 0};
|
||||||
@ -70,8 +81,9 @@ private:
|
|||||||
AP_OSD_Setting batused{true, 1, 3};
|
AP_OSD_Setting batused{true, 1, 3};
|
||||||
AP_OSD_Setting sats{true, 1, 4};
|
AP_OSD_Setting sats{true, 1, 4};
|
||||||
AP_OSD_Setting fltmode{true, 12, 14};
|
AP_OSD_Setting fltmode{true, 12, 14};
|
||||||
AP_OSD_Setting message{false, 0, 0};
|
AP_OSD_Setting message{false, 2, 13};
|
||||||
AP_OSD_Setting gspeed{false, 0, 0};
|
AP_OSD_Setting gspeed{false, 0, 0};
|
||||||
|
AP_OSD_Setting horizon{true, 15, 8};
|
||||||
|
|
||||||
void draw_altitude(uint8_t x, uint8_t y);
|
void draw_altitude(uint8_t x, uint8_t y);
|
||||||
void draw_bat_volt(uint8_t x, uint8_t y);
|
void draw_bat_volt(uint8_t x, uint8_t y);
|
||||||
@ -82,6 +94,7 @@ private:
|
|||||||
void draw_fltmode(uint8_t x, uint8_t y);
|
void draw_fltmode(uint8_t x, uint8_t y);
|
||||||
void draw_message(uint8_t x, uint8_t y);
|
void draw_message(uint8_t x, uint8_t y);
|
||||||
void draw_gspeed(uint8_t x, uint8_t y);
|
void draw_gspeed(uint8_t x, uint8_t y);
|
||||||
|
void draw_horizon(uint8_t x, uint8_t y);
|
||||||
};
|
};
|
||||||
|
|
||||||
class AP_OSD {
|
class AP_OSD {
|
||||||
@ -103,9 +116,15 @@ public:
|
|||||||
OSD_NONE=0,
|
OSD_NONE=0,
|
||||||
OSD_MAX7456=1,
|
OSD_MAX7456=1,
|
||||||
};
|
};
|
||||||
|
enum switch_method {
|
||||||
|
TOGGLE=0,
|
||||||
|
PWM_RANGE=1,
|
||||||
|
AUTO_SWITCH=2,
|
||||||
|
};
|
||||||
|
|
||||||
AP_Int8 osd_type;
|
AP_Int8 osd_type;
|
||||||
AP_Int8 rc_channel;
|
AP_Int8 rc_channel;
|
||||||
|
AP_Int8 sw_method;
|
||||||
|
|
||||||
AP_OSD_Screen screen[AP_OSD_NUM_SCREENS];
|
AP_OSD_Screen screen[AP_OSD_NUM_SCREENS];
|
||||||
|
|
||||||
@ -113,8 +132,13 @@ private:
|
|||||||
void timer();
|
void timer();
|
||||||
void update_osd();
|
void update_osd();
|
||||||
void update_current_screen();
|
void update_current_screen();
|
||||||
|
void next_screen();
|
||||||
AP_OSD_Backend *backend;
|
AP_OSD_Backend *backend;
|
||||||
uint32_t last_update_ms;
|
uint32_t last_update_ms;
|
||||||
|
|
||||||
|
//variables for screen switching
|
||||||
uint8_t current_screen;
|
uint8_t current_screen;
|
||||||
|
uint16_t previous_channel_value;
|
||||||
|
bool switch_debouncer;
|
||||||
|
uint32_t last_switch_ms;
|
||||||
};
|
};
|
||||||
|
Loading…
Reference in New Issue
Block a user