mirror of https://github.com/ArduPilot/ardupilot
AP_OSD: formatting fixes
This commit is contained in:
parent
aef04fd924
commit
f592806184
|
@ -286,13 +286,13 @@ void AP_OSD::stats()
|
||||||
void AP_OSD::update_current_screen()
|
void AP_OSD::update_current_screen()
|
||||||
{
|
{
|
||||||
// Switch on ARM/DISARM event
|
// Switch on ARM/DISARM event
|
||||||
if (AP_Notify::flags.armed){
|
if (AP_Notify::flags.armed) {
|
||||||
if (!was_armed && arm_scr > 0 && arm_scr <= AP_OSD_NUM_SCREENS && screen[arm_scr-1].enabled){
|
if (!was_armed && arm_scr > 0 && arm_scr <= AP_OSD_NUM_SCREENS && screen[arm_scr-1].enabled) {
|
||||||
current_screen = arm_scr-1;
|
current_screen = arm_scr-1;
|
||||||
}
|
}
|
||||||
was_armed = true;
|
was_armed = true;
|
||||||
} else if (was_armed) {
|
} 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;
|
current_screen = disarm_scr-1;
|
||||||
}
|
}
|
||||||
was_armed = false;
|
was_armed = false;
|
||||||
|
@ -300,13 +300,13 @@ void AP_OSD::update_current_screen()
|
||||||
|
|
||||||
// Switch on failsafe event
|
// Switch on failsafe event
|
||||||
if (AP_Notify::flags.failsafe_radio || AP_Notify::flags.failsafe_battery) {
|
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;
|
pre_fs_screen = current_screen;
|
||||||
current_screen = failsafe_scr-1;
|
current_screen = failsafe_scr-1;
|
||||||
}
|
}
|
||||||
was_failsafe = true;
|
was_failsafe = true;
|
||||||
} else if (was_failsafe) {
|
} else if (was_failsafe) {
|
||||||
if (screen[pre_fs_screen].enabled){
|
if (screen[pre_fs_screen].enabled) {
|
||||||
current_screen = pre_fs_screen;
|
current_screen = pre_fs_screen;
|
||||||
}
|
}
|
||||||
was_failsafe = false;
|
was_failsafe = false;
|
||||||
|
|
|
@ -27,7 +27,8 @@ class AP_OSD_Backend;
|
||||||
/*
|
/*
|
||||||
class to hold one setting
|
class to hold one setting
|
||||||
*/
|
*/
|
||||||
class AP_OSD_Setting {
|
class AP_OSD_Setting
|
||||||
|
{
|
||||||
public:
|
public:
|
||||||
AP_Int8 enabled;
|
AP_Int8 enabled;
|
||||||
AP_Int8 xpos;
|
AP_Int8 xpos;
|
||||||
|
@ -44,7 +45,8 @@ class AP_OSD;
|
||||||
/*
|
/*
|
||||||
class to hold one screen of settings
|
class to hold one screen of settings
|
||||||
*/
|
*/
|
||||||
class AP_OSD_Screen {
|
class AP_OSD_Screen
|
||||||
|
{
|
||||||
public:
|
public:
|
||||||
// constructor
|
// constructor
|
||||||
AP_OSD_Screen();
|
AP_OSD_Screen();
|
||||||
|
@ -181,7 +183,8 @@ private:
|
||||||
void draw_bat2used(uint8_t x, uint8_t y);
|
void draw_bat2used(uint8_t x, uint8_t y);
|
||||||
};
|
};
|
||||||
|
|
||||||
class AP_OSD {
|
class AP_OSD
|
||||||
|
{
|
||||||
public:
|
public:
|
||||||
friend class AP_OSD_Screen;
|
friend class AP_OSD_Screen;
|
||||||
//constructor
|
//constructor
|
||||||
|
|
|
@ -20,7 +20,8 @@
|
||||||
#include <AP_OSD/AP_OSD.h>
|
#include <AP_OSD/AP_OSD.h>
|
||||||
|
|
||||||
|
|
||||||
class AP_OSD_Backend {
|
class AP_OSD_Backend
|
||||||
|
{
|
||||||
|
|
||||||
public:
|
public:
|
||||||
//constructor
|
//constructor
|
||||||
|
|
|
@ -18,7 +18,8 @@
|
||||||
#include <AP_OSD/AP_OSD_Backend.h>
|
#include <AP_OSD/AP_OSD_Backend.h>
|
||||||
#include <AP_Common/Bitmask.h>
|
#include <AP_Common/Bitmask.h>
|
||||||
|
|
||||||
class AP_OSD_MAX7456 : public AP_OSD_Backend {
|
class AP_OSD_MAX7456 : public AP_OSD_Backend
|
||||||
|
{
|
||||||
|
|
||||||
public:
|
public:
|
||||||
|
|
||||||
|
|
|
@ -25,7 +25,8 @@
|
||||||
#include <SFML/Graphics.hpp>
|
#include <SFML/Graphics.hpp>
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
class AP_OSD_SITL : public AP_OSD_Backend {
|
class AP_OSD_SITL : public AP_OSD_Backend
|
||||||
|
{
|
||||||
|
|
||||||
public:
|
public:
|
||||||
static AP_OSD_Backend *probe(AP_OSD &osd);
|
static AP_OSD_Backend *probe(AP_OSD &osd);
|
||||||
|
|
|
@ -678,14 +678,14 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = {
|
||||||
// @Values: 0:Disabled,1:Enabled
|
// @Values: 0:Disabled,1:Enabled
|
||||||
|
|
||||||
// @Param: ASPD1_X
|
// @Param: ASPD1_X
|
||||||
// @DisplayName: ASPD1_X
|
// @DisplayName: ASPD1_X
|
||||||
// @Description: Horizontal position on screen
|
// @Description: Horizontal position on screen
|
||||||
// @Range: 0 29
|
// @Range: 0 29
|
||||||
|
|
||||||
// @Param: ASPD1_Y
|
// @Param: ASPD1_Y
|
||||||
// @DisplayName: ASPD1_Y
|
// @DisplayName: ASPD1_Y
|
||||||
// @Description: Vertical position on screen
|
// @Description: Vertical position on screen
|
||||||
// @Range: 0 15
|
// @Range: 0 15
|
||||||
AP_SUBGROUPINFO(aspd1, "ASPD1", 42, AP_OSD_Screen, AP_OSD_Setting),
|
AP_SUBGROUPINFO(aspd1, "ASPD1", 42, AP_OSD_Screen, AP_OSD_Setting),
|
||||||
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
|
@ -1421,7 +1421,7 @@ void AP_OSD_Screen::draw_eff(uint8_t x, uint8_t y)
|
||||||
Vector2f v = ahrs.groundspeed_vector();
|
Vector2f v = ahrs.groundspeed_vector();
|
||||||
float speed = u_scale(SPEED,v.length());
|
float speed = u_scale(SPEED,v.length());
|
||||||
float current_amps;
|
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);
|
backend->write(x, y, false, "%c%3d%c", SYM_EFF,int(1000.0f*current_amps/speed),SYM_MAH);
|
||||||
} else {
|
} else {
|
||||||
backend->write(x, y, false, "%c---%c", SYM_EFF,SYM_MAH);
|
backend->write(x, y, false, "%c---%c", SYM_EFF,SYM_MAH);
|
||||||
|
@ -1442,7 +1442,9 @@ void AP_OSD_Screen::draw_climbeff(uint8_t x, uint8_t y)
|
||||||
WITH_SEMAPHORE(baro.get_semaphore());
|
WITH_SEMAPHORE(baro.get_semaphore());
|
||||||
vspd = baro.get_climb_rate();
|
vspd = baro.get_climb_rate();
|
||||||
}
|
}
|
||||||
if (vspd < 0.0) vspd = 0.0;
|
if (vspd < 0.0) {
|
||||||
|
vspd = 0.0;
|
||||||
|
}
|
||||||
AP_BattMonitor &battery = AP::battery();
|
AP_BattMonitor &battery = AP::battery();
|
||||||
float amps;
|
float amps;
|
||||||
if (battery.current_amps(amps) && is_positive(amps)) {
|
if (battery.current_amps(amps) && is_positive(amps)) {
|
||||||
|
|
Loading…
Reference in New Issue