AP_OSD: separate parameter screen

display parameter names and types and allow modification via stick gestures
add support for updating selected parameters
support symbolic names for cetain options with add vehicle specific labels
add support for OSD parameter access and modification over mavlink
save OSD parameter when setting
add missing serial protocols
set defaults on settings correctly
re-organise defaults for NTSC screens and add 9th parameter
allow parameter control to be disabled
add plane aux options (from vierfuffzig)
only enable osd param on bitmap enabled backends
make sure draw() is elided on non-bitmap backends
This commit is contained in:
Andy Piper 2020-04-18 21:16:02 +01:00 committed by Peter Barker
parent 13676f9784
commit c483c04d4b
5 changed files with 1425 additions and 48 deletions

View File

@ -162,6 +162,22 @@ const AP_Param::GroupInfo AP_OSD::var_info[] = {
// @User: Standard
AP_GROUPINFO("_FS_SCR", 19, AP_OSD, failsafe_scr, 0),
#if OSD_PARAM_ENABLED
// @Param: _BTN_DELAY
// @DisplayName: Button delay
// @Description: Debounce time in ms for stick commanded parameter navigation.
// @Range: 0 3000
// @User: Advanced
AP_GROUPINFO("_BTN_DELAY", 20, AP_OSD, button_delay_ms, 300),
// @Group: 5_
// @Path: AP_OSD_ParamScreen.cpp
AP_SUBGROUPINFO(param_screen[0], "5_", 21, AP_OSD, AP_OSD_ParamScreen),
// @Group: 6_
// @Path: AP_OSD_ParamScreen.cpp
AP_SUBGROUPINFO(param_screen[1], "6_", 22, AP_OSD, AP_OSD_ParamScreen),
#endif
AP_GROUPEND
};
@ -252,14 +268,13 @@ void AP_OSD::update_osd()
stats();
update_current_screen();
screen[current_screen].set_backend(backend);
get_screen(current_screen).set_backend(backend);
// skip the drawing if we are not using a font based backend. This saves a lot of flash space when
// using the MSP OSD system on boards that don't have a MAX7456
#if defined(WITH_SITL_OSD) || defined(HAL_WITH_SPI_OSD)
screen[current_screen].draw();
#if HAL_WITH_OSD_BITMAP
get_screen(current_screen).draw();
#endif
}
backend->flush();
@ -317,12 +332,12 @@ 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 (!was_armed && arm_scr > 0 && arm_scr <= AP_OSD_NUM_DISPLAY_SCREENS && get_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_DISPLAY_SCREENS && get_screen(disarm_scr-1).enabled) {
current_screen = disarm_scr-1;
}
was_armed = false;
@ -330,13 +345,13 @@ void AP_OSD::update_current_screen()
// 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_DISPLAY_SCREENS && get_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 (get_screen(pre_fs_screen).enabled) {
current_screen = pre_fs_screen;
}
was_failsafe = false;
@ -373,7 +388,7 @@ void AP_OSD::update_current_screen()
//select screen based on pwm ranges specified
case PWM_RANGE:
for (int i=0; i<AP_OSD_NUM_SCREENS; i++) {
if (screen[i].enabled && screen[i].channel_min <= channel_value && screen[i].channel_max > channel_value && previous_pwm_screen != i) {
if (get_screen(i).enabled && get_screen(i).channel_min <= channel_value && get_screen(i).channel_max > channel_value && previous_pwm_screen != i) {
current_screen = previous_pwm_screen = i;
break;
}
@ -406,7 +421,7 @@ void AP_OSD::next_screen()
uint8_t t = current_screen;
do {
t = (t + 1)%AP_OSD_NUM_SCREENS;
} while (t != current_screen && !screen[t].enabled);
} while (t != current_screen && !get_screen(t).enabled);
current_screen = t;
}
@ -417,6 +432,52 @@ void AP_OSD::set_nav_info(NavInfo &navinfo)
nav_info = navinfo;
}
// handle OSD parameter configuration
void AP_OSD::handle_msg(const mavlink_message_t &msg, const GCS_MAVLINK& link)
{
bool found = false;
switch (msg.msgid) {
case MAVLINK_MSG_ID_OSD_PARAM_CONFIG: {
mavlink_osd_param_config_t packet;
mavlink_msg_osd_param_config_decode(&msg, &packet);
#if OSD_PARAM_ENABLED
for (uint8_t i = 0; i < AP_OSD_NUM_PARAM_SCREENS; i++) {
if (packet.osd_screen == i + AP_OSD_NUM_DISPLAY_SCREENS + 1) {
param_screen[i].handle_write_msg(packet, link);
found = true;
}
}
#endif
// send back an error
if (!found) {
mavlink_msg_osd_param_config_reply_send(link.get_chan(), packet.request_id, OSD_PARAM_INVALID_SCREEN);
}
}
break;
case MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG: {
mavlink_osd_param_show_config_t packet;
mavlink_msg_osd_param_show_config_decode(&msg, &packet);
#if OSD_PARAM_ENABLED
for (uint8_t i = 0; i < AP_OSD_NUM_PARAM_SCREENS; i++) {
if (packet.osd_screen == i + AP_OSD_NUM_DISPLAY_SCREENS + 1) {
param_screen[i].handle_read_msg(packet, link);
found = true;
}
}
#endif
// send back an error
if (!found) {
mavlink_msg_osd_param_show_config_reply_send(link.get_chan(), packet.request_id, OSD_PARAM_INVALID_SCREEN,
nullptr, OSD_PARAM_NONE, 0, 0, 0);
}
}
break;
default:
break;
}
}
AP_OSD *AP::osd() {
return AP_OSD::get_singleton();
}

View File

@ -20,15 +20,35 @@
#include <AP_Param/AP_Param.h>
#include <AP_Math/AP_Math.h>
#include <AP_BLHeli/AP_BLHeli.h>
#include <RC_Channel/RC_Channel.h>
#include <AP_Param/AP_Param.h>
#include <GCS_MAVLink/GCS.h>
#ifndef OSD_ENABLED
#define OSD_ENABLED 0
#endif
#ifndef HAL_WITH_OSD_BITMAP
#define HAL_WITH_OSD_BITMAP defined(HAL_WITH_SPI_OSD) || defined(WITH_SITL_OSD)
#endif
#ifndef OSD_PARAM_ENABLED
#define OSD_PARAM_ENABLED HAL_WITH_OSD_BITMAP && !HAL_MINIMIZE_FEATURES
#endif
class AP_OSD_Backend;
class AP_MSP;
#define AP_OSD_NUM_SCREENS 4
#define AP_OSD_NUM_DISPLAY_SCREENS 4
#if OSD_PARAM_ENABLED
#define AP_OSD_NUM_PARAM_SCREENS 2
#else
#define AP_OSD_NUM_PARAM_SCREENS 0
#endif
#define AP_OSD_NUM_SCREENS (AP_OSD_NUM_DISPLAY_SCREENS + AP_OSD_NUM_PARAM_SCREENS)
#define PARAM_INDEX(key, idx, group) (uint32_t(uint32_t(key) << 23 | uint32_t(idx) << 18 | uint32_t(group)))
#define PARAM_TOKEN_INDEX(token) PARAM_INDEX(AP_Param::get_persistent_key(token.key), token.idx, token.group_element)
/*
class to hold one setting
@ -48,32 +68,61 @@ public:
class AP_OSD;
/*
class to hold one screen of settings
*/
class AP_OSD_Screen
class AP_OSD_AbstractScreen
{
public:
// constructor
AP_OSD_Screen();
void draw(void);
AP_OSD_AbstractScreen() {}
#if OSD_PARAM_ENABLED
virtual void draw(void) = 0;
#endif
void set_backend(AP_OSD_Backend *_backend);
// User settable parameters
static const struct AP_Param::GroupInfo var_info[];
AP_Int8 enabled;
AP_Int16 channel_min;
AP_Int16 channel_max;
private:
friend class AP_MSP;
friend class AP_MSP_Telem_Backend;
protected:
bool check_option(uint32_t option);
enum unit_type {
ALTITUDE=0,
SPEED=1,
VSPEED=2,
DISTANCE=3,
DISTANCE_LONG=4,
TEMPERATURE=5,
UNIT_TYPE_LAST=6,
};
char u_icon(enum unit_type unit);
float u_scale(enum unit_type unit, float value);
AP_OSD_Backend *backend;
AP_OSD *osd;
};
/*
class to hold one screen of settings
*/
class AP_OSD_Screen : public AP_OSD_AbstractScreen
{
public:
// constructor
AP_OSD_Screen();
#if OSD_PARAM_ENABLED
void draw(void) override;
#else
void draw(void);
#endif
// User settable parameters
static const struct AP_Param::GroupInfo var_info[];
private:
friend class AP_MSP;
friend class AP_MSP_Telem_Backend;
static const uint8_t message_visible_width = 26;
static const uint8_t message_scroll_time_ms = 200;
@ -138,21 +187,6 @@ private:
AP_OSD_Setting batt_bar{true, 1, 1};
AP_OSD_Setting arming{true, 1, 1};
bool check_option(uint32_t option);
enum unit_type {
ALTITUDE=0,
SPEED=1,
VSPEED=2,
DISTANCE=3,
DISTANCE_LONG=4,
TEMPERATURE=5,
UNIT_TYPE_LAST=6,
};
char u_icon(enum unit_type unit);
float u_scale(enum unit_type unit, float value);
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);
@ -204,12 +238,142 @@ private:
void draw_clk(uint8_t x, uint8_t y);
};
#if OSD_PARAM_ENABLED
/*
class to hold one setting
*/
class AP_OSD_ParamSetting : public AP_OSD_Setting
{
public:
// configured index.
AP_Int32 _param_group;
AP_Int16 _param_key;
AP_Int8 _param_idx;
// metadata
AP_Float _param_min;
AP_Float _param_max;
AP_Float _param_incr;
AP_Int8 _type;
// parameter number
uint8_t _param_number;
AP_Param* _param;
ap_var_type _param_type;
AP_Param::ParamToken _current_token;
// structure to contain setting constraints for important settings
struct ParamMetadata {
float min_value;
float max_value;
float increment;
uint8_t values_max;
const char** values;
};
static const ParamMetadata _param_metadata[];
AP_OSD_ParamSetting(uint8_t param_number, bool enabled, uint8_t x, uint8_t y, int16_t key, int8_t idx, int32_t group,
int8_t type = OSD_PARAM_NONE, float min = 0.0f, float max = 1.0f, float incr = 0.001f);
// initialize the setting from the configured information
void update();
// set the ranges from static metadata
bool set_from_metadata();
bool set_by_name(const char* name, uint8_t config_type, float pmin=0, float pmax=0, float pincr=0);
void guess_ranges(bool force = false);
void save_as_new();
const ParamMetadata* get_custom_metadata() const {
return (_type > 0 ? &_param_metadata[_type - 1] : nullptr);
}
// User settable parameters
static const struct AP_Param::GroupInfo var_info[];
private:
};
/*
class to hold one screen of settings
*/
class AP_OSD_ParamScreen : public AP_OSD_AbstractScreen
{
public:
AP_OSD_ParamScreen();
enum class Event {
NONE,
MENU_ENTER,
MENU_UP,
MENU_DOWN,
MENU_EXIT
};
enum class MenuState {
PARAM_SELECT,
PARAM_VALUE_MODIFY,
PARAM_PARAM_MODIFY
};
static const uint8_t NUM_PARAMS = 9;
static const uint8_t SAVE_PARAM = NUM_PARAMS + 1;
void draw(void) override;
void handle_write_msg(const mavlink_osd_param_config_t& packet, const GCS_MAVLINK& link);
void handle_read_msg(const mavlink_osd_param_show_config_t& packet, const GCS_MAVLINK& link);
// Save button co-ordinates
AP_Int8 save_x;
AP_Int8 save_y;
// User settable parameters
static const struct AP_Param::GroupInfo var_info[];
private:
AP_OSD_ParamSetting params[NUM_PARAMS] = {
{1, true, 2, 2, 102, 0, 4034 }, // ATC_RAT_PIT_P
{2, true, 2, 3, 102, 0, 130 }, // ATC_RAT_PIT_D
{3, true, 2, 4, 102, 0, 4033 }, // ATC_RAT_RLL_P
{4, true, 2, 5, 102, 0, 129 }, // ATC_RAT_RLL_D
{5, true, 2, 6, 102, 0, 4035 }, // ATC_RAT_YAW_P
{6, true, 2, 7, 102, 0, 131 }, // ATC_RAT_YAW_D
{7, true, 2, 8, 6, 0, 25041, OSD_PARAM_AUX_FUNCTION }, // RC7_OPTION
{8, true, 2, 9, 6, 0, 25105, OSD_PARAM_AUX_FUNCTION }, // RC8_OPTION
{9, true, 2, 10, 36, 0, 1047, OSD_PARAM_FAILSAFE_ACTION_2 } // BATT_FS_LOW_ACT
};
void update_state_machine();
void draw_parameter(uint8_t param_number, uint8_t x, uint8_t y);
void modify_parameter(uint8_t number, Event ev);
void modify_configured_parameter(uint8_t number, Event ev);
void save_parameters();
Event map_rc_input_to_event() const;
RC_Channel::AuxSwitchPos get_channel_pos(uint8_t rcmapchan) const;
uint8_t _selected_param = 1;
uint16_t _requires_save;
MenuState _menu_state = MenuState::PARAM_SELECT;
Event _last_rc_event = Event::NONE;
// start time of the current button press
uint32_t _transition_start_ms;
// timeout of the current button press
uint32_t _transition_timeout_ms;
// number of consecutive times the current transition has happened
uint32_t _transition_count;
};
#endif
class AP_OSD
{
public:
friend class AP_OSD_Screen;
friend class AP_MSP;
friend class AP_MSP_Telem_Backend;
friend class AP_OSD_ParamScreen;
//constructor
AP_OSD();
@ -257,6 +421,7 @@ public:
AP_Int8 arm_scr;
AP_Int8 disarm_scr;
AP_Int8 failsafe_scr;
AP_Int32 button_delay_ms;
enum {
OPTION_DECIMAL_PACK = 1U<<0,
@ -276,8 +441,10 @@ public:
AP_Int8 units;
AP_OSD_Screen screen[AP_OSD_NUM_SCREENS];
AP_OSD_Screen screen[AP_OSD_NUM_DISPLAY_SCREENS];
#if OSD_PARAM_ENABLED
AP_OSD_ParamScreen param_screen[AP_OSD_NUM_PARAM_SCREENS];
#endif
struct NavInfo {
float wp_distance;
int32_t wp_bearing;
@ -295,6 +462,21 @@ public:
_disable = false;
}
AP_OSD_AbstractScreen& get_screen(uint8_t idx) {
#if OSD_PARAM_ENABLED
if (idx >= AP_OSD_NUM_DISPLAY_SCREENS) {
return param_screen[idx - AP_OSD_NUM_DISPLAY_SCREENS];
}
#endif
return screen[idx];
}
// Check whether arming is allowed
bool pre_arm_check(char *failure_msg, const uint8_t failure_msg_len) const;
bool is_readonly_screen() const { return current_screen < AP_OSD_NUM_DISPLAY_SCREENS; }
// handle OSD parameter configuration
void handle_msg(const mavlink_message_t &msg, const GCS_MAVLINK& link);
private:
void osd_thread();
void update_osd();

View File

@ -0,0 +1,706 @@
/*
* 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 <limits.h>
#include <ctype.h>
#include <GCS_MAVLink/GCS.h>
#include <AP_RCMapper/AP_RCMapper.h>
#include <AP_Arming/AP_Arming.h>
extern const AP_HAL::HAL& hal;
#if OSD_PARAM_ENABLED
const AP_Param::GroupInfo AP_OSD_ParamScreen::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_ParamScreen, enabled, 0, AP_PARAM_FLAG_ENABLE),
// @Param: CHAN_MIN
// @DisplayName: Transmitter switch screen minimum pwm
// @Description: This sets the PWM lower limit for this screen
// @Range: 900 2100
// @User: Standard
AP_GROUPINFO("CHAN_MIN", 2, AP_OSD_ParamScreen, channel_min, 900),
// @Param: CHAN_MAX
// @DisplayName: Transmitter switch screen maximum pwm
// @Description: This sets the PWM upper limit for this screen
// @Range: 900 2100
// @User: Standard
AP_GROUPINFO("CHAN_MAX", 3, AP_OSD_ParamScreen, channel_max, 2100),
// @Param: PARAM1_EN
// @DisplayName: PARAM1_EN
// @Description: Enables display of parameter 1
// @Values: 0:Disabled,1:Enabled
// @Param: PARAM1_X
// @DisplayName: PARAM1_X
// @Description: Horizontal position on screen
// @Range: 0 29
// @Param: PARAM1_Y
// @DisplayName: PARAM1_Y
// @Description: Vertical position on screen
// @Range: 0 15
AP_SUBGROUPINFO(params[0], "PARAM1", 4, AP_OSD_ParamScreen, AP_OSD_ParamSetting),
// @Param: PARAM2_EN
// @DisplayName: PARAM21_EN
// @Description: Enables display of parameter 2
// @Values: 0:Disabled,1:Enabled
// @Param: PARAM2_X
// @DisplayName: PARAM2_X
// @Description: Horizontal position on screen
// @Range: 0 29
// @Param: PARAM2_Y
// @DisplayName: PARAM2_Y
// @Description: Vertical position on screen
// @Range: 0 15
AP_SUBGROUPINFO(params[1], "PARAM2", 5, AP_OSD_ParamScreen, AP_OSD_ParamSetting),
// @Param: PARAM3_EN
// @DisplayName: PARAM3_EN
// @Description: Enables display of parameter 3
// @Values: 0:Disabled,1:Enabled
// @Param: PARAM3_X
// @DisplayName: PARAM3_X
// @Description: Horizontal position on screen
// @Range: 0 29
// @Param: PARAM3_Y
// @DisplayName: PARAM3_Y
// @Description: Vertical position on screen
// @Range: 0 15
AP_SUBGROUPINFO(params[2], "PARAM3", 6, AP_OSD_ParamScreen, AP_OSD_ParamSetting),
// @Param: PARAM4_EN
// @DisplayName: PARAM4_EN
// @Description: Enables display of parameter 4
// @Values: 0:Disabled,1:Enabled
// @Param: PARAM4_X
// @DisplayName: PARAM4_X
// @Description: Horizontal position on screen
// @Range: 0 29
// @Param: PARAM4_Y
// @DisplayName: PARAM4_Y
// @Description: Vertical position on screen
// @Range: 0 15
AP_SUBGROUPINFO(params[3], "PARAM4", 7, AP_OSD_ParamScreen, AP_OSD_ParamSetting),
// @Param: PARAM5_EN
// @DisplayName: PARAM5_EN
// @Description: Enables display of parameter 5
// @Values: 0:Disabled,1:Enabled
// @Param: PARAM5_X
// @DisplayName: PARAM5_X
// @Description: Horizontal position on screen
// @Range: 0 29
// @Param: PARAM5_Y
// @DisplayName: PARAM5_Y
// @Description: Vertical position on screen
// @Range: 0 15
AP_SUBGROUPINFO(params[4], "PARAM5", 8, AP_OSD_ParamScreen, AP_OSD_ParamSetting),
// @Param: PARAM6_EN
// @DisplayName: PARAM6_EN
// @Description: Enables display of parameter 6
// @Values: 0:Disabled,1:Enabled
// @Param: PARAM6_X
// @DisplayName: PARAM6_X
// @Description: Horizontal position on screen
// @Range: 0 29
// @Param: PARAM6_Y
// @DisplayName: PARAM6_Y
// @Description: Vertical position on screen
// @Range: 0 15
AP_SUBGROUPINFO(params[5], "PARAM6", 9, AP_OSD_ParamScreen, AP_OSD_ParamSetting),
// @Param: PARAM7_EN
// @DisplayName: PARAM7_EN
// @Description: Enables display of parameter 7
// @Values: 0:Disabled,1:Enabled
// @Param: PARAM7_X
// @DisplayName: PARAM7_X
// @Description: Horizontal position on screen
// @Range: 0 29
// @Param: PARAM7_Y
// @DisplayName: PARAM7_Y
// @Description: Vertical position on screen
// @Range: 0 15
AP_SUBGROUPINFO(params[6], "PARAM7", 10, AP_OSD_ParamScreen, AP_OSD_ParamSetting),
// @Param: PARAM8_EN
// @DisplayName: PARAM8_EN
// @Description: Enables display of parameter 8
// @Values: 0:Disabled,1:Enabled
// @Param: PARAM8_X
// @DisplayName: PARAM8_X
// @Description: Horizontal position on screen
// @Range: 0 29
// @Param: PARAM8_Y
// @DisplayName: PARAM8_Y
// @Description: Vertical position on screen
// @Range: 0 15
AP_SUBGROUPINFO(params[7], "PARAM8", 11, AP_OSD_ParamScreen, AP_OSD_ParamSetting),
// @Param: PARAM9_EN
// @DisplayName: PARAM9_EN
// @Description: Enables display of parameter 8
// @Values: 0:Disabled,1:Enabled
// @Param: PARAM9_X
// @DisplayName: PARAM9_X
// @Description: Horizontal position on screen
// @Range: 0 29
// @Param: PARAM9_Y
// @DisplayName: PARAM9_Y
// @Description: Vertical position on screen
// @Range: 0 15
AP_SUBGROUPINFO(params[8], "PARAM9", 12, AP_OSD_ParamScreen, AP_OSD_ParamSetting),
// @Param: SAVE_X
// @DisplayName: SAVE_X
// @Description: Horizontal position of Save button on screen
// @Range: 0 25
// @User: Advanced
AP_GROUPINFO("SAVE_X", 13, AP_OSD_ParamScreen, save_x, 23),
// @Param: SAVE_Y
// @DisplayName: SAVE_Y
// @Description: Vertical position of Save button on screen
// @Range: 0 15
// @User: Advanced
AP_GROUPINFO("SAVE_Y", 14, AP_OSD_ParamScreen, save_y, 11),
AP_GROUPEND
};
#define OSD_HOLD_BUTTON_PRESS_DELAY 100
#define OSD_HOLD_BUTTON_PRESS_COUNT 18
#define OSD_PARAM_DEBUG 0
#if OSD_PARAM_DEBUG
static const char* event_names[5] = {
"NONE", "MENU_ENTER", "MENU_UP", "MENU_DOWN", "IN_MENU_EXIT"
};
#define debug(fmt, args ...) do { hal.console->printf("OSD: " fmt, args); } while (0)
#else
#define debug(fmt, args ...)
#endif
AP_OSD_ParamScreen::AP_OSD_ParamScreen() {
AP_Param::setup_object_defaults(this, var_info);
}
void AP_OSD_ParamScreen::draw_parameter(uint8_t number, uint8_t x, uint8_t y)
{
bool param_blink = false;
bool value_blink = false;
const bool selected = number == _selected_param;
switch(_menu_state) {
case MenuState::PARAM_SELECT:
param_blink = selected;
break;
case MenuState::PARAM_VALUE_MODIFY:
value_blink = selected;
break;
case MenuState::PARAM_PARAM_MODIFY:
param_blink = value_blink = selected;
break;
}
if (number >= NUM_PARAMS + 1) {
backend->write(x, y, param_blink, "%s", _requires_save ? " SAVE" : "REBOOT");
return;
}
AP_OSD_ParamSetting& setting = params[number-1];
setting.update();
ap_var_type type = setting._param_type;
AP_Param* p = setting._param;
if (p != nullptr) {
// grab the name of the parameter
char name[17];
p->copy_name_token(setting._current_token, name, 16);
name[16] = 0;
const AP_OSD_ParamSetting::ParamMetadata* metadata = setting.get_custom_metadata();
uint16_t value_pos = 19;
backend->write(x, y, param_blink, "%s:", name);
switch (type) {
case AP_PARAM_INT8: {
int8_t val = ((AP_Int8*)p)->get();
if (metadata != nullptr && val >= 0 && val < metadata->values_max) {
backend->write(value_pos, y, value_blink, "%s", metadata->values[val]);
} else {
backend->write(value_pos, y, value_blink, "%hhd", val);
}
break;
}
case AP_PARAM_INT16: {
int16_t val = ((AP_Int16*)p)->get();
if (metadata != nullptr && val >= 0 && val < metadata->values_max) {
backend->write(value_pos, y, value_blink, "%s", metadata->values[val]);
} else {
backend->write(value_pos, y, value_blink, "%hd", val);
}
break;
}
case AP_PARAM_INT32: {
int32_t val = ((AP_Int16*)p)->get();
if (metadata != nullptr && val >= 0 && val < metadata->values_max) {
backend->write(value_pos, y, value_blink, "%s", metadata->values[val]);
} else {
backend->write(value_pos, y, value_blink, "%d", val);
}
break;
}
case AP_PARAM_FLOAT: {
const float val = ((AP_Float*)p)->get();
// cope with really small value
if (val < 0.01 && !is_zero(val)) {
backend->write(value_pos, y, value_blink, "%.4f", val);
} else if (val < 0.001 && !is_zero(val)) {
backend->write(value_pos, y, value_blink, "%.5f", val);
} else {
backend->write(value_pos, y, value_blink, "%.3f", val);
}
break;
}
case AP_PARAM_VECTOR3F:
case AP_PARAM_NONE:
case AP_PARAM_GROUP:
break;
}
}
}
// modify the selected parameter number
void AP_OSD_ParamScreen::modify_parameter(uint8_t number, Event ev)
{
if (number > NUM_PARAMS) {
return;
}
const AP_OSD_ParamSetting& setting = params[number-1];
AP_Param* p = setting._param;
if (p->is_read_only()) {
return;
}
_requires_save |= 1 << (number-1);
float incr = setting._param_incr * ((ev == Event::MENU_DOWN) ? -1.0f : 1.0f);
int32_t incr_int = int32_t(roundf(incr));
int32_t max_int = int32_t(roundf(setting._param_max));
int32_t min_int = int32_t(roundf(setting._param_min));
if (p != nullptr) {
switch (setting._param_type) {
// there is no way to validate the ranges, so as a rough guess prevent
// integer types going below -1;
case AP_PARAM_INT8: {
AP_Int8* param = (AP_Int8*)p;
param->set(constrain_int16(param->get() + incr_int, min_int, max_int));
break;
}
case AP_PARAM_INT16: {
AP_Int16* param = (AP_Int16*)p;
param->set(constrain_int16(param->get() + incr_int, min_int, max_int));
break;
}
case AP_PARAM_INT32: {
AP_Int32* param = (AP_Int32*)p;
param->set(constrain_int32(param->get() + incr_int, min_int, max_int));
break;
}
case AP_PARAM_FLOAT: {
AP_Float* param = (AP_Float*)p;
param->set(constrain_float(param->get() + incr, setting._param_min, setting._param_max));
break;
}
case AP_PARAM_VECTOR3F:
case AP_PARAM_NONE:
case AP_PARAM_GROUP:
break;
}
}
}
// modify which parameter is configued for the given selection
void AP_OSD_ParamScreen::modify_configured_parameter(uint8_t number, Event ev)
{
if (number > NUM_PARAMS) {
return;
}
_requires_save |= 1 << (number-1);
AP_OSD_ParamSetting& setting = params[number-1];
AP_Param* param;
if (ev == Event::MENU_DOWN) {
param = AP_Param::next_scalar(&setting._current_token, &setting._param_type);
} else {
// going backwards is somewhat convoluted as the param code is geared for going forward
ap_var_type type = AP_PARAM_NONE, prev_type = AP_PARAM_NONE, prev_prev_type = AP_PARAM_NONE;
AP_Param::ParamToken token, prev_token, prev_prev_token;
for (param = AP_Param::first(&token, &type);
param && (setting._current_token.key != token.key
|| setting._current_token.idx != token.idx
|| setting._current_token.group_element != token.group_element);
param = AP_Param::next_scalar(&token, &type)) {
prev_prev_token = prev_token;
prev_prev_type = prev_type;
prev_token = token;
prev_type = type;
}
if (param != nullptr) {
param = AP_Param::next_scalar(&prev_prev_token, &prev_prev_type);
setting._current_token = prev_prev_token;
setting._param_type = prev_prev_type;
}
}
if (param != nullptr) {
// update the stored index
setting._param_group = setting._current_token.group_element;
setting._param_key = AP_Param::get_persistent_key(setting._current_token.key);
setting._param_idx = setting._current_token.idx;
setting._param = param;
setting._type = OSD_PARAM_NONE;
// force update() to refresh the token
setting._current_token.key = 0;
setting._current_token.idx = 0;
setting._current_token.group_element = 0;
}
}
// save all of the parameters
void AP_OSD_ParamScreen::save_parameters()
{
if (!_requires_save) {
return;
}
for (uint8_t i = 0; i < NUM_PARAMS; i++) {
if (params[i].enabled && (_requires_save & (1 << i))) {
AP_Param* p = params[i]._param;
if (p != nullptr) {
p->save();
}
params[i].save_as_new();
}
}
_requires_save = 0;
}
// return radio values as LOW, MIDDLE, HIGH
// this function uses different threshold values to RC_Chanel::get_channel_pos()
// to avoid glitching on the stick travel
RC_Channel::AuxSwitchPos AP_OSD_ParamScreen::get_channel_pos(uint8_t rcmapchan) const
{
const RC_Channel* chan = rc().channel(rcmapchan-1);
if (chan == nullptr) {
return RC_Channel::AuxSwitchPos::LOW;
}
const uint16_t in = chan->get_radio_in();
if (in <= 900 || in >= 2200) {
return RC_Channel::AuxSwitchPos::LOW;
}
// switch is reversed if 'reversed' option set on channel and switches reverse is allowed by RC_OPTIONS
bool switch_reversed = chan->get_reverse() && rc().switch_reverse_allowed();
if (in < 1300) {
return switch_reversed ? RC_Channel::AuxSwitchPos::HIGH : RC_Channel::AuxSwitchPos::LOW;
} else if (in > 1700) {
return switch_reversed ? RC_Channel::AuxSwitchPos::LOW : RC_Channel::AuxSwitchPos::HIGH;
} else {
return RC_Channel::AuxSwitchPos::MIDDLE;
}
}
// map rc input to an event
AP_OSD_ParamScreen::Event AP_OSD_ParamScreen::map_rc_input_to_event() const
{
const RC_Channel::AuxSwitchPos throttle = get_channel_pos(AP::rcmap()->throttle());
const RC_Channel::AuxSwitchPos yaw = get_channel_pos(AP::rcmap()->yaw());
const RC_Channel::AuxSwitchPos roll = get_channel_pos(AP::rcmap()->roll());
const RC_Channel::AuxSwitchPos pitch = get_channel_pos(AP::rcmap()->pitch());
Event result = Event::NONE;
if (yaw != RC_Channel::AuxSwitchPos::MIDDLE || throttle != RC_Channel::AuxSwitchPos::LOW) {
return result;
}
if (pitch == RC_Channel::AuxSwitchPos::MIDDLE && roll == RC_Channel::AuxSwitchPos::LOW) {
result = Event::MENU_EXIT;
} else if (pitch == RC_Channel::AuxSwitchPos::MIDDLE && roll == RC_Channel::AuxSwitchPos::HIGH) {
result = Event::MENU_ENTER;
} else if (pitch == RC_Channel::AuxSwitchPos::LOW && roll == RC_Channel::AuxSwitchPos::MIDDLE) {
result = Event::MENU_UP;
} else if (pitch == RC_Channel::AuxSwitchPos::HIGH && roll == RC_Channel::AuxSwitchPos::MIDDLE) {
result = Event::MENU_DOWN;
} else {
// OSD option has not changed so assume stick re-centering
result = Event::NONE;
}
return result;
}
// update the state machine when disarmed
void AP_OSD_ParamScreen::update_state_machine()
{
const uint32_t now = AP_HAL::millis();
if ((now - _transition_start_ms) < _transition_timeout_ms) {
return;
}
const Event ev = map_rc_input_to_event();
// only take action on transitions
if (ev == Event::NONE && ev == _last_rc_event) {
return;
}
debug("update_state_machine(%s)\n", event_names[int(ev)]);
_transition_start_ms = now;
if (ev == _last_rc_event) {
_transition_timeout_ms = OSD_HOLD_BUTTON_PRESS_DELAY;
_transition_count++;
} else {
_transition_timeout_ms = osd->button_delay_ms;
_transition_count = 0;
}
_last_rc_event = ev;
// if we were armed then there is no selected parameter - so find one
if (_selected_param == 0) {
_selected_param = 1;
for (uint8_t i = 0; i < NUM_PARAMS && !params[_selected_param-1].enabled; i++) {
_selected_param++;
}
}
switch (ev) {
case Event::MENU_ENTER:
switch(_menu_state) {
case MenuState::PARAM_SELECT:
if (_selected_param == SAVE_PARAM) {
if (_transition_count >= OSD_HOLD_BUTTON_PRESS_COUNT) {
save_parameters();
hal.scheduler->reboot(false);
} else {
save_parameters();
}
} else {
_menu_state = MenuState::PARAM_VALUE_MODIFY;
}
break;
case MenuState::PARAM_VALUE_MODIFY:
if (_transition_count >= OSD_HOLD_BUTTON_PRESS_COUNT) {
_menu_state = MenuState::PARAM_PARAM_MODIFY;
}
break;
case MenuState::PARAM_PARAM_MODIFY:
break;
}
break;
case Event::MENU_UP:
switch (_menu_state) {
case MenuState::PARAM_SELECT:
_selected_param--;
if (_selected_param < 1) {
_selected_param = SAVE_PARAM;
}
// skip over parameters that are not enabled
for (uint8_t i = 0; i < NUM_PARAMS + 1 && (_selected_param != SAVE_PARAM && !params[_selected_param-1].enabled); i++) {
_selected_param--;
if (_selected_param < 1) {
_selected_param = SAVE_PARAM;
}
}
// repeat at the standard rate
_transition_timeout_ms = osd->button_delay_ms;
break;
case MenuState::PARAM_VALUE_MODIFY:
modify_parameter(_selected_param, ev);
break;
case MenuState::PARAM_PARAM_MODIFY:
modify_configured_parameter(_selected_param, ev);
break;
}
break;
case Event::MENU_DOWN:
switch (_menu_state) {
case MenuState::PARAM_SELECT:
_selected_param++;
if (_selected_param > SAVE_PARAM) {
_selected_param = 1;
}
// skip over parameters that are not enabled
for (uint8_t i = 0; i < NUM_PARAMS + 1 && (_selected_param != SAVE_PARAM && !params[_selected_param-1].enabled); i++) {
_selected_param++;
if (_selected_param > SAVE_PARAM) {
_selected_param = 1;
}
}
// repeat at the standard rate
_transition_timeout_ms = osd->button_delay_ms;
break;
case MenuState::PARAM_VALUE_MODIFY:
modify_parameter(_selected_param, ev);
break;
case MenuState::PARAM_PARAM_MODIFY:
modify_configured_parameter(_selected_param, ev);
break;
}
break;
case Event::MENU_EXIT:
switch(_menu_state) {
case MenuState::PARAM_SELECT:
break;
case MenuState::PARAM_VALUE_MODIFY:
_menu_state = MenuState::PARAM_SELECT;
break;
case MenuState::PARAM_PARAM_MODIFY:
_menu_state = MenuState::PARAM_VALUE_MODIFY;
break;
}
break;
case Event::NONE:
break;
}
}
void AP_OSD_ParamScreen::draw(void)
{
if (!enabled || !backend) {
return;
}
// first update the state machine
if (!AP::arming().is_armed()) {
update_state_machine();
} else {
_selected_param = 0;
}
for (uint8_t i = 0; i < NUM_PARAMS; i++) {
AP_OSD_ParamSetting n = params[i];
if (n.enabled) {
draw_parameter(n._param_number, n.xpos, n.ypos);
}
}
// the save button
draw_parameter(SAVE_PARAM, save_x, save_y);
}
// handle OSD configuration messages
void AP_OSD_ParamScreen::handle_write_msg(const mavlink_osd_param_config_t& packet, const GCS_MAVLINK& link)
{
// request out of range - return an error
if (packet.osd_index < 1 || packet.osd_index > AP_OSD_ParamScreen::NUM_PARAMS) {
mavlink_msg_osd_param_config_reply_send(link.get_chan(), packet.request_id, OSD_PARAM_INVALID_PARAMETER_INDEX);
return;
}
// set the parameter
bool ret = params[packet.osd_index - 1].set_by_name(packet.param_id, packet.config_type, packet.min_value, packet.max_value, packet.increment);
mavlink_msg_osd_param_config_reply_send(link.get_chan(), packet.request_id, ret ? OSD_PARAM_SUCCESS : OSD_PARAM_INVALID_PARAMETER);
}
// handle OSD show configuration messages
void AP_OSD_ParamScreen::handle_read_msg(const mavlink_osd_param_show_config_t& packet, const GCS_MAVLINK& link)
{
// request out of range - return an error
if (packet.osd_index < 1 || packet.osd_index > AP_OSD_ParamScreen::NUM_PARAMS) {
mavlink_msg_osd_param_show_config_reply_send(link.get_chan(), packet.request_id, OSD_PARAM_INVALID_PARAMETER_INDEX,
nullptr, OSD_PARAM_NONE, 0, 0, 0);
return;
}
// get the parameter and make sure it is fresh
AP_OSD_ParamSetting& param = params[packet.osd_index - 1];
param.update();
// check for bad things
if (param._param == nullptr) {
mavlink_msg_osd_param_show_config_reply_send(link.get_chan(), packet.request_id, OSD_PARAM_INVALID_PARAMETER_INDEX,
nullptr, OSD_PARAM_NONE, 0, 0, 0);
return;
}
// get the name and send back the details
char buf[AP_MAX_NAME_SIZE+1];
param._param->copy_name_token(param._current_token, buf, AP_MAX_NAME_SIZE);
buf[AP_MAX_NAME_SIZE] = 0;
mavlink_msg_osd_param_show_config_reply_send(link.get_chan(), packet.request_id, OSD_PARAM_SUCCESS,
buf, param._type, param._param_min, param._param_max, param._param_incr);
}
#endif // OSD_PARAM_ENABLED
// pre_arm_check - returns true if all pre-takeoff checks have completed successfully
bool AP_OSD::pre_arm_check(char *failure_msg, const uint8_t failure_msg_len) const
{
// currently in the OSD menu, do not allow arming
if (!is_readonly_screen()) {
hal.util->snprintf(failure_msg, failure_msg_len, "In OSD menu");
return false;
}
// if we got this far everything must be ok
return true;
}

View File

@ -0,0 +1,430 @@
/*
* 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"
#include <AP_Vehicle/AP_Vehicle_Type.h>
#include <SRV_Channel/SRV_Channel.h>
#if OSD_PARAM_ENABLED
const AP_Param::GroupInfo AP_OSD_ParamSetting::var_info[] = {
// @Param: _EN
// @DisplayName: Enable
// @Description: Enable setting
// @Values: 0:Disabled,1:Enabled
// @User: Standard
AP_GROUPINFO("_EN", 1, AP_OSD_ParamSetting, enabled, 0),
// @Param: _X
// @DisplayName: X position
// @Description: Horizontal position on screen
// @Range: 0 29
// @User: Standard
AP_GROUPINFO("_X", 2, AP_OSD_ParamSetting, xpos, 0),
// @Param: _Y
// @DisplayName: Y position
// @Description: Vertical position on screen
// @Range: 0 15
// @User: Standard
AP_GROUPINFO("_Y", 3, AP_OSD_ParamSetting, ypos, 0),
// Parameter access keys. These default to -1 too allow user overrides
// to work properly
// @Param: _KEY
// @DisplayName: Parameter key
// @Description: Key of the parameter to be displayed and modified
// @User: Standard
AP_GROUPINFO("_KEY", 4, AP_OSD_ParamSetting, _param_key, -1),
// @Param: _IDX
// @DisplayName: Parameter index
// @Description: Index of the parameter to be displayed and modified
// @User: Standard
AP_GROUPINFO("_IDX", 5, AP_OSD_ParamSetting, _param_idx, -1),
// @Param: _GRP
// @DisplayName: Parameter group
// @Description: Group of the parameter to be displayed and modified
// @User: Standard
AP_GROUPINFO("_GRP", 6, AP_OSD_ParamSetting, _param_group, -1),
// @Param: _MIN
// @DisplayName: Parameter minimum
// @Description: Minimum value of the parameter to be displayed and modified
// @User: Standard
AP_GROUPINFO("_MIN", 7, AP_OSD_ParamSetting, _param_min, 0.0f),
// @Param: _MAX
// @DisplayName: Parameter maximum
// @Description: Maximum of the parameter to be displayed and modified
// @User: Standard
AP_GROUPINFO("_MAX", 8, AP_OSD_ParamSetting, _param_max, 1.0f),
// @Param: _INCR
// @DisplayName: Parameter increment
// @Description: Increment of the parameter to be displayed and modified
// @User: Standard
AP_GROUPINFO("_INCR", 9, AP_OSD_ParamSetting, _param_incr, 0.001f),
// @Param: _TYPE
// @DisplayName: Parameter type
// @Description: Type of the parameter to be displayed and modified
// @User: Standard
AP_GROUPINFO("_TYPE", 10, AP_OSD_ParamSetting, _type, 0),
AP_GROUPEND
};
#define PARAM_COMPOSITE_INDEX(key, idx, group) (uint32_t((uint32_t(key) << 23) | (uint32_t(idx) << 18) | uint32_t(group)))
#define OSD_PARAM_DEBUG 0
#if OSD_PARAM_DEBUG
#define debug(fmt, args ...) do { hal.console->printf("OSD: " fmt, args); } while (0)
#else
#define debug(fmt, args ...)
#endif
// at the cost of a little flash, we can create much better ranges and values for certain important settings
// common labels - all strings must be upper case
#if APM_BUILD_TYPE(APM_BUILD_ArduPlane) || APM_BUILD_TYPE(APM_BUILD_ArduCopter)
static const char* SERIAL_PROTOCOL_VALUES[] = {
"", "MAV", "MAV2", "FSKY_D", "FSKY_S", "GPS", "", "ALEX", "STORM", "RNG",
"FSKY_TX", "LID360", "", "BEACN", "VOLZ", "SBUS", "ESC_TLM", "DEV_TLM", "OPTFLW", "RBTSRV",
"NMEA", "WNDVNE", "SLCAN", "RCIN", "MGSQRT", "LTM", "RUNCAM", "HOT_TLM", "SCRIPT", "CRSF",
"GEN", "WNCH", "MSP", "DJI"
};
static const char* SERVO_FUNCTIONS[] = {
"NONE", "RCPASS", "FLAP", "FLAP_AUTO", "AIL", "", "MNT_PAN", "MNT_TLT", "MNT_RLL", "MNT_OPEN",
"CAM_TRG", "", "MNT2_PAN", "MNT2_TLT", "MNT2_RLL", "MNT2_OPEN", "DIF_SPL_L1", "DIF_SPL_R1", "", "ELE",
"", "RUD", "SPR_PMP", "SPR_SPIN", "FLPRON_L", "FLPRON_R", "GRND_STEER", "PARACHT", "GRIP", "GEAR",
"ENG_RUN_EN", "HELI_RSC", "HELI_TAIL_RSC", "MOT_1", "MOT_2", "MOT_3", "MOT_4", "MOT_5", "MOT_6", "MOT_7",
"MOT_8", "MOT_TLT", "", "", "", "", "", "", "", "",
"", "RCIN_1", "RCIN_2", "RCIN_3", "RCIN_4", "RCIN_5", "RCIN_6", "RCIN_7", "RCIN_8", "RCIN_9",
"RCIN_10", "RCIN_11", "RCIN_12", "RCIN_13", "RCIN_14", "RCIN_15", "RCIN_16", "IGN", "", "START",
"THR", "TRCK_YAW", "TRCK_PIT", "THR_L", "THR_R", "TLTMOT_L", "TLTMOT_R", "ELEVN_L", "ELEVN_R", "VTAIL_L",
"VTAIL_R", "BOOST_THR", "MOT_9", "MOT_10", "MOT_11", "MOT_12", "DIF_SPL_L2", "DIF_SPL_R2", "", "MAIN_SAIL",
"CAM_ISO", "CAM_APTR", "CAM_FOC", "CAM_SH_SPD", "SCRPT_1", "SCRPT_2", "SCRPT_3", "SCRPT_4", "SCRPT_5", "SCRPT_6",
"SCRPT_7", "SCRPT_8", "SCRPT_9", "SCRPT_10", "SCRPT_11", "SCRPT_12", "SCRPT_13", "SCRPT_14", "SCRPT_15", "SCRPT_16",
"", "", "", "", "", "", "", "", "", "",
"NEOPX_1", "NEOPX_2", "NEOPX_3", "NEOPX_4", "RAT_RLL", "RAT_PIT","RAT_THRST", "RAT_YAW", "WSAIL_EL", "PRLED_1",
"PRLED_2", "PRLED_3", "PRLED_CLK", "WNCH_CL"
};
#endif
#if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
static const char* AUX_OPTIONS[] = {
"NONE", "", "", "", "RTL", "", "", "", "", "CAM_TRG",
"", "", "", "", "", "", "AUTO", "", "", "",
"", "", "", "", "MIS_RST", "", "", "", "RLY", "LAND_GR",
"LOST_SND", "M_ESTOP", "", "", "", "RLY3", "RLY4", "", "OA_ADSB", "",
"", "ARM/DS", "", "INVERT", "", "", "RC_OVRD", "", "", "",
"", "MANUAL", "", "", "", "GUIDE", "LOIT", "", "CLR_WP", "",
"", "", "COMP_LRN", "", "REV_THR", "GPS_DIS", "RLY5", "RLY6", "", "",
"", "", "CIRCLE", "", "", "", "", "TAKEOFF", "RCAM_CTL", "RCAM_OSD",
"", "DSARM", "QASS3POS", "", "AIR", "GEN", "TER_AUTO", "CROW_SEL", "SOAR", "",
"", "", "", "", "", "", "", "", "", "",
"KILLIMU1", "KILLIMU2", "CAM_TOG", "", "", "GPSYAW_DIS"
};
static const char* FLTMODES[] = {
"MAN", "CIRC", "STAB", "TRAIN", "ACRO", "FBWA", "FBWB", "CRUISE", "ATUNE", "", "AUTO",
"RTL", "LOIT", "TKOF", "ADSB", "GUID", "", "QSTAB", "QHOV", "QLOIT", "QLAND",
"QRTL", "QTUNE", "QACRO"
};
static const char* FS_ACT[] = {
"NONE", "RTL", "LAND", "TERM", "QLAND", "PARA"
};
static const char* FS_SHRT_ACTNS[] = {
"CRC_NOCHNGE", "CIRC", "FBWA", "DSABLE"
};
static const char* FS_LNG_ACTNS[] = {
"CNTNUE", "RTL", "GLIDE", "PARACHT"
};
// plane parameters
const AP_OSD_ParamSetting::ParamMetadata AP_OSD_ParamSetting::_param_metadata[OSD_PARAM_NUM_TYPES] = {
{ -1, AP_SerialManager::SerialProtocol_NumProtocols - 1, 1, ARRAY_SIZE(SERIAL_PROTOCOL_VALUES), SERIAL_PROTOCOL_VALUES }, // OSD_PARAM_SERIAL_PROTOCOL
{ 0, SRV_Channel::k_nr_aux_servo_functions - 1, 1, ARRAY_SIZE(SERVO_FUNCTIONS), SERVO_FUNCTIONS }, // OSD_PARAM_SERVO_FUNCTION
{ 0, 105, 1, ARRAY_SIZE(AUX_OPTIONS), AUX_OPTIONS }, // OSD_PARAM_AUX_FUNCTION
{ 0, 23, 1, ARRAY_SIZE(FLTMODES), FLTMODES }, // OSD_PARAM_FLIGHT_MODE
{ 0, 5, 1, ARRAY_SIZE(FS_ACT), FS_ACT }, // OSD_PARAM_FAILSAFE_ACTION
{ 0, 3, 1, ARRAY_SIZE(FS_SHRT_ACTNS), FS_SHRT_ACTNS }, // OSD_PARAM_FAILSAFE_ACTION_1
{ 0, 3, 1, ARRAY_SIZE(FS_LNG_ACTNS), FS_LNG_ACTNS }, // OSD_PARAM_FAILSAFE_ACTION_2
};
#elif APM_BUILD_TYPE(APM_BUILD_ArduCopter)
static const char* AUX_OPTIONS[] = {
"NONE", "", "FLIP", "SIMP", "RTL", "SAV_TRM", "", "SAV_WP", "", "CAM_TRG",
"RNG", "FENCE", "", "SSIMP", "ACRO_TRN", "SPRAY", "AUTO", "AUTOTN", "LAND", "GRIP",
"", "CHUTE_EN", "CHUTE_RL", "CHUTE_3P", "MIS_RST", "ATT_FF", "ATT_ACC", "RET_MNT", "RLY", "LAND_GR",
"LOST_SND", "M_ESTOP", "M_ILOCK", "BRAKE", "RLY2", "RLY3", "RLY4", "THROW", "OA_ADSB", "PR_LOIT",
"OA_PROX", "ARM/DS", "SMRT_RTL", "INVERT", "", "", "RC_OVRD", "USR1", "USR2", "USR3",
"", "", "ACRO", "", "", "GUIDE", "LOIT", "FOLLOW", "CLR_WP", "",
"ZZAG", "ZZ_SVWP", "COMP_LRN", "", "", "GPS_DIS", "RLY5", "RLY6", "STAB", "PHOLD",
"AHOLD", "FHOLD", "CIRCLE", "DRIFT", "", "", "STANDBY", "", "RCAM_CTL", "RCAM_OSD",
"VISO_CAL", "DISARM", "", "ZZ_Auto", "AIR", "", "", "", "", "",
"", "", "", "", "", "", "", "", "", "",
"KILLIMU1", "KILLIMU2", "CAM_MOD_TOG", "", "", "GPSYAW_DIS"
};
static const char* FLTMODES[] = {
"STAB", "ACRO", "ALTHOLD", "AUTO", "GUIDED", "LOIT", "RTL", "CIRC", "", "LAND",
"", "DRFT", "", "SPORT", "FLIP", "ATUN", "POSHLD", "BRAKE", "THROW", "AVD_ADSB",
"GUID_NOGPS", "SMRTRTL", "FLOHOLD", "FOLLOW", "ZIGZAG", "SYSID", "HELI_ARO"
};
static const char* FS_OPTIONS[] = {
"NONE", "CONT_RCFS", "CONT_GCSFS", "CONT_RC/GCSFS", "", "", "", "CONT_LAND", "",
"", "", "", "", "", "", "CONT_CTRL_GCS", "", "", "CONTNUE"
};
static const char* THR_FS_ACT[] = {
"NONE", "RTL", "CONT", "LAND", "SRTL_RTL", "SRTL_LAND"
};
static const char* FS_ACT[] = {
"NONE", "LAND", "RTL", "SRTL_RTL", "SRTL_LAND", "TERM"
};
// copter parameters
const AP_OSD_ParamSetting::ParamMetadata AP_OSD_ParamSetting::_param_metadata[OSD_PARAM_NUM_TYPES] = {
{ -1, AP_SerialManager::SerialProtocol_NumProtocols - 1, 1, ARRAY_SIZE(SERIAL_PROTOCOL_VALUES), SERIAL_PROTOCOL_VALUES }, // OSD_PARAM_SERIAL_PROTOCOL
{ 0, SRV_Channel::k_nr_aux_servo_functions - 1, 1, ARRAY_SIZE(SERVO_FUNCTIONS), SERVO_FUNCTIONS }, // OSD_PARAM_SERVO_FUNCTION
{ 0, 105, 1, ARRAY_SIZE(AUX_OPTIONS), AUX_OPTIONS }, // OSD_PARAM_AUX_FUNCTION
{ 0, 23, 1, ARRAY_SIZE(FLTMODES), FLTMODES }, // OSD_PARAM_FLIGHT_MODE
{ 0, 3, 1, ARRAY_SIZE(FS_OPTIONS), FS_OPTIONS }, // OSD_PARAM_FAILSAFE_ACTION
{ 0, 5, 1, ARRAY_SIZE(FS_ACT), FS_ACT }, // OSD_PARAM_FAILSAFE_ACTION_1
{ 0, 5, 1, ARRAY_SIZE(THR_FS_ACT), THR_FS_ACT }, // OSD_PARAM_FAILSAFE_ACTION_2
};
#else
const AP_OSD_ParamSetting::ParamMetadata AP_OSD_ParamSetting::_param_metadata[OSD_PARAM_NUM_TYPES] = {};
#endif
extern const AP_HAL::HAL& hal;
// constructor
AP_OSD_ParamSetting::AP_OSD_ParamSetting(uint8_t param_number, bool _enabled, uint8_t x, uint8_t y, int16_t key, int8_t idx, int32_t group, int8_t type, float min, float max, float incr)
: AP_OSD_Setting(_enabled, x, y), _param_number(param_number)
{
_param_group = group;
_param_idx = idx;
_param_key = key;
_param_min = min;
_param_max = max;
_param_incr = incr;
_type = type;
}
// update the contained parameter
void AP_OSD_ParamSetting::update()
{
// if the user has not made any changes then skip the update
if (PARAM_TOKEN_INDEX(_current_token) == PARAM_COMPOSITE_INDEX(_param_key, _param_idx, _param_group) && _param_key >= 0) {
return;
}
// if a parameter was configured then use that
_current_token = AP_Param::ParamToken {};
// surely there is a more efficient way than brute-force search
for (_param = AP_Param::first(&_current_token, &_param_type);
_param && (AP_Param::get_persistent_key(_current_token.key) != uint16_t(_param_key.get())
|| _current_token.idx != uint8_t(_param_idx.get())
|| _current_token.group_element != uint32_t(_param_group.get()));
_param = AP_Param::next_scalar(&_current_token, &_param_type)) {
}
if (_param == nullptr) {
enabled = false;
} else {
guess_ranges();
}
}
// update parameter settings from the named parameter
bool AP_OSD_ParamSetting::set_by_name(const char* name, uint8_t config_type, float pmin, float pmax, float pincr)
{
AP_Param::ParamToken token = AP_Param::ParamToken {};
ap_var_type type;
AP_Param* param = AP_Param::find_by_name(name, &type, &token);
if (param == nullptr) {
// leave unchanged
return false;
} else {
_current_token = token;
_param_type = type;
_param = param;
enabled.set_and_save_ifchanged(true);
}
_type.set_and_save_ifchanged(config_type);
if (config_type == OSD_PARAM_NONE && !is_zero(pincr)) {
// ranges
_param_min.set_and_save_ifchanged(pmin);
_param_max.set_and_save_ifchanged(pmax);
_param_incr.set_and_save_ifchanged(pincr);
} else {
guess_ranges(true);
}
_param_key.set_and_save_ifchanged(AP_Param::get_persistent_key(_current_token.key));
_param_idx.set_and_save_ifchanged(_current_token.idx);
_param_group.set_and_save_ifchanged(_current_token.group_element);
return true;
}
// guess the ranges and increment for the selected parameter
// only called when a change has been made
void AP_OSD_ParamSetting::guess_ranges(bool force)
{
if (_param->is_read_only()) {
return;
}
// check for statically configured setting metadata
if (set_from_metadata()) {
return;
}
// nothing statically configured so guess some appropriate values
float min = -1, max = 127, incr = 1;
if (_param != nullptr) {
switch (_param_type) {
case AP_PARAM_INT8:
break;
case AP_PARAM_INT16: {
AP_Int16* p = (AP_Int16*)_param;
min = -1;
uint8_t digits = 0;
for (int16_t int16p = p->get(); int16p > 0; int16p /= 10) {
digits++;
}
incr = MAX(1, powf(10, digits - 2));
max = powf(10, digits + 1);
debug("Guessing range for value %d as %f -> %f, %f\n", p->get(), min, max, incr);
break;
}
case AP_PARAM_INT32: {
AP_Int32* p = (AP_Int32*)_param;
min = -1;
uint8_t digits = 0;
for (int32_t int32p = p->get(); int32p > 0; int32p /= 10) {
digits++;
}
incr = MAX(1, powf(10, digits - 2));
max = powf(10, digits + 1);
debug("Guessing range for value %d as %f -> %f, %f\n", p->get(), min, max, incr);
break;
}
case AP_PARAM_FLOAT: {
AP_Float* p = (AP_Float*)_param;
uint8_t digits = 0;
for (float floatp = p->get(); floatp > 1.0f; floatp /= 10) {
digits++;
}
float floatp = p->get();
if (digits < 1) {
if (!is_zero(floatp)) {
incr = floatp / 100.0f; // move in 1% increments
} else {
incr = 0.01f; // move in absolute 1% increments
}
max = 1.0;
min = 0.0f;
} else {
if (!is_zero(floatp)) {
incr = floatp / 100.0f; // move in 1% increments
} else {
incr = MAX(1, powf(10, digits - 2));
}
max = powf(10, digits + 1);
min = 0.0f;
}
debug("Guessing range for value %f as %f -> %f, %f\n", p->get(), min, max, incr);
break;
}
case AP_PARAM_VECTOR3F:
case AP_PARAM_NONE:
case AP_PARAM_GROUP:
break;
}
if (force || !_param_min.configured()) {
_param_min = min;
}
if (force || !_param_max.configured()) {
_param_max = max;
}
if (force || !_param_incr.configured()) {
_param_incr = incr;
}
}
}
bool AP_OSD_ParamSetting::set_from_metadata()
{
// check for statically configured setting metadata
if (_type > 0 && _type < OSD_PARAM_NUM_TYPES && _param_metadata[_type - 1].values_max > 0) {
_param_incr = _param_metadata[_type - 1].increment;
_param_min = _param_metadata[_type - 1].min_value;
_param_max = _param_metadata[_type - 1].max_value;
return true;
}
return false;
}
// modify the selected parameter values
void AP_OSD_ParamSetting::save_as_new()
{
_param_group.save();
_param_key.save();
_param_idx.save();
// the user has configured the range and increment, but the parameter
// is no longer valid so reset these to guessed values
guess_ranges(true);
if (_param_min.configured()) {
_param_min.save();
}
if (_param_max.configured()) {
_param_max.save();
}
if (_param_incr.configured()) {
_param_incr.save();
}
}
#endif // OSD_PARAM_ENABLED

View File

@ -842,6 +842,7 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = {
// constructor
AP_OSD_Screen::AP_OSD_Screen()
{
AP_Param::setup_object_defaults(this, var_info);
}
//Symbols
@ -875,8 +876,6 @@ AP_OSD_Screen::AP_OSD_Screen()
#define SYM_FTMIN 0xE8
#define SYM_FTSEC 0x99
#define SYM_SAT_L 0x1E
#define SYM_SAT_R 0x1F
#define SYM_HDOP_L 0xBD
@ -894,7 +893,6 @@ AP_OSD_Screen::AP_OSD_Screen()
#define SYM_AH_V_START 0xCA
#define SYM_AH_V_COUNT 6
#define SYM_AH_CENTER_LINE_LEFT 0x26
#define SYM_AH_CENTER_LINE_RIGHT 0x27
#define SYM_AH_CENTER 0x7E
@ -932,13 +930,13 @@ AP_OSD_Screen::AP_OSD_Screen()
#define SYM_AH 0xF3
#define SYM_CLK 0xBC
void AP_OSD_Screen::set_backend(AP_OSD_Backend *_backend)
void AP_OSD_AbstractScreen::set_backend(AP_OSD_Backend *_backend)
{
backend = _backend;
osd = _backend->get_osd();
};
bool AP_OSD_Screen::check_option(uint32_t option)
bool AP_OSD_AbstractScreen::check_option(uint32_t option)
{
return osd?(osd->options & option) != 0 : false;
}
@ -946,7 +944,7 @@ bool AP_OSD_Screen::check_option(uint32_t option)
/*
get the right units icon given a unit
*/
char AP_OSD_Screen::u_icon(enum unit_type unit)
char AP_OSD_AbstractScreen::u_icon(enum unit_type unit)
{
static const char icons_metric[UNIT_TYPE_LAST] {
(char)SYM_ALT_M, //ALTITUDE
@ -992,7 +990,7 @@ char AP_OSD_Screen::u_icon(enum unit_type unit)
/*
scale a value for the user selected units
*/
float AP_OSD_Screen::u_scale(enum unit_type unit, float value)
float AP_OSD_AbstractScreen::u_scale(enum unit_type unit, float value)
{
static const float scale_metric[UNIT_TYPE_LAST] = {
1.0, //ALTITUDE m