mirror of https://github.com/ArduPilot/ardupilot
AP_OSD: formatting fixes
This commit is contained in:
parent
694075768f
commit
0f0ceb6499
|
@ -136,14 +136,14 @@ const AP_Param::GroupInfo AP_OSD::var_info[] = {
|
|||
// @Range: 1 20
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("_MSG_TIME", 16, AP_OSD, msgtime_s, 10),
|
||||
|
||||
|
||||
// @Param: _ARM_SCR
|
||||
// @DisplayName: Arm screen
|
||||
// @Description: Screen to be shown on Arm event. Zero to disable the feature.
|
||||
// @Range: 0 4
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("_ARM_SCR", 17, AP_OSD, arm_scr, 0),
|
||||
|
||||
|
||||
// @Param: _DSARM_SCR
|
||||
// @DisplayName: Disarm screen
|
||||
// @Description: Screen to be shown on disarm event. Zero to disable the feature.
|
||||
|
@ -171,7 +171,7 @@ AP_OSD::AP_OSD()
|
|||
#ifdef WITH_SITL_OSD
|
||||
osd_type.set_default(2);
|
||||
#endif
|
||||
|
||||
|
||||
#ifdef HAL_OSD_TYPE_DEFAULT
|
||||
osd_type.set_default(HAL_OSD_TYPE_DEFAULT);
|
||||
#endif
|
||||
|
@ -244,10 +244,10 @@ void AP_OSD::stats()
|
|||
return;
|
||||
}
|
||||
|
||||
// flight distance
|
||||
// flight distance
|
||||
uint32_t delta_ms = now - last_update_ms;
|
||||
last_update_ms = now;
|
||||
|
||||
|
||||
AP_AHRS &ahrs = AP::ahrs();
|
||||
Vector2f v = ahrs.groundspeed_vector();
|
||||
float speed = v.length();
|
||||
|
@ -256,10 +256,10 @@ void AP_OSD::stats()
|
|||
}
|
||||
float dist_m = (speed * delta_ms)*0.001;
|
||||
last_distance_m += dist_m;
|
||||
|
||||
|
||||
// maximum ground speed
|
||||
max_speed_mps = fmaxf(max_speed_mps,speed);
|
||||
|
||||
|
||||
// maximum distance
|
||||
Location loc;
|
||||
if (ahrs.get_position(loc) && ahrs.home_is_set()) {
|
||||
|
@ -267,7 +267,7 @@ void AP_OSD::stats()
|
|||
float distance = home_loc.get_distance(loc);
|
||||
max_dist_m = fmaxf(max_dist_m, distance);
|
||||
}
|
||||
|
||||
|
||||
// maximum altitude
|
||||
float alt;
|
||||
AP::ahrs().get_relative_position_D_home(alt);
|
||||
|
@ -286,32 +286,32 @@ void AP_OSD::stats()
|
|||
void AP_OSD::update_current_screen()
|
||||
{
|
||||
// Switch on ARM/DISARM event
|
||||
if (AP_Notify::flags.armed){
|
||||
if (!was_armed && arm_scr > 0 && arm_scr <= AP_OSD_NUM_SCREENS && screen[arm_scr-1].enabled){
|
||||
if (AP_Notify::flags.armed) {
|
||||
if (!was_armed && arm_scr > 0 && arm_scr <= AP_OSD_NUM_SCREENS && screen[arm_scr-1].enabled) {
|
||||
current_screen = arm_scr-1;
|
||||
}
|
||||
was_armed = true;
|
||||
} else if (was_armed) {
|
||||
if (disarm_scr > 0 && disarm_scr <= AP_OSD_NUM_SCREENS && screen[disarm_scr-1].enabled){
|
||||
if (disarm_scr > 0 && disarm_scr <= AP_OSD_NUM_SCREENS && screen[disarm_scr-1].enabled) {
|
||||
current_screen = disarm_scr-1;
|
||||
}
|
||||
}
|
||||
was_armed = false;
|
||||
}
|
||||
|
||||
|
||||
// Switch on failsafe event
|
||||
if (AP_Notify::flags.failsafe_radio || AP_Notify::flags.failsafe_battery) {
|
||||
if (!was_failsafe && failsafe_scr > 0 && failsafe_scr <= AP_OSD_NUM_SCREENS && screen[failsafe_scr-1].enabled){
|
||||
if (!was_failsafe && failsafe_scr > 0 && failsafe_scr <= AP_OSD_NUM_SCREENS && screen[failsafe_scr-1].enabled) {
|
||||
pre_fs_screen = current_screen;
|
||||
current_screen = failsafe_scr-1;
|
||||
}
|
||||
was_failsafe = true;
|
||||
} else if (was_failsafe) {
|
||||
if (screen[pre_fs_screen].enabled){
|
||||
if (screen[pre_fs_screen].enabled) {
|
||||
current_screen = pre_fs_screen;
|
||||
}
|
||||
}
|
||||
was_failsafe = false;
|
||||
}
|
||||
|
||||
|
||||
if (rc_channel == 0) {
|
||||
return;
|
||||
}
|
||||
|
|
|
@ -27,7 +27,8 @@ class AP_OSD_Backend;
|
|||
/*
|
||||
class to hold one setting
|
||||
*/
|
||||
class AP_OSD_Setting {
|
||||
class AP_OSD_Setting
|
||||
{
|
||||
public:
|
||||
AP_Int8 enabled;
|
||||
AP_Int8 xpos;
|
||||
|
@ -44,7 +45,8 @@ class AP_OSD;
|
|||
/*
|
||||
class to hold one screen of settings
|
||||
*/
|
||||
class AP_OSD_Screen {
|
||||
class AP_OSD_Screen
|
||||
{
|
||||
public:
|
||||
// constructor
|
||||
AP_OSD_Screen();
|
||||
|
@ -183,7 +185,8 @@ private:
|
|||
void draw_clk(uint8_t x, uint8_t y);
|
||||
};
|
||||
|
||||
class AP_OSD {
|
||||
class AP_OSD
|
||||
{
|
||||
public:
|
||||
friend class AP_OSD_Screen;
|
||||
//constructor
|
||||
|
@ -255,7 +258,7 @@ public:
|
|||
};
|
||||
|
||||
void set_nav_info(NavInfo &nav_info);
|
||||
|
||||
|
||||
|
||||
private:
|
||||
void osd_thread();
|
||||
|
@ -264,7 +267,7 @@ private:
|
|||
void update_current_screen();
|
||||
void next_screen();
|
||||
AP_OSD_Backend *backend;
|
||||
|
||||
|
||||
//variables for screen switching
|
||||
uint8_t current_screen;
|
||||
uint16_t previous_channel_value;
|
||||
|
@ -275,7 +278,7 @@ private:
|
|||
int8_t pre_fs_screen;
|
||||
bool was_armed;
|
||||
bool was_failsafe;
|
||||
|
||||
|
||||
uint32_t last_update_ms;
|
||||
float last_distance_m;
|
||||
float max_dist_m;
|
||||
|
|
|
@ -20,7 +20,8 @@
|
|||
#include <AP_OSD/AP_OSD.h>
|
||||
|
||||
|
||||
class AP_OSD_Backend {
|
||||
class AP_OSD_Backend
|
||||
{
|
||||
|
||||
public:
|
||||
//constructor
|
||||
|
|
|
@ -18,7 +18,8 @@
|
|||
#include <AP_OSD/AP_OSD_Backend.h>
|
||||
#include <AP_Common/Bitmask.h>
|
||||
|
||||
class AP_OSD_MAX7456 : public AP_OSD_Backend {
|
||||
class AP_OSD_MAX7456 : public AP_OSD_Backend
|
||||
{
|
||||
|
||||
public:
|
||||
|
||||
|
|
|
@ -25,7 +25,8 @@
|
|||
#include <SFML/Graphics.hpp>
|
||||
#endif
|
||||
|
||||
class AP_OSD_SITL : public AP_OSD_Backend {
|
||||
class AP_OSD_SITL : public AP_OSD_Backend
|
||||
{
|
||||
|
||||
public:
|
||||
static AP_OSD_Backend *probe(AP_OSD &osd);
|
||||
|
|
|
@ -607,7 +607,7 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = {
|
|||
// @Description: Vertical position on screen
|
||||
// @Range: 0 15
|
||||
AP_SUBGROUPINFO(btemp, "BTEMP", 37, AP_OSD_Screen, AP_OSD_Setting),
|
||||
|
||||
|
||||
// @Param: ATEMP_EN
|
||||
// @DisplayName: ATEMP_EN
|
||||
// @Description: Displays temperature reported by primary airspeed sensor
|
||||
|
@ -623,7 +623,7 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = {
|
|||
// @Description: Vertical position on screen
|
||||
// @Range: 0 15
|
||||
AP_SUBGROUPINFO(atemp, "ATEMP", 38, AP_OSD_Screen, AP_OSD_Setting),
|
||||
|
||||
|
||||
// @Param: BAT2VLT_EN
|
||||
// @DisplayName: BAT2VLT_EN
|
||||
// @Description: Displays battery2 voltage
|
||||
|
@ -655,8 +655,8 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = {
|
|||
// @Description: Vertical position on screen
|
||||
// @Range: 0 15
|
||||
AP_SUBGROUPINFO(bat2used, "BAT2USED", 40, AP_OSD_Screen, AP_OSD_Setting),
|
||||
|
||||
|
||||
|
||||
|
||||
// @Param: ASPD2_EN
|
||||
// @DisplayName: ASPD2_EN
|
||||
// @Description: Displays airspeed reported directly from secondary airspeed sensor
|
||||
|
@ -672,21 +672,21 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = {
|
|||
// @Description: Vertical position on screen
|
||||
// @Range: 0 15
|
||||
AP_SUBGROUPINFO(aspd2, "ASPD2", 41, AP_OSD_Screen, AP_OSD_Setting),
|
||||
|
||||
|
||||
// @Param: ASPD1_EN
|
||||
// @DisplayName: ASPD1_EN
|
||||
// @Description: Displays airspeed reported directly from primary airspeed sensor
|
||||
// @Values: 0:Disabled,1:Enabled
|
||||
|
||||
|
||||
// @Param: ASPD1_X
|
||||
// @DisplayName: ASPD1_X
|
||||
// @Description: Horizontal position on screen
|
||||
// @Range: 0 29
|
||||
|
||||
// @Param: ASPD1_Y
|
||||
// @DisplayName: ASPD1_Y
|
||||
// @Description: Vertical position on screen
|
||||
// @Range: 0 15
|
||||
// @DisplayName: ASPD1_X
|
||||
// @Description: Horizontal position on screen
|
||||
// @Range: 0 29
|
||||
|
||||
// @Param: ASPD1_Y
|
||||
// @DisplayName: ASPD1_Y
|
||||
// @Description: Vertical position on screen
|
||||
// @Range: 0 15
|
||||
AP_SUBGROUPINFO(aspd1, "ASPD1", 42, AP_OSD_Screen, AP_OSD_Setting),
|
||||
|
||||
// @Param: CLK_EN
|
||||
|
@ -1411,15 +1411,15 @@ void AP_OSD_Screen::draw_stat(uint8_t x, uint8_t y)
|
|||
backend->write(x, y+2, false, "%5.1f%c", (double)osd->max_current_a, SYM_AMP);
|
||||
backend->write(x, y+3, false, "%5d%c", (int)u_scale(ALTITUDE, osd->max_alt_m), u_icon(ALTITUDE));
|
||||
backend->write(x, y+4, false, "%c", SYM_HOME);
|
||||
draw_distance(x+1, y+4, osd->max_dist_m);
|
||||
draw_distance(x+1, y+4, osd->max_dist_m);
|
||||
backend->write(x, y+5, false, "%c", SYM_DIST);
|
||||
draw_distance(x+1, y+5, osd->last_distance_m);
|
||||
draw_distance(x+1, y+5, osd->last_distance_m);
|
||||
}
|
||||
|
||||
void AP_OSD_Screen::draw_dist(uint8_t x, uint8_t y)
|
||||
{
|
||||
backend->write(x, y, false, "%c", SYM_DIST);
|
||||
draw_distance(x+1, y, osd->last_distance_m);
|
||||
draw_distance(x+1, y, osd->last_distance_m);
|
||||
}
|
||||
|
||||
void AP_OSD_Screen::draw_flightime(uint8_t x, uint8_t y)
|
||||
|
@ -1428,7 +1428,7 @@ void AP_OSD_Screen::draw_flightime(uint8_t x, uint8_t y)
|
|||
if (stats) {
|
||||
uint32_t t = stats->get_flight_time_s();
|
||||
backend->write(x, y, false, "%c%3u:%02u", SYM_FLY, t/60, t%60);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void AP_OSD_Screen::draw_eff(uint8_t x, uint8_t y)
|
||||
|
@ -1439,7 +1439,7 @@ void AP_OSD_Screen::draw_eff(uint8_t x, uint8_t y)
|
|||
Vector2f v = ahrs.groundspeed_vector();
|
||||
float speed = u_scale(SPEED,v.length());
|
||||
float current_amps;
|
||||
if ((speed > 2.0) && battery.current_amps(current_amps)){
|
||||
if ((speed > 2.0) && battery.current_amps(current_amps)) {
|
||||
backend->write(x, y, false, "%c%3d%c", SYM_EFF,int(1000.0f*current_amps/speed),SYM_MAH);
|
||||
} else {
|
||||
backend->write(x, y, false, "%c---%c", SYM_EFF,SYM_MAH);
|
||||
|
@ -1460,14 +1460,16 @@ void AP_OSD_Screen::draw_climbeff(uint8_t x, uint8_t y)
|
|||
WITH_SEMAPHORE(baro.get_semaphore());
|
||||
vspd = baro.get_climb_rate();
|
||||
}
|
||||
if (vspd < 0.0) vspd = 0.0;
|
||||
if (vspd < 0.0) {
|
||||
vspd = 0.0;
|
||||
}
|
||||
AP_BattMonitor &battery = AP::battery();
|
||||
float amps;
|
||||
if (battery.current_amps(amps) && is_positive(amps)) {
|
||||
backend->write(x, y, false,"%c%c%3.1f%c",SYM_PTCHUP,SYM_EFF,(double)(3.6f * u_scale(VSPEED,vspd)/amps),unit_icon);
|
||||
} else {
|
||||
backend->write(x, y, false,"%c%c---%c",SYM_PTCHUP,SYM_EFF,unit_icon);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void AP_OSD_Screen::draw_btemp(uint8_t x, uint8_t y)
|
||||
|
|
Loading…
Reference in New Issue