AP_OSD: use cleaner conditional compilation for the various OSD options

provide suitable defaults for parameter screens on different vehicles
build fixes
Co-authored-by: Peter Barker <pb-gh@barker.dropbear.id.au>
This commit is contained in:
Andy Piper 2020-09-10 21:51:04 +01:00 committed by Andrew Tridgell
parent 460293d6a8
commit 46d4d9a97e
5 changed files with 101 additions and 31 deletions

View File

@ -267,16 +267,7 @@ void AP_OSD::update_osd()
update_current_screen(); update_current_screen();
get_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 HAL_WITH_OSD_BITMAP
#if OSD_PARAM_ENABLED
get_screen(current_screen).draw(); get_screen(current_screen).draw();
#else
((AP_OSD_Screen&)get_screen(current_screen)).draw();
#endif
#endif
} }
backend->flush(); backend->flush();

View File

@ -73,9 +73,7 @@ class AP_OSD_AbstractScreen
public: public:
// constructor // constructor
AP_OSD_AbstractScreen() {} AP_OSD_AbstractScreen() {}
#if OSD_PARAM_ENABLED virtual void draw(void) {}
virtual void draw(void) = 0;
#endif
void set_backend(AP_OSD_Backend *_backend); void set_backend(AP_OSD_Backend *_backend);
@ -111,10 +109,11 @@ class AP_OSD_Screen : public AP_OSD_AbstractScreen
public: public:
// constructor // constructor
AP_OSD_Screen(); AP_OSD_Screen();
#if OSD_PARAM_ENABLED
// 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 HAL_WITH_OSD_BITMAP
void draw(void) override; void draw(void) override;
#else
void draw(void);
#endif #endif
// User settable parameters // User settable parameters
@ -269,11 +268,19 @@ public:
uint8_t values_max; uint8_t values_max;
const char** values; const char** values;
}; };
// compact structure used to hold default values for static initialization
struct Initializer {
uint8_t index;
AP_Param::ParamToken token;
int8_t type;
};
static const ParamMetadata _param_metadata[]; 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, 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); int8_t type = OSD_PARAM_NONE, float min = 0.0f, float max = 1.0f, float incr = 0.001f);
AP_OSD_ParamSetting(uint8_t param_number);
AP_OSD_ParamSetting(const Initializer& initializer);
// initialize the setting from the configured information // initialize the setting from the configured information
void update(); void update();
@ -300,7 +307,7 @@ private:
class AP_OSD_ParamScreen : public AP_OSD_AbstractScreen class AP_OSD_ParamScreen : public AP_OSD_AbstractScreen
{ {
public: public:
AP_OSD_ParamScreen(); AP_OSD_ParamScreen(uint8_t index);
enum class Event { enum class Event {
NONE, NONE,
@ -331,17 +338,7 @@ public:
static const struct AP_Param::GroupInfo var_info[]; static const struct AP_Param::GroupInfo var_info[];
private: private:
AP_OSD_ParamSetting params[NUM_PARAMS] = { AP_OSD_ParamSetting params[NUM_PARAMS] { 1, 2, 3, 4, 5, 6, 7, 8, 9 };
{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 update_state_machine();
void draw_parameter(uint8_t param_number, uint8_t x, uint8_t y); void draw_parameter(uint8_t param_number, uint8_t x, uint8_t y);
@ -443,7 +440,7 @@ public:
AP_OSD_Screen screen[AP_OSD_NUM_DISPLAY_SCREENS]; AP_OSD_Screen screen[AP_OSD_NUM_DISPLAY_SCREENS];
#if OSD_PARAM_ENABLED #if OSD_PARAM_ENABLED
AP_OSD_ParamScreen param_screen[AP_OSD_NUM_PARAM_SCREENS]; AP_OSD_ParamScreen param_screen[AP_OSD_NUM_PARAM_SCREENS] { 0, 1 };
#endif #endif
struct NavInfo { struct NavInfo {
float wp_distance; float wp_distance;

View File

@ -232,7 +232,68 @@ static const char* event_names[5] = {
#define debug(fmt, args ...) #define debug(fmt, args ...)
#endif #endif
AP_OSD_ParamScreen::AP_OSD_ParamScreen() { static const AP_OSD_ParamSetting::Initializer PARAM_DEFAULTS[AP_OSD_NUM_PARAM_SCREENS][AP_OSD_ParamScreen::NUM_PARAMS] {
#if APM_BUILD_TYPE(APM_BUILD_ArduCopter)
{
{ 1, { 102, 0, 4033 }, OSD_PARAM_NONE }, // ATC_RAT_RLL_P
{ 2, { 102, 0, 129 }, OSD_PARAM_NONE }, // ATC_RAT_RLL_D
{ 3, { 102, 0, 705 }, OSD_PARAM_NONE }, // ATC_RAT_RLL_FLTD
{ 4, { 102, 0, 4034 }, OSD_PARAM_NONE }, // ATC_RAT_PIT_P
{ 5, { 102, 0, 130 }, OSD_PARAM_NONE }, // ATC_RAT_PIT_D
{ 6, { 102, 0, 706 }, OSD_PARAM_NONE }, // ATC_RAT_PIT_FLTD
{ 7, { 102, 0, 4035 }, OSD_PARAM_NONE }, // ATC_RAT_YAW_P
{ 8, { 102, 0, 131 }, OSD_PARAM_NONE }, // ATC_RAT_YAW_D
{ 9, { 102, 0, 643 }, OSD_PARAM_NONE } // ATC_RAT_YAW_FLTE
},
{
{ 1, { 3, 0, 231 }, OSD_PARAM_NONE }, // INS_LOG_BAT_OPT
{ 2, { 3, 0, 167 }, OSD_PARAM_NONE }, // INS_LOG_BAT_MASK
{ 3, { 60, 0, 0 }, OSD_PARAM_NONE }, // LOG_BITMASK
{ 4, { 3, 0, 18 }, OSD_PARAM_NONE }, // INS_GYRO_FILT
{ 5, { 102, 0, 6 }, OSD_PARAM_NONE }, // ATC_THR_MIX_MAN
{ 6, { 102, 0, 5 }, OSD_PARAM_NONE }, // ATC_THR_MIX_MAX
{ 7, { 6, 0, 25041 }, OSD_PARAM_AUX_FUNCTION }, // RC7_OPTION
{ 8, { 6, 0, 25105 }, OSD_PARAM_AUX_FUNCTION }, // RC8_OPTION
{ 9, { 36, 0, 1047 }, OSD_PARAM_FAILSAFE_ACTION_2 } // BATT_FS_LOW_ACT
}
#elif APM_BUILD_TYPE(APM_BUILD_ArduPlane)
{
{ 1, { 232, 0, 1 }, OSD_PARAM_NONE }, // RLL2SRV_P
{ 2, { 232, 0, 3 }, OSD_PARAM_NONE }, // RLL2SRV_I
{ 3, { 232, 0, 2 }, OSD_PARAM_NONE }, // RLL2SRV_D
{ 4, { 233, 0, 1 }, OSD_PARAM_NONE }, // PTCH2SRV_P
{ 5, { 233, 0, 3 }, OSD_PARAM_NONE }, // PTCH2SRV_I
{ 6, { 233, 0, 2 }, OSD_PARAM_NONE }, // PTCH2SRV_D
{ 7, { 233, 0, 6 }, OSD_PARAM_NONE }, // PTCH2SRV_RLL
{ 8, { 199, 0, 1 }, OSD_PARAM_NONE }, // TUNE_PARAM
{ 9, { 199, 0, 320 }, OSD_PARAM_NONE } // TUNE_RANGE
},
{
{ 1, { 185, 0, 0 }, OSD_PARAM_NONE }, // TRIM_THROTTLE
{ 2, { 155, 0, 0 }, OSD_PARAM_NONE }, // TRIM_ARSPD_CM
{ 3, { 4, 0, 1094 }, OSD_PARAM_NONE }, // SERVO_AUTO_TRIM
{ 4, { 120, 0, 0 }, OSD_PARAM_NONE}, // ARSPD_FBW_MIN
{ 5, { 121, 0, 0 }, OSD_PARAM_NONE }, // ARSPD_FBW_MAX
{ 6, { 156, 0, 0 }, OSD_PARAM_NONE }, // ALT_HOLD_RTL
{ 7, { 140, 2, 8 }, OSD_PARAM_NONE }, // AHRS_TRIM_Y
{ 8, { 182, 0, 0 }, OSD_PARAM_NONE }, // THR_MAX
{ 9, { 189, 0, 0 }, OSD_PARAM_NONE } // THR_SLEWRATE
}
#else
{
{ 1 }, { 2 }, { 3 }, { 4 }, { 5 }, { 6 }, { 7 }, { 8 }, { 9 },
},
{
{ 1 }, { 2 }, { 3 }, { 4 }, { 5 }, { 6 }, { 7 }, { 8 }, { 9 }
}
#endif
};
AP_OSD_ParamScreen::AP_OSD_ParamScreen(uint8_t index)
{
for (uint8_t i = 0; i < NUM_PARAMS; i++) {
params[i] = PARAM_DEFAULTS[index][i];
}
AP_Param::setup_object_defaults(this, var_info); AP_Param::setup_object_defaults(this, var_info);
} }
@ -703,4 +764,3 @@ bool AP_OSD::pre_arm_check(char *failure_msg, const uint8_t failure_msg_len) con
// if we got this far everything must be ok // if we got this far everything must be ok
return true; return true;
} }

View File

@ -246,6 +246,27 @@ AP_OSD_ParamSetting::AP_OSD_ParamSetting(uint8_t param_number, bool _enabled, ui
_type = type; _type = type;
} }
// default constructor that just sets some sensible defaults that exist on all platforms
AP_OSD_ParamSetting::AP_OSD_ParamSetting(uint8_t param_number)
: AP_OSD_Setting(false, 2, param_number + 1), _param_number(param_number)
{
_param_min = 0.0f;
_param_max = 1.0f;
_param_incr = 0.001f;
_type = OSD_PARAM_NONE;
}
// construct a setting from a compact static initializer structure
AP_OSD_ParamSetting::AP_OSD_ParamSetting(const Initializer& initializer)
: AP_OSD_ParamSetting(initializer.index)
{
_param_group = initializer.token.group_element;
_param_idx = initializer.token.idx;
_param_key = initializer.token.key;
_type = initializer.type;
enabled = true;
}
// update the contained parameter // update the contained parameter
void AP_OSD_ParamSetting::update() void AP_OSD_ParamSetting::update()
{ {

View File

@ -1692,6 +1692,7 @@ void AP_OSD_Screen::draw_clk(uint8_t x, uint8_t y)
#define DRAW_SETTING(n) if (n.enabled) draw_ ## n(n.xpos, n.ypos) #define DRAW_SETTING(n) if (n.enabled) draw_ ## n(n.xpos, n.ypos)
#if HAL_WITH_OSD_BITMAP
void AP_OSD_Screen::draw(void) void AP_OSD_Screen::draw(void)
{ {
if (!enabled || !backend) { if (!enabled || !backend) {
@ -1746,4 +1747,4 @@ void AP_OSD_Screen::draw(void)
DRAW_SETTING(climbeff); DRAW_SETTING(climbeff);
DRAW_SETTING(eff); DRAW_SETTING(eff);
} }
#endif