Copter: free allocations in case of allocation failure
[ardupilot.git] / libraries / AP_OSD / AP_OSD_MSP_DisplayPort.cpp
blobcec42388847a00f1a44dd82edc8c5c700d94aa86
1 /*
2 * This file is free software: you can redistribute it and/or modify it
3 * under the terms of the GNU General Public License as published by the
4 * Free Software Foundation, either version 3 of the License, or
5 * (at your option) any later version.
7 * This file is distributed in the hope that it will be useful, but
8 * WITHOUT ANY WARRANTY; without even the implied warranty of
9 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
10 * See the GNU General Public License for more details.
12 * You should have received a copy of the GNU General Public License along
13 * with this program. If not, see <http://www.gnu.org/licenses/>.
17 OSD backend for MSP
19 #include <AP_MSP/AP_MSP.h>
20 #include <AP_MSP/msp.h>
21 #include "AP_OSD_MSP_DisplayPort.h"
23 #if HAL_WITH_MSP_DISPLAYPORT
25 #include <GCS_MAVLink/GCS.h>
27 static const struct AP_Param::defaults_table_struct defaults_table[] = {
29 { "PARAM_NAME", value_float }
33 extern const AP_HAL::HAL &hal;
34 constexpr uint8_t AP_OSD_MSP_DisplayPort::symbols[AP_OSD_NUM_SYMBOLS];
36 // initialise backend
37 bool AP_OSD_MSP_DisplayPort::init(void)
39 // check if we have a DisplayPort backend to use
40 const AP_MSP *msp = AP::msp();
41 if (msp == nullptr) {
42 GCS_SEND_TEXT(MAV_SEVERITY_WARNING,"MSP backend not available");
43 return false;
45 _displayport = msp->find_protocol(AP_SerialManager::SerialProtocol_MSP_DisplayPort);
46 if (_displayport == nullptr) {
47 GCS_SEND_TEXT(MAV_SEVERITY_WARNING,"MSP DisplayPort uart not available");
48 return false;
50 // re-init port here for use in this thread
51 _displayport->init_uart();
52 return true;
55 // called by the OSD thread once
56 void AP_OSD_MSP_DisplayPort::osd_thread_run_once()
58 if (_displayport != nullptr) {
59 _displayport->init_uart();
63 void AP_OSD_MSP_DisplayPort::clear(void)
65 // check if we need to enable some options
66 // but only for actual OSD screens
67 if (_osd.get_current_screen() < AP_OSD_NUM_DISPLAY_SCREENS) {
68 const uint8_t txt_resolution = _osd.screen[_osd.get_current_screen()].get_txt_resolution();
69 const uint8_t font_index = _osd.screen[_osd.get_current_screen()].get_font_index();
70 _displayport->msp_displayport_set_options(font_index, txt_resolution);
73 // clear remote MSP screen
74 _displayport->msp_displayport_clear_screen();
76 // toggle flashing @1Hz
77 const uint32_t now = AP_HAL::millis();
78 if ((uint32_t(now * 0.004) & 0x01) != _blink_on) {
79 _blink_on = !_blink_on;
80 blink_phase = (blink_phase+1)%4;
84 void AP_OSD_MSP_DisplayPort::write(uint8_t x, uint8_t y, const char* text)
86 _displayport->msp_displayport_write_string(x, y, 0, text);
89 uint8_t AP_OSD_MSP_DisplayPort::format_string_for_osd(char* buff, uint8_t size, bool decimal_packed, const char *fmt, va_list ap)
91 const AP_MSP *msp = AP::msp();
92 const bool pack = decimal_packed && msp && !msp->is_option_enabled(AP_MSP::Option::DISPLAYPORT_BTFL_SYMBOLS);
93 return AP_OSD_Backend::format_string_for_osd(buff, size, pack, fmt, ap);
96 void AP_OSD_MSP_DisplayPort::flush(void)
98 // grab the screen and force a redraw
99 _displayport->msp_displayport_grab();
100 _displayport->msp_displayport_draw_screen();
102 // ok done processing displayport data
103 // let's process incoming MSP frames (and reply if needed)
104 _displayport->process_incoming_data();
107 void AP_OSD_MSP_DisplayPort::init_symbol_set(uint8_t *lookup_table, const uint8_t size)
109 const AP_MSP *msp = AP::msp();
110 // do we use backend specific symbols table?
111 if (msp && msp->is_option_enabled(AP_MSP::Option::DISPLAYPORT_BTFL_SYMBOLS)) {
112 memcpy(lookup_table, symbols, size);
113 } else {
114 memcpy(lookup_table, AP_OSD_Backend::symbols, size);
118 // override built in positions with defaults for MSP OSD
119 void AP_OSD_MSP_DisplayPort::setup_defaults(void)
121 AP_Param::set_defaults_from_table(defaults_table, ARRAY_SIZE(defaults_table));
124 AP_OSD_Backend *AP_OSD_MSP_DisplayPort::probe(AP_OSD &osd)
126 AP_OSD_MSP_DisplayPort *backend = NEW_NOTHROW AP_OSD_MSP_DisplayPort(osd);
127 if (!backend) {
128 return nullptr;
130 if (!backend->init()) {
131 delete backend;
132 return nullptr;
134 return backend;
137 // return a correction factor used to display angles correctly
138 float AP_OSD_MSP_DisplayPort::get_aspect_ratio_correction() const
140 return 12.0/18.0;
144 #endif