AP_OSD: moved to new parameter system

This commit is contained in:
Andrew Tridgell 2018-06-24 20:00:23 +10:00
parent 8e8508a9f3
commit 8f8107d13f
4 changed files with 337 additions and 224 deletions

View File

@ -17,117 +17,45 @@
* Many thanks to their authors.
*/
#include <AP_OSD/AP_OSD.h>
#include <AP_OSD/AP_OSD_MAX7456.h>
#include <AP_Math/AP_Math.h>
#include <AP_AHRS/AP_AHRS.h>
#include <AP_RSSI/AP_RSSI.h>
#include <AP_Notify/AP_Notify.h>
#include "AP_OSD.h"
#include "AP_OSD_MAX7456.h"
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL/Util.h>
#include <utility>
// Character coordinate and attributes
#define VISIBLE_FLAG 0x0800
#define VISIBLE(x) (x & VISIBLE_FLAG)
#define OSD_POS(x,y) (x | (y << 5))
#define OSD_X(x) (x & 0x001F)
#define OSD_Y(x) ((x >> 5) & 0x001F)
//Symbols
#define SYM_BLANK 0x20
#define SYM_COLON 0x2D
#define SYM_ZERO_HALF_TRAILING_DOT 192
#define SYM_ZERO_HALF_LEADING_DOT 208
#define SYM_M 177
#define SYM_ALT_M 177
#define SYM_BATT_FULL 0x90
#define SYM_RSSI 0x01
#define SYM_VOLT 0x06
#define SYM_AMP 0x9A
#define SYM_MAH 0x07
#define SYM_SAT_L 0x1E
#define SYM_SAT_R 0x1F
#define AH_SYMBOL_COUNT 9
const AP_Param::GroupInfo AP_OSD::var_info[] = {
// @Param: ENABLED
// @DisplayName: Enable OSD
// @Description: Enable OSD
// @Values: 0:Disabled,1:Enabled
// @Param: _TYPE
// @DisplayName: OSD type
// @Description: OSD type
// @Values: 0:None,1:MAX7456
// @User: Standard
AP_GROUPINFO_FLAGS("ENABLED", 0, AP_OSD, osd_enabled, 1, AP_PARAM_FLAG_ENABLE),
AP_GROUPINFO_FLAGS("_TYPE", 1, AP_OSD, osd_type, 0, AP_PARAM_FLAG_ENABLE),
// @Param: UPDATE_FONT
// @Param: _UPDATE_FONT
// @DisplayName: Update font
// @Description: Undate font inside osd chip
// @Values: 0:Do not update,1:Update
// @User: Standard
AP_GROUPINFO("UPDATE_FONT", 1, AP_OSD, update_font, 1),
AP_GROUPINFO("_UPDATE_FONT", 2, AP_OSD, update_font, 1),
// @Param: 1_ALTITUDE
// @DisplayName: Altitude position
// @Description: Altitude position and visibility
// @Values: 2048 * visible + x + y * 16
// @User: Advanced
AP_GROUPINFO("1_ALTITUDE", 2, AP_OSD, pos_altitude, OSD_POS(1, 0) | VISIBLE_FLAG),
// @Group: 1_
// @Path: AP_OSD_Screen.cpp
AP_SUBGROUPINFO(screen[0], "1_", 3, AP_OSD, AP_OSD_Screen),
// @Param:1_BATT_VOLTAGE
// @DisplayName:
// @Description:
// @Values: 2048 * visible + x + y * 16
// @User: Advanced
AP_GROUPINFO("1_BAT_VOLT", 3, AP_OSD, pos_batt_voltage, OSD_POS(12, 0) | VISIBLE_FLAG),
// @Group: 2_
// @Path: AP_OSD_Screen.cpp
AP_SUBGROUPINFO(screen[1], "2_", 4, AP_OSD, AP_OSD_Screen),
// @Param:1_RSSI
// @DisplayName:
// @Description:
// @Values: 2048 * visible + x + y * 16
// @User: Advanced
AP_GROUPINFO("1_RSSI", 4, AP_OSD, pos_rssi, OSD_POS(23, 0) | VISIBLE_FLAG),
// @Param:1_CURRENT_DRAW
// @DisplayName:
// @Description:
// @Values: 2048 * visible + x + y * 16
// @User: Advanced
AP_GROUPINFO("1_CUR_DRAW", 5, AP_OSD, pos_current_draw, OSD_POS(1, 3) | VISIBLE_FLAG),
// @Param:1_MAH_DRAWN
// @DisplayName:
// @Description:
// @Values: 2048 * visible + x + y * 16
// @User: Advanced
AP_GROUPINFO("1_MAH_DRAWN", 6, AP_OSD, pos_mah_drawn, OSD_POS(1, 4) | VISIBLE_FLAG),
// @Param:1_GPS_SATS
// @DisplayName:
// @Description:
// @Values: 2048 * visible + x + y * 16
// @User: Advanced
AP_GROUPINFO("1_GPS_SATS", 7, AP_OSD, pos_gps_sats, OSD_POS(0, 11) | VISIBLE_FLAG),
// @Param:1_FLYMODE
// @DisplayName:
// @Description:
// @Values: 2048 * visible + x + y * 16
// @User: Advanced
AP_GROUPINFO("1_FLYMODE", 8, AP_OSD, pos_flymode, OSD_POS(12, 12) | VISIBLE_FLAG),
// @Param:1_MESSAGES
// @DisplayName:
// @Description:
// @Values: 2048 * visible + x + y * 16
// @User: Advanced
AP_GROUPINFO("1_MESSAGES", 9, AP_OSD, pos_messages, OSD_POS(1, 13) | VISIBLE_FLAG),
// @Group: 2_
// @Path: AP_OSD_Screen.cpp
AP_SUBGROUPINFO(screen[2], "3_", 5, AP_OSD, AP_OSD_Screen),
// @Group: 2_
// @Path: AP_OSD_Screen.cpp
AP_SUBGROUPINFO(screen[3], "4_", 6, AP_OSD, AP_OSD_Screen),
AP_GROUPEND
};
@ -140,26 +68,30 @@ AP_OSD::AP_OSD() : backend(nullptr), last_update_ms(0)
void AP_OSD::init()
{
if (!osd_enabled) {
return;
switch ((enum osd_types)osd_type.get()) {
case OSD_NONE:
break;
case OSD_MAX7456:
AP_HAL::OwnPtr<AP_HAL::Device> spi_dev = std::move(hal.spi->get_device("osd"));
if (!spi_dev) {
break;
}
backend = AP_OSD_MAX7456::probe(*this, std::move(spi_dev));
if (backend == nullptr) {
break;
}
hal.console->printf("Started MAX7456 OSD\n");
hal.scheduler->register_io_process(FUNCTOR_BIND_MEMBER(&AP_OSD::timer, void));
break;
}
AP_HAL::OwnPtr<AP_HAL::Device> spi_dev = std::move(hal.spi->get_device("osd"));
if (!spi_dev) {
return;
}
backend = AP_OSD_MAX7456::probe(*this, std::move(spi_dev));
if (backend == nullptr) {
return;
}
last_update_ms = 0;
hal.scheduler->register_io_process(FUNCTOR_BIND_MEMBER(&AP_OSD::timer, void));
}
void AP_OSD::timer()
{
uint32_t now = AP_HAL::millis();
if (now - last_update_ms > 16) {
if (now - last_update_ms > 100) {
last_update_ms = now;
update_osd();
}
@ -169,104 +101,9 @@ void AP_OSD::update_osd()
{
backend->clear();
draw_messages();
draw_flymode();
draw_altitude();
draw_batt_voltage();
draw_rssi();
draw_current_draw();
draw_mah_drawn();
draw_gps_sats();
screen[current_screen].set_backend(backend);
screen[current_screen].draw();
backend->flush();
}
void AP_OSD::draw_altitude()
{
if (VISIBLE(pos_altitude)) {
uint8_t x = OSD_X(pos_altitude);
uint8_t y = OSD_Y(pos_altitude);
float alt;
AP_AHRS::get_singleton()->get_relative_position_D_home(alt);
backend->write(x, y, false, "%4.0f%c", alt, SYM_ALT_M);
}
}
void AP_OSD::draw_batt_voltage()
{
if (VISIBLE(pos_batt_voltage)) {
uint8_t x = OSD_X(pos_batt_voltage);
uint8_t y = OSD_Y(pos_batt_voltage);
AP_BattMonitor & battery = AP_BattMonitor::battery();
uint8_t p = battery.capacity_remaining_pct();
p = (100 - p) / 16.6;
backend->write(x,y, battery.has_failsafed(), "%c%2.1fV", SYM_BATT_FULL + p, battery.voltage());
}
}
void AP_OSD::draw_rssi()
{
if (VISIBLE(pos_rssi)) {
uint8_t x = OSD_X(pos_rssi);
uint8_t y = OSD_Y(pos_rssi);
int rssi = AP_RSSI::get_instance()->read_receiver_rssi_uint8();
rssi = (rssi * 99) / 255;
backend->write(x, y, rssi < 5, "%c%2d", SYM_RSSI, rssi);
}
}
void AP_OSD::draw_current_draw()
{
if (VISIBLE(pos_current_draw)) {
uint8_t x = OSD_X(pos_current_draw);
uint8_t y = OSD_Y(pos_current_draw);
AP_BattMonitor & battery = AP_BattMonitor::battery();
float current = battery.current_amps();
backend->write(x, y, false, "%c%2.1f",SYM_AMP, current);
}
}
void AP_OSD::draw_flymode()
{
if (VISIBLE(pos_flymode)) {
uint8_t x = OSD_X(pos_flymode);
uint8_t y = OSD_Y(pos_flymode);
backend->write(x, y, AP_Notify::instance()->get_flight_mode_str());
}
}
void AP_OSD::draw_gps_sats()
{
if (VISIBLE(pos_gps_sats)) {
uint8_t x = OSD_X(pos_gps_sats);
uint8_t y = OSD_Y(pos_gps_sats);
AP_GPS& gps = AP::gps();
bool has_3dfix = gps.status() <= AP_GPS::GPS_OK_FIX_2D;
backend->write(x, y, !has_3dfix, "%c%c%2d", SYM_SAT_L, SYM_SAT_R, gps.num_sats());
}
}
void AP_OSD::draw_mah_drawn()
{
if (VISIBLE(pos_mah_drawn)) {
uint8_t x = OSD_X(pos_mah_drawn);
uint8_t y = OSD_Y(pos_mah_drawn);
AP_BattMonitor & battery = AP_BattMonitor::battery();
backend->write(x,y, battery.has_failsafed(), "%c%4.0f", SYM_MAH, battery.consumed_mah());
}
}
void AP_OSD::draw_messages()
{
if (VISIBLE(pos_messages)) {
uint8_t x = OSD_X(pos_messages);
uint8_t y = OSD_Y(pos_messages);
AP_Notify * notify = AP_Notify::instance();
bool text_is_valid = AP_HAL::millis() - notify->get_text_updated_millis() < 20000;
if (text_is_valid) {
backend->write(x, y, notify->get_text());
}
}
}

View File

@ -20,6 +20,62 @@
class AP_OSD_Backend;
#define AP_OSD_NUM_SCREENS 4
/*
class to hold one setting
*/
class AP_OSD_Setting {
public:
AP_Int8 enabled;
AP_Int8 xpos;
AP_Int8 ypos;
AP_OSD_Setting(bool enabled, uint8_t x, uint8_t y);
// User settable parameters
static const struct AP_Param::GroupInfo var_info[];
};
/*
class to hold one screen of settings
*/
class AP_OSD_Screen {
public:
// constructor
AP_OSD_Screen();
void draw(void);
void set_backend(AP_OSD_Backend *_backend) { backend = _backend; };
// User settable parameters
static const struct AP_Param::GroupInfo var_info[];
private:
AP_Int8 enabled;
AP_OSD_Backend *backend;
AP_OSD_Setting altitude{true, 1, 1};
AP_OSD_Setting bat_volt{true, 9, 1};
AP_OSD_Setting rssi{false, 0, 0};
AP_OSD_Setting current{true, 1, 2};
AP_OSD_Setting batused{true, 1, 3};
AP_OSD_Setting sats{true, 1, 4};
AP_OSD_Setting fltmode{true, 12, 14};
AP_OSD_Setting message{false, 0, 0};
void draw_altitude(uint8_t x, uint8_t y);
void draw_bat_volt(uint8_t x, uint8_t y);
void draw_rssi(uint8_t x, uint8_t y);
void draw_current(uint8_t x, uint8_t y);
void draw_batused(uint8_t x, uint8_t y);
void draw_sats(uint8_t x, uint8_t y);
void draw_fltmode(uint8_t x, uint8_t y);
void draw_message(uint8_t x, uint8_t y);
};
class AP_OSD {
public:
//constructor
@ -35,17 +91,15 @@ public:
// User settable parameters
static const struct AP_Param::GroupInfo var_info[];
AP_Int8 osd_enabled;
enum osd_types {
OSD_NONE=0,
OSD_MAX7456=1,
};
AP_Int8 osd_type;
AP_Int8 update_font;
AP_Int16 pos_altitude;
AP_Int16 pos_batt_voltage;
AP_Int16 pos_rssi;
AP_Int16 pos_current_draw;
AP_Int16 pos_mah_drawn;
AP_Int16 pos_gps_sats;
AP_Int16 pos_flymode;
AP_Int16 pos_messages;
AP_OSD_Screen screen[AP_OSD_NUM_SCREENS];
private:
void timer();
@ -53,15 +107,5 @@ private:
AP_OSD_Backend *backend;
uint32_t last_update_ms;
void draw_altitude();
void draw_batt_voltage();
void draw_rssi();
void draw_current_draw();
void draw_mah_drawn();
void draw_horizon();
void draw_ontime_flytime();
void draw_gps_sats();
void draw_flymode();
void draw_messages();
uint8_t current_screen;
};

View File

@ -0,0 +1,175 @@
/*
* This file is free software: you can redistribute it and/or modify it
* under the terms of the GNU General Public License as published by the
* Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This file is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>.
*
* AP_OSD partially based on betaflight and inav osd.c implemention.
* clarity.mcm font is taken from inav configurator.
* Many thanks to their authors.
*/
/*
parameter settings for one screen
*/
#include "AP_OSD.h"
#include "AP_OSD_Backend.h"
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL/Util.h>
#include <AP_AHRS/AP_AHRS.h>
#include <AP_Math/AP_Math.h>
#include <AP_RSSI/AP_RSSI.h>
#include <AP_Notify/AP_Notify.h>
const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = {
// @Param: ENABLE
// @DisplayName: Enable screen
// @Description: Enable this screen
// @Values: 0:Disabled,1:Enabled
// @User: Standard
AP_GROUPINFO_FLAGS("ENABLE", 1, AP_OSD_Screen, enabled, 0, AP_PARAM_FLAG_ENABLE),
// @Group: ALTITUDE
// @Path: AP_OSD_Setting.cpp
AP_SUBGROUPINFO(altitude, "ALTITUDE", 2, AP_OSD_Screen, AP_OSD_Setting),
// @Group: BATVOLT
// @Path: AP_OSD_Setting.cpp
AP_SUBGROUPINFO(bat_volt, "BAT_VOLS", 3, AP_OSD_Screen, AP_OSD_Setting),
// @Group: RSSI
// @Path: AP_OSD_Setting.cpp
AP_SUBGROUPINFO(rssi, "RSSI", 4, AP_OSD_Screen, AP_OSD_Setting),
// @Group: CURRENT
// @Path: AP_OSD_Setting.cpp
AP_SUBGROUPINFO(current, "CURRENT", 5, AP_OSD_Screen, AP_OSD_Setting),
// @Group: BATUSED
// @Path: AP_OSD_Setting.cpp
AP_SUBGROUPINFO(batused, "BATUSED", 6, AP_OSD_Screen, AP_OSD_Setting),
// @Group: SATS
// @Path: AP_OSD_Setting.cpp
AP_SUBGROUPINFO(sats, "SATS", 7, AP_OSD_Screen, AP_OSD_Setting),
// @Group: FLTMODE
// @Path: AP_OSD_Setting.cpp
AP_SUBGROUPINFO(fltmode, "FLTMODE", 8, AP_OSD_Screen, AP_OSD_Setting),
// @Group: MESSAGE
// @Path: AP_OSD_Setting.cpp
AP_SUBGROUPINFO(message, "MESSAGE", 9, AP_OSD_Screen, AP_OSD_Setting),
AP_GROUPEND
};
// constructor
AP_OSD_Screen::AP_OSD_Screen()
{
}
//Symbols
#define SYM_BLANK 0x20
#define SYM_COLON 0x2D
#define SYM_ZERO_HALF_TRAILING_DOT 192
#define SYM_ZERO_HALF_LEADING_DOT 208
#define SYM_M 177
#define SYM_ALT_M 177
#define SYM_BATT_FULL 0x90
#define SYM_RSSI 0x01
#define SYM_VOLT 0x06
#define SYM_AMP 0x9A
#define SYM_MAH 0x07
#define SYM_SAT_L 0x1E
#define SYM_SAT_R 0x1F
#define AH_SYMBOL_COUNT 9
void AP_OSD_Screen::draw_altitude(uint8_t x, uint8_t y)
{
float alt;
AP_AHRS::get_singleton()->get_relative_position_D_home(alt);
backend->write(x, y, false, "%4.0f%c", alt, SYM_ALT_M);
}
void AP_OSD_Screen::draw_bat_volt(uint8_t x, uint8_t y)
{
AP_BattMonitor &battery = AP_BattMonitor::battery();
uint8_t p = battery.capacity_remaining_pct();
p = (100 - p) / 16.6;
backend->write(x,y, battery.has_failsafed(), "%c%2.1fV", SYM_BATT_FULL + p, battery.voltage());
}
void AP_OSD_Screen::draw_rssi(uint8_t x, uint8_t y)
{
int rssiv = AP_RSSI::get_instance()->read_receiver_rssi_uint8();
rssiv = (rssiv * 99) / 255;
backend->write(x, y, rssiv < 5, "%c%2d", SYM_RSSI, rssiv);
}
void AP_OSD_Screen::draw_current(uint8_t x, uint8_t y)
{
AP_BattMonitor &battery = AP_BattMonitor::battery();
float amps = battery.current_amps();
backend->write(x, y, false, "%c%2.1f", SYM_AMP, amps);
}
void AP_OSD_Screen::draw_fltmode(uint8_t x, uint8_t y)
{
backend->write(x, y, AP_Notify::instance()->get_flight_mode_str());
}
void AP_OSD_Screen::draw_sats(uint8_t x, uint8_t y)
{
AP_GPS & gps = AP::gps();
bool has_3dfix = gps.status() <= AP_GPS::GPS_OK_FIX_2D;
backend->write(x, y, !has_3dfix, "%c%c%2d", SYM_SAT_L, SYM_SAT_R, gps.num_sats());
}
void AP_OSD_Screen::draw_batused(uint8_t x, uint8_t y)
{
AP_BattMonitor &battery = AP_BattMonitor::battery();
backend->write(x,y, battery.has_failsafed(), "%c%4.0f", SYM_MAH, battery.consumed_mah());
}
void AP_OSD_Screen::draw_message(uint8_t x, uint8_t y)
{
AP_Notify * notify = AP_Notify::instance();
if (notify) {
bool text_is_valid = AP_HAL::millis() - notify->get_text_updated_millis() < 20000;
if (text_is_valid) {
backend->write(x, y, notify->get_text());
}
}
}
#define DRAW_SETTING(n) if (n.enabled) draw_ ## n(n.xpos, n.ypos)
void AP_OSD_Screen::draw(void)
{
if (!enabled || !backend) {
return;
}
DRAW_SETTING(altitude);
DRAW_SETTING(bat_volt);
DRAW_SETTING(rssi);
DRAW_SETTING(current);
DRAW_SETTING(batused);
DRAW_SETTING(sats);
DRAW_SETTING(fltmode);
DRAW_SETTING(message);
}

View File

@ -0,0 +1,57 @@
/*
* This file is free software: you can redistribute it and/or modify it
* under the terms of the GNU General Public License as published by the
* Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This file is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>.
*
* AP_OSD partially based on betaflight and inav osd.c implemention.
* clarity.mcm font is taken from inav configurator.
* Many thanks to their authors.
*/
/*
parameter object for one setting in AP_OSD
*/
#include "AP_OSD.h"
const AP_Param::GroupInfo AP_OSD_Setting::var_info[] = {
// @Param: _EN
// @DisplayName: Enable
// @Description: Enable setting
// @Values: 0:Disabled,1:Enabled
// @User: Standard
AP_GROUPINFO("_EN", 1, AP_OSD_Setting, enabled, 0),
// @Param: _X
// @DisplayName: X position
// @Description: Horizontal position on screen
// @Range: 0 31
// @User: Standard
AP_GROUPINFO("_X", 2, AP_OSD_Setting, xpos, 0),
// @Param: _Y
// @DisplayName: Y position
// @Description: Vertical position on screen
// @Range: 0 15
// @User: Standard
AP_GROUPINFO("_Y", 3, AP_OSD_Setting, ypos, 0),
AP_GROUPEND
};
// constructor
AP_OSD_Setting::AP_OSD_Setting(bool _enabled, uint8_t x, uint8_t y)
{
enabled = _enabled;
xpos = x;
ypos = y;
}