mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-07 00:13:59 -04:00
AP_OSD: added support for an MSP based OSD
This commit is contained in:
parent
234ed303fe
commit
b8b285b359
@ -25,6 +25,7 @@
|
||||
#ifdef WITH_SITL_OSD
|
||||
#include "AP_OSD_SITL.h"
|
||||
#endif
|
||||
#include "AP_OSD_MSP.h"
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_HAL/Util.h>
|
||||
#include <RC_Channel/RC_Channel.h>
|
||||
@ -218,9 +219,17 @@ void AP_OSD::init()
|
||||
break;
|
||||
}
|
||||
#endif
|
||||
case OSD_MSP: {
|
||||
backend = AP_OSD_MSP::probe(*this);
|
||||
if (backend == nullptr) {
|
||||
break;
|
||||
}
|
||||
if (backend != nullptr) {
|
||||
// create thread as higher priority than IO
|
||||
hal.console->printf("Started MSP OSD\n");
|
||||
break;
|
||||
}
|
||||
}
|
||||
if (backend != nullptr && (enum osd_types)osd_type.get() != OSD_MSP) {
|
||||
// create thread as higher priority than IO for all backends but MSP which has its own
|
||||
hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_OSD::osd_thread, void), "OSD", 1024, AP_HAL::Scheduler::PRIORITY_IO, 1);
|
||||
}
|
||||
}
|
||||
|
@ -26,6 +26,7 @@
|
||||
#endif
|
||||
|
||||
class AP_OSD_Backend;
|
||||
class AP_MSP;
|
||||
|
||||
#define AP_OSD_NUM_SCREENS 4
|
||||
|
||||
@ -68,6 +69,9 @@ public:
|
||||
AP_Int16 channel_max;
|
||||
|
||||
private:
|
||||
friend class AP_MSP;
|
||||
friend class AP_MSP_Telem_Backend;
|
||||
|
||||
AP_OSD_Backend *backend;
|
||||
AP_OSD *osd;
|
||||
|
||||
@ -124,6 +128,16 @@ private:
|
||||
AP_OSD_Setting bat2used{false, 0, 0};
|
||||
AP_OSD_Setting clk{false, 0, 0};
|
||||
|
||||
// MSP OSD only
|
||||
AP_OSD_Setting sidebars{false, 0, 0};
|
||||
AP_OSD_Setting crosshair{false, 0, 0};
|
||||
AP_OSD_Setting home_dist{true, 1, 1};
|
||||
AP_OSD_Setting home_dir{true, 1, 1};
|
||||
AP_OSD_Setting power{true, 1, 1};
|
||||
AP_OSD_Setting cell_volt{true, 1, 1};
|
||||
AP_OSD_Setting batt_bar{true, 1, 1};
|
||||
AP_OSD_Setting arming{true, 1, 1};
|
||||
|
||||
bool check_option(uint32_t option);
|
||||
|
||||
enum unit_type {
|
||||
@ -194,6 +208,8 @@ class AP_OSD
|
||||
{
|
||||
public:
|
||||
friend class AP_OSD_Screen;
|
||||
friend class AP_MSP;
|
||||
friend class AP_MSP_Telem_Backend;
|
||||
//constructor
|
||||
AP_OSD();
|
||||
|
||||
@ -217,6 +233,7 @@ public:
|
||||
OSD_NONE=0,
|
||||
OSD_MAX7456=1,
|
||||
OSD_SITL=2,
|
||||
OSD_MSP=3,
|
||||
};
|
||||
enum switch_method {
|
||||
TOGGLE=0,
|
||||
|
188
libraries/AP_OSD/AP_OSD_MSP.cpp
Normal file
188
libraries/AP_OSD/AP_OSD_MSP.cpp
Normal file
@ -0,0 +1,188 @@
|
||||
/*
|
||||
* 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/>.
|
||||
*
|
||||
*/
|
||||
/*
|
||||
OSD backend for MSP
|
||||
*/
|
||||
#include "AP_OSD_MSP.h"
|
||||
|
||||
|
||||
static const struct AP_Param::defaults_table_struct defaults_table[] = {
|
||||
/*
|
||||
//OSD_RSSI_VALUE
|
||||
{ "OSD_RSSI_EN", 1.0 },
|
||||
{ "OSD_RSSI_X", 1.0 },
|
||||
{ "OSD_RSSI_Y", 1.0 },
|
||||
|
||||
//OSD_MAIN_BATT_VOLTAGE
|
||||
{ "OSD_BAT_VOLT_EN", 1.0 },
|
||||
{ "OSD_BAT_VOLT_X", 1.0 },
|
||||
{ "OSD_BAT_VOLT_Y", 1.0 },
|
||||
|
||||
//OSD_CRAFT_NAME (text flightmode + status text messages + wind)
|
||||
{ "OSD_MESSAGE_EN", 1.0 },
|
||||
{ "OSD_MESSAGE_X", 1.0 },
|
||||
{ "OSD_MESSAGE_Y", 1.0 },
|
||||
|
||||
//OSD_FLYMODE (displays failsafe status and optionally rtl engaged)
|
||||
{ "OSD_FLTMODE_EN", 1.0 },
|
||||
{ "OSD_FLTMODE_X", 1.0 },
|
||||
{ "OSD_FLTMODE_Y", 1.0 },
|
||||
|
||||
//OSD_CURRENT_DRAW
|
||||
{ "OSD_CURRENT_EN", 1.0 },
|
||||
{ "OSD_CURRENT_X", 1.0 },
|
||||
{ "OSD_CURRENT_Y", 1.0 },
|
||||
|
||||
//OSD_MAH_DRAWN
|
||||
{ "OSD_BATUSED_EN", 1.0 },
|
||||
{ "OSD_BATUSED_X", 1.0 },
|
||||
{ "OSD_BATUSED_Y", 1.0 },
|
||||
|
||||
//OSD_GPS_SPEED
|
||||
{ "OSD_GSPEED_EN", 1.0 },
|
||||
{ "OSD_GSPEED_X", 1.0 },
|
||||
{ "OSD_GSPEED_Y", 1.0 },
|
||||
|
||||
//OSD_GPS_SATS
|
||||
{ "OSD_SATS_EN", 1.0 },
|
||||
{ "OSD_SATS_X", 1.0 },
|
||||
{ "OSD_SATS_Y", 1.0 },
|
||||
|
||||
//OSD_ALTITUDE
|
||||
{ "OSD_ALTITUDE_EN", 1.0 },
|
||||
{ "OSD_ALTITUDE_X", 1.0 },
|
||||
{ "OSD_ALTITUDE_Y", 1.0 },
|
||||
|
||||
//OSD_GPS_LON
|
||||
{ "OSD_GPSLONG_EN", 1.0 },
|
||||
{ "OSD_GPSLONG_X", 1.0 },
|
||||
{ "OSD_GPSLONG_Y", 1.0 },
|
||||
|
||||
//OSD_GPS_LAT
|
||||
{ "OSD_GPSLAT_EN", 1.0 },
|
||||
{ "OSD_GPSLAT_X", 1.0 },
|
||||
{ "OSD_GPSLAT_Y", 1.0 },
|
||||
|
||||
//OSD_PITCH_ANGLE
|
||||
{ "OSD_PITCH_EN", 1.0 },
|
||||
{ "OSD_PITCH_X", 1.0 },
|
||||
{ "OSD_PITCH_Y", 1.0 },
|
||||
|
||||
//OSD_ROLL_ANGLE
|
||||
{ "OSD_ROLL_EN", 1.0 },
|
||||
{ "OSD_ROLL_X", 1.0 },
|
||||
{ "OSD_ROLL_Y", 1.0 },
|
||||
|
||||
//OSD_MAIN_BATT_USAGE
|
||||
{ "OSD_BATTBAR_EN", 1.0 },
|
||||
{ "OSD_BATTBAR_X", 1.0 },
|
||||
{ "OSD_BATTBAR_Y", 1.0 },
|
||||
|
||||
//OSD_NUMERICAL_VARIO
|
||||
{ "OSD_VSPEED_EN", 1.0 },
|
||||
{ "OSD_VSPEED_X", 1.0 },
|
||||
{ "OSD_VSPEED_Y", 1.0 },
|
||||
|
||||
#ifdef HAVE_AP_BLHELI_SUPPORT
|
||||
//OSD_ESC_TMP
|
||||
{ "OSD_BLHTEMP_EN", 1.0 },
|
||||
{ "OSD_BLHTEMP_X", 1.0 },
|
||||
{ "OSD_BLHTEMP_Y", 1.0 },
|
||||
#endif
|
||||
|
||||
//OSD_RTC_DATETIME
|
||||
{ "OSD_CLK_EN", 1.0 },
|
||||
{ "OSD_CLK_X", 1.0 },
|
||||
{ "OSD_CLK_Y", 1.0 },
|
||||
|
||||
// --------------------------
|
||||
// MSP OSD only
|
||||
// --------------------------
|
||||
|
||||
// OSD items disabled by default (partially supported)
|
||||
//OSD_CROSSHAIRS
|
||||
{ "OSD_CRSSHAIR_EN", 0 },
|
||||
|
||||
//OSD_ARTIFICIAL_HORIZON
|
||||
{ "OSD_HORIZON_EN", 0 },
|
||||
|
||||
//OSD_HORIZON_SIDEBARS
|
||||
{ "OSD_SIDEBARS_EN", 0 },
|
||||
|
||||
//OSD_NUMERICAL_HEADING
|
||||
{ "OSD_HEADING_EN", 0.0 },
|
||||
|
||||
// Supported OSD items
|
||||
|
||||
//OSD_POWER
|
||||
{ "OSD_POWER_EN", 1.0 },
|
||||
{ "OSD_POWER_X", 1.0 },
|
||||
{ "OSD_POWER_Y", 1.0 },
|
||||
|
||||
//OSD_AVG_CELL_VOLTAGE
|
||||
{ "OSD_CELLVOLT_EN", 1.0 },
|
||||
{ "OSD_CELLVOLT_X", 1.0 },
|
||||
{ "OSD_CELLVOLT_Y", 1.0 },
|
||||
|
||||
//OSD_DISARMED
|
||||
{ "OSD_ARMING_EN", 1.0 },
|
||||
{ "OSD_ARMING_X", 1.0 },
|
||||
{ "OSD_ARMING_Y", 1.0 },
|
||||
|
||||
//OSD_HOME_DIR
|
||||
{ "OSD_HOMEDIR_EN", 1.0 },
|
||||
{ "OSD_HOMEDIR_X", 1.0 },
|
||||
{ "OSD_HOMEDIR_Y", 1.0 },
|
||||
|
||||
//OSD_HOME_DIST
|
||||
{ "OSD_HOMEDIST_EN", 1.0 },
|
||||
{ "OSD_HOMEDIST_X", 1.0 },
|
||||
{ "OSD_HOMEDIST_Y", 1.0 },
|
||||
*/
|
||||
};
|
||||
|
||||
|
||||
extern const AP_HAL::HAL &hal;
|
||||
|
||||
// initialise backend
|
||||
bool AP_OSD_MSP::init(void)
|
||||
{
|
||||
return true;
|
||||
}
|
||||
|
||||
// override built in positions with defaults for MSP OSD
|
||||
void AP_OSD_MSP::setup_defaults(void)
|
||||
{
|
||||
AP_Param::set_defaults_from_table(defaults_table, ARRAY_SIZE(defaults_table));
|
||||
}
|
||||
|
||||
AP_OSD_Backend *AP_OSD_MSP::probe(AP_OSD &osd)
|
||||
{
|
||||
AP_OSD_MSP *backend = new AP_OSD_MSP(osd);
|
||||
if (!backend) {
|
||||
return nullptr;
|
||||
}
|
||||
if (!backend->init()) {
|
||||
delete backend;
|
||||
return nullptr;
|
||||
}
|
||||
return backend;
|
||||
}
|
||||
|
||||
AP_OSD_MSP::AP_OSD_MSP(AP_OSD &osd):
|
||||
AP_OSD_Backend(osd)
|
||||
{
|
||||
}
|
27
libraries/AP_OSD/AP_OSD_MSP.h
Normal file
27
libraries/AP_OSD/AP_OSD_MSP.h
Normal file
@ -0,0 +1,27 @@
|
||||
#include <AP_OSD/AP_OSD_Backend.h>
|
||||
#include <AP_MSP/AP_MSP.h>
|
||||
|
||||
class AP_OSD_MSP : public AP_OSD_Backend
|
||||
{
|
||||
|
||||
public:
|
||||
static AP_OSD_Backend *probe(AP_OSD &osd);
|
||||
|
||||
//initilize display port and underlying hardware
|
||||
bool init() override;
|
||||
|
||||
//draw given text to framebuffer
|
||||
void write(uint8_t x, uint8_t y, const char* text) override {};
|
||||
|
||||
//flush framebuffer to screen
|
||||
void flush() override {};
|
||||
|
||||
//clear framebuffer
|
||||
void clear() override {};
|
||||
|
||||
private:
|
||||
//constructor
|
||||
AP_OSD_MSP(AP_OSD &osd);
|
||||
|
||||
void setup_defaults(void);
|
||||
};
|
@ -34,6 +34,7 @@
|
||||
#include <AP_GPS/AP_GPS.h>
|
||||
#include <AP_Baro/AP_Baro.h>
|
||||
#include <AP_RTC/AP_RTC.h>
|
||||
#include <AP_MSP/msp.h>
|
||||
|
||||
#include <ctype.h>
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
@ -705,6 +706,136 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = {
|
||||
// @Range: 0 15
|
||||
AP_SUBGROUPINFO(clk, "CLK", 43, AP_OSD_Screen, AP_OSD_Setting),
|
||||
|
||||
#if HAL_MSP_ENABLED
|
||||
// @Param: SIDEBARS_EN
|
||||
// @DisplayName: SIDEBARS_EN
|
||||
// @Description: Displays artificial horizon side bars (MSP OSD only)
|
||||
// @Values: 0:Disabled,1:Enabled
|
||||
|
||||
// @Param: SIDEBARS_X
|
||||
// @DisplayName: SIDEBARS_X
|
||||
// @Description: Horizontal position on screen (MSP OSD only)
|
||||
// @Range: 0 29
|
||||
|
||||
// @Param: SIDEBARS_Y
|
||||
// @DisplayName: SIDEBARS_Y
|
||||
// @Description: Vertical position on screen (MSP OSD only)
|
||||
// @Range: 0 15
|
||||
AP_SUBGROUPINFO(sidebars, "SIDEBARS", 44, AP_OSD_Screen, AP_OSD_Setting),
|
||||
|
||||
// @Param: CRSSHAIR_EN
|
||||
// @DisplayName: CRSSHAIR_EN
|
||||
// @Description: Displays artificial horizon crosshair (MSP OSD only)
|
||||
// @Values: 0:Disabled,1:Enabled
|
||||
|
||||
// @Param: CRSSHAIR_X
|
||||
// @DisplayName: CRSSHAIR_X
|
||||
// @Description: Horizontal position on screen (MSP OSD only)
|
||||
// @Range: 0 29
|
||||
|
||||
// @Param: CRSSHAIR_Y
|
||||
// @DisplayName: CRSSHAIR_Y
|
||||
// @Description: Vertical position on screen (MSP OSD only)
|
||||
// @Range: 0 15
|
||||
AP_SUBGROUPINFO(crosshair, "CRSSHAIR", 45, AP_OSD_Screen, AP_OSD_Setting),
|
||||
|
||||
// @Param: HOMEDIST_EN
|
||||
// @DisplayName: HOMEDIST_EN
|
||||
// @Description: Displays distance from HOME (MSP OSD only)
|
||||
// @Values: 0:Disabled,1:Enabled
|
||||
|
||||
// @Param: HOMEDIST_X
|
||||
// @DisplayName: HOMEDIST_X
|
||||
// @Description: Horizontal position on screen (MSP OSD only)
|
||||
// @Range: 0 29
|
||||
|
||||
// @Param: HOMEDIST_Y
|
||||
// @DisplayName: HOMEDIST_Y
|
||||
// @Description: Vertical position on screen (MSP OSD only)
|
||||
// @Range: 0 15
|
||||
AP_SUBGROUPINFO(home_dist, "HOMEDIST", 46, AP_OSD_Screen, AP_OSD_Setting),
|
||||
|
||||
// @Param: HOMEDIR_EN
|
||||
// @DisplayName: HOMEDIR_EN
|
||||
// @Description: Displays relative direction to HOME (MSP OSD only)
|
||||
// @Values: 0:Disabled,1:Enabled
|
||||
|
||||
// @Param: HOMEDIR_X
|
||||
// @DisplayName: HOMEDIR_X
|
||||
// @Description: Horizontal position on screen
|
||||
// @Range: 0 29
|
||||
|
||||
// @Param: HOMEDIR_Y
|
||||
// @DisplayName: HOMEDIR_Y
|
||||
// @Description: Vertical position on screen
|
||||
// @Range: 0 15
|
||||
AP_SUBGROUPINFO(home_dir, "HOMEDIR", 47, AP_OSD_Screen, AP_OSD_Setting),
|
||||
|
||||
// @Param: POWER_EN
|
||||
// @DisplayName: POWER_EN
|
||||
// @Description: Displays power (MSP OSD only)
|
||||
// @Values: 0:Disabled,1:Enabled
|
||||
|
||||
// @Param: POWER_X
|
||||
// @DisplayName: POWER_X
|
||||
// @Description: Horizontal position on screen
|
||||
// @Range: 0 29
|
||||
|
||||
// @Param: POWER_Y
|
||||
// @DisplayName: POWER_Y
|
||||
// @Description: Vertical position on screen
|
||||
// @Range: 0 15
|
||||
AP_SUBGROUPINFO(power, "POWER", 48, AP_OSD_Screen, AP_OSD_Setting),
|
||||
|
||||
// @Param: CELL_VOLT_EN
|
||||
// @DisplayName: CELL_VOLT_EN
|
||||
// @Description: Displays average cell voltage (MSP OSD only)
|
||||
// @Values: 0:Disabled,1:Enabled
|
||||
|
||||
// @Param: CELL_VOLT_X
|
||||
// @DisplayName: CELL_VOLT_X
|
||||
// @Description: Horizontal position on screen
|
||||
// @Range: 0 29
|
||||
|
||||
// @Param: CELL_VOLT_Y
|
||||
// @DisplayName: CELL_VOLT_Y
|
||||
// @Description: Vertical position on screen
|
||||
// @Range: 0 15
|
||||
AP_SUBGROUPINFO(cell_volt, "CELLVOLT", 49, AP_OSD_Screen, AP_OSD_Setting),
|
||||
|
||||
// @Param: BATT_BAR_EN
|
||||
// @DisplayName: BATT_BAR_EN
|
||||
// @Description: Displays battery usage bar (MSP OSD only)
|
||||
// @Values: 0:Disabled,1:Enabled
|
||||
|
||||
// @Param: BATT_BAR_X
|
||||
// @DisplayName: BATT_BAR_X
|
||||
// @Description: Horizontal position on screen
|
||||
// @Range: 0 29
|
||||
|
||||
// @Param: BATT_BAR_Y
|
||||
// @DisplayName: BATT_BAR_Y
|
||||
// @Description: Vertical position on screen
|
||||
// @Range: 0 15
|
||||
AP_SUBGROUPINFO(batt_bar, "BATTBAR", 50, AP_OSD_Screen, AP_OSD_Setting),
|
||||
|
||||
// @Param: ARMING_EN
|
||||
// @DisplayName: ARMING_EN
|
||||
// @Description: Displays arming status (MSP OSD only)
|
||||
// @Values: 0:Disabled,1:Enabled
|
||||
|
||||
// @Param: ARMING_X
|
||||
// @DisplayName: ARMING_X
|
||||
// @Description: Horizontal position on screen
|
||||
// @Range: 0 29
|
||||
|
||||
// @Param: ARMING_Y
|
||||
// @DisplayName: ARMING_Y
|
||||
// @Description: Vertical position on screen
|
||||
// @Range: 0 15
|
||||
AP_SUBGROUPINFO(arming, "ARMING", 51, AP_OSD_Screen, AP_OSD_Setting),
|
||||
#endif //HAL_MSP_ENABLED
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user