mirror of https://github.com/ArduPilot/ardupilot
AP_OSD: use internal enumeration in place of mavlink enumeration
this will let us more-easily compile without the mavlink headers
This commit is contained in:
parent
392aa8fd48
commit
d5e4d191d5
|
@ -329,6 +329,18 @@ class AP_OSD_ParamSetting
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
|
|
||||||
|
enum class Type : uint8_t {
|
||||||
|
NONE = 0,
|
||||||
|
SERIAL_PROTOCOL = 1,
|
||||||
|
SERVO_FUNCTION = 2,
|
||||||
|
AUX_FUNCTION = 3,
|
||||||
|
FLIGHT_MODE = 4,
|
||||||
|
FAILSAFE_ACTION = 5,
|
||||||
|
FAILSAFE_ACTION_1 = 6,
|
||||||
|
FAILSAFE_ACTION_2 = 7,
|
||||||
|
NUM_TYPES = 8,
|
||||||
|
};
|
||||||
|
|
||||||
AP_Int8 enabled;
|
AP_Int8 enabled;
|
||||||
AP_Int8 xpos;
|
AP_Int8 xpos;
|
||||||
AP_Int8 ypos;
|
AP_Int8 ypos;
|
||||||
|
@ -341,7 +353,7 @@ public:
|
||||||
AP_Float _param_min;
|
AP_Float _param_min;
|
||||||
AP_Float _param_max;
|
AP_Float _param_max;
|
||||||
AP_Float _param_incr;
|
AP_Float _param_incr;
|
||||||
AP_Int8 _type;
|
AP_Enum<Type> _type;
|
||||||
|
|
||||||
// parameter number
|
// parameter number
|
||||||
uint8_t _param_number;
|
uint8_t _param_number;
|
||||||
|
@ -357,11 +369,12 @@ 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
|
// compact structure used to hold default values for static initialization
|
||||||
struct Initializer {
|
struct Initializer {
|
||||||
uint8_t index;
|
uint8_t index;
|
||||||
AP_Param::ParamToken token;
|
AP_Param::ParamToken token;
|
||||||
int8_t type;
|
Type type;
|
||||||
};
|
};
|
||||||
|
|
||||||
static const ParamMetadata _param_metadata[];
|
static const ParamMetadata _param_metadata[];
|
||||||
|
|
|
@ -129,49 +129,49 @@ static const char* event_names[5] = {
|
||||||
static const AP_OSD_ParamSetting::Initializer PARAM_DEFAULTS[AP_OSD_NUM_PARAM_SCREENS][AP_OSD_ParamScreen::NUM_PARAMS] {
|
static const AP_OSD_ParamSetting::Initializer PARAM_DEFAULTS[AP_OSD_NUM_PARAM_SCREENS][AP_OSD_ParamScreen::NUM_PARAMS] {
|
||||||
#if APM_BUILD_COPTER_OR_HELI
|
#if APM_BUILD_COPTER_OR_HELI
|
||||||
{
|
{
|
||||||
{ 1, { 102, 0, 4033 }, OSD_PARAM_NONE }, // ATC_RAT_RLL_P
|
{ 1, { 102, 0, 4033 }, AP_OSD_ParamSetting::Type::NONE }, // ATC_RAT_RLL_P
|
||||||
{ 2, { 102, 0, 129 }, OSD_PARAM_NONE }, // ATC_RAT_RLL_D
|
{ 2, { 102, 0, 129 }, AP_OSD_ParamSetting::Type::NONE }, // ATC_RAT_RLL_D
|
||||||
{ 3, { 102, 0, 705 }, OSD_PARAM_NONE }, // ATC_RAT_RLL_FLTD
|
{ 3, { 102, 0, 705 }, AP_OSD_ParamSetting::Type::NONE }, // ATC_RAT_RLL_FLTD
|
||||||
{ 4, { 102, 0, 4034 }, OSD_PARAM_NONE }, // ATC_RAT_PIT_P
|
{ 4, { 102, 0, 4034 }, AP_OSD_ParamSetting::Type::NONE }, // ATC_RAT_PIT_P
|
||||||
{ 5, { 102, 0, 130 }, OSD_PARAM_NONE }, // ATC_RAT_PIT_D
|
{ 5, { 102, 0, 130 }, AP_OSD_ParamSetting::Type::NONE }, // ATC_RAT_PIT_D
|
||||||
{ 6, { 102, 0, 706 }, OSD_PARAM_NONE }, // ATC_RAT_PIT_FLTD
|
{ 6, { 102, 0, 706 }, AP_OSD_ParamSetting::Type::NONE }, // ATC_RAT_PIT_FLTD
|
||||||
{ 7, { 102, 0, 4035 }, OSD_PARAM_NONE }, // ATC_RAT_YAW_P
|
{ 7, { 102, 0, 4035 }, AP_OSD_ParamSetting::Type::NONE }, // ATC_RAT_YAW_P
|
||||||
{ 8, { 102, 0, 131 }, OSD_PARAM_NONE }, // ATC_RAT_YAW_D
|
{ 8, { 102, 0, 131 }, AP_OSD_ParamSetting::Type::NONE }, // ATC_RAT_YAW_D
|
||||||
{ 9, { 102, 0, 643 }, OSD_PARAM_NONE } // ATC_RAT_YAW_FLTE
|
{ 9, { 102, 0, 643 }, AP_OSD_ParamSetting::Type::NONE } // ATC_RAT_YAW_FLTE
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
{ 1, { 3, 0, 231 }, OSD_PARAM_NONE }, // INS_LOG_BAT_OPT
|
{ 1, { 3, 0, 231 }, AP_OSD_ParamSetting::Type::NONE }, // INS_LOG_BAT_OPT
|
||||||
{ 2, { 3, 0, 167 }, OSD_PARAM_NONE }, // INS_LOG_BAT_MASK
|
{ 2, { 3, 0, 167 }, AP_OSD_ParamSetting::Type::NONE }, // INS_LOG_BAT_MASK
|
||||||
{ 3, { 60, 0, 0 }, OSD_PARAM_NONE }, // LOG_BITMASK
|
{ 3, { 60, 0, 0 }, AP_OSD_ParamSetting::Type::NONE }, // LOG_BITMASK
|
||||||
{ 4, { 3, 0, 18 }, OSD_PARAM_NONE }, // INS_GYRO_FILT
|
{ 4, { 3, 0, 18 }, AP_OSD_ParamSetting::Type::NONE }, // INS_GYRO_FILT
|
||||||
{ 5, { 102, 0, 6 }, OSD_PARAM_NONE }, // ATC_THR_MIX_MAN
|
{ 5, { 102, 0, 6 }, AP_OSD_ParamSetting::Type::NONE }, // ATC_THR_MIX_MAN
|
||||||
{ 6, { 102, 0, 5 }, OSD_PARAM_NONE }, // ATC_THR_MIX_MAX
|
{ 6, { 102, 0, 5 }, AP_OSD_ParamSetting::Type::NONE }, // ATC_THR_MIX_MAX
|
||||||
{ 7, { 6, 0, 25041 }, OSD_PARAM_AUX_FUNCTION }, // RC7_OPTION
|
{ 7, { 6, 0, 25041 }, AP_OSD_ParamSetting::Type::AUX_FUNCTION }, // RC7_OPTION
|
||||||
{ 8, { 6, 0, 25105 }, OSD_PARAM_AUX_FUNCTION }, // RC8_OPTION
|
{ 8, { 6, 0, 25105 }, AP_OSD_ParamSetting::Type::AUX_FUNCTION }, // RC8_OPTION
|
||||||
{ 9, { 36, 0, 1047 }, OSD_PARAM_FAILSAFE_ACTION_2 } // BATT_FS_LOW_ACT
|
{ 9, { 36, 0, 1047 }, AP_OSD_ParamSetting::Type::FAILSAFE_ACTION_2 } // BATT_FS_LOW_ACT
|
||||||
}
|
}
|
||||||
#elif APM_BUILD_TYPE(APM_BUILD_ArduPlane)
|
#elif APM_BUILD_TYPE(APM_BUILD_ArduPlane)
|
||||||
{
|
{
|
||||||
{ 1, { 232, 0, 265 }, OSD_PARAM_NONE }, // RLL_RATE_FF
|
{ 1, { 232, 0, 265 }, AP_OSD_ParamSetting::Type::NONE }, // RLL_RATE_FF
|
||||||
{ 2, { 232, 0, 4041 }, OSD_PARAM_NONE }, // RLL_RATE_P
|
{ 2, { 232, 0, 4041 }, AP_OSD_ParamSetting::Type::NONE }, // RLL_RATE_P
|
||||||
{ 3, { 232, 0, 73 }, OSD_PARAM_NONE }, // RLL_RATE_I
|
{ 3, { 232, 0, 73 }, AP_OSD_ParamSetting::Type::NONE }, // RLL_RATE_I
|
||||||
{ 4, { 233, 0, 267 }, OSD_PARAM_NONE }, // PTCH_RATE_FF
|
{ 4, { 233, 0, 267 }, AP_OSD_ParamSetting::Type::NONE }, // PTCH_RATE_FF
|
||||||
{ 5, { 233, 0, 4043 }, OSD_PARAM_NONE }, // PTCH_RATE_P
|
{ 5, { 233, 0, 4043 }, AP_OSD_ParamSetting::Type::NONE }, // PTCH_RATE_P
|
||||||
{ 6, { 233, 0, 75 }, OSD_PARAM_NONE }, // PTCH_RATE_I
|
{ 6, { 233, 0, 75 }, AP_OSD_ParamSetting::Type::NONE }, // PTCH_RATE_I
|
||||||
{ 7, { 233, 0, 6 }, OSD_PARAM_NONE }, // PTCH2SRV_RLL
|
{ 7, { 233, 0, 6 }, AP_OSD_ParamSetting::Type::NONE }, // PTCH2SRV_RLL
|
||||||
{ 8, { 199, 0, 1 }, OSD_PARAM_NONE }, // TUNE_PARAM
|
{ 8, { 199, 0, 1 }, AP_OSD_ParamSetting::Type::NONE }, // TUNE_PARAM
|
||||||
{ 9, { 199, 0, 320 }, OSD_PARAM_NONE } // TUNE_RANGE
|
{ 9, { 199, 0, 320 }, AP_OSD_ParamSetting::Type::NONE } // TUNE_RANGE
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
{ 1, { 185, 0, 0 }, OSD_PARAM_NONE }, // TRIM_THROTTLE
|
{ 1, { 185, 0, 0 }, AP_OSD_ParamSetting::Type::NONE }, // TRIM_THROTTLE
|
||||||
{ 2, { 155, 0, 0 }, OSD_PARAM_NONE }, // AIRSPEED_CRUISE
|
{ 2, { 155, 0, 0 }, AP_OSD_ParamSetting::Type::NONE }, // AIRSPEED_CRUISE
|
||||||
{ 3, { 4, 0, 1094 }, OSD_PARAM_NONE }, // SERVO_AUTO_TRIM
|
{ 3, { 4, 0, 1094 }, AP_OSD_ParamSetting::Type::NONE }, // SERVO_AUTO_TRIM
|
||||||
{ 4, { 120, 0, 0 }, OSD_PARAM_NONE}, // AIRSPEED_MIN
|
{ 4, { 120, 0, 0 }, AP_OSD_ParamSetting::Type::NONE}, // AIRSPEED_MIN
|
||||||
{ 5, { 121, 0, 0 }, OSD_PARAM_NONE }, // AIRSPEED_MAX
|
{ 5, { 121, 0, 0 }, AP_OSD_ParamSetting::Type::NONE }, // AIRSPEED_MAX
|
||||||
{ 6, { 156, 0, 0 }, OSD_PARAM_NONE }, // RTL_ALTITUDE
|
{ 6, { 156, 0, 0 }, AP_OSD_ParamSetting::Type::NONE }, // RTL_ALTITUDE
|
||||||
{ 7, { 140, 2, 8 }, OSD_PARAM_NONE }, // AHRS_TRIM_Y
|
{ 7, { 140, 2, 8 }, AP_OSD_ParamSetting::Type::NONE }, // AHRS_TRIM_Y
|
||||||
{ 8, { 182, 0, 0 }, OSD_PARAM_NONE }, // THR_MAX
|
{ 8, { 182, 0, 0 }, AP_OSD_ParamSetting::Type::NONE }, // THR_MAX
|
||||||
{ 9, { 189, 0, 0 }, OSD_PARAM_NONE } // THR_SLEWRATE
|
{ 9, { 189, 0, 0 }, AP_OSD_ParamSetting::Type::NONE } // THR_SLEWRATE
|
||||||
}
|
}
|
||||||
#else
|
#else
|
||||||
{
|
{
|
||||||
|
@ -381,7 +381,7 @@ void AP_OSD_ParamScreen::modify_configured_parameter(uint8_t number, Event ev)
|
||||||
setting._param_key.set(AP_Param::get_persistent_key(setting._current_token.key));
|
setting._param_key.set(AP_Param::get_persistent_key(setting._current_token.key));
|
||||||
setting._param_idx.set(setting._current_token.idx);
|
setting._param_idx.set(setting._current_token.idx);
|
||||||
setting._param = param;
|
setting._param = param;
|
||||||
setting._type.set(OSD_PARAM_NONE);
|
setting._type.set(AP_OSD_ParamSetting::Type::NONE);
|
||||||
// force update() to refresh the token
|
// force update() to refresh the token
|
||||||
setting._current_token.key = 0;
|
setting._current_token.key = 0;
|
||||||
setting._current_token.idx = 0;
|
setting._current_token.idx = 0;
|
||||||
|
@ -636,7 +636,7 @@ void AP_OSD_ParamScreen::handle_read_msg(const mavlink_osd_param_show_config_t&
|
||||||
// request out of range - return an error
|
// request out of range - return an error
|
||||||
if (packet.osd_index < 1 || packet.osd_index > AP_OSD_ParamScreen::NUM_PARAMS) {
|
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,
|
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);
|
nullptr, uint8_t(AP_OSD_ParamSetting::Type::NONE), 0, 0, 0);
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
// get the parameter and make sure it is fresh
|
// get the parameter and make sure it is fresh
|
||||||
|
@ -646,7 +646,7 @@ void AP_OSD_ParamScreen::handle_read_msg(const mavlink_osd_param_show_config_t&
|
||||||
// check for bad things
|
// check for bad things
|
||||||
if (param._param == nullptr) {
|
if (param._param == nullptr) {
|
||||||
mavlink_msg_osd_param_show_config_reply_send(link.get_chan(), packet.request_id, OSD_PARAM_INVALID_PARAMETER_INDEX,
|
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);
|
nullptr, uint8_t(AP_OSD_ParamSetting::Type::NONE), 0, 0, 0);
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
// get the name and send back the details
|
// get the name and send back the details
|
||||||
|
|
|
@ -25,6 +25,7 @@
|
||||||
#include <AP_Vehicle/AP_Vehicle_Type.h>
|
#include <AP_Vehicle/AP_Vehicle_Type.h>
|
||||||
#include <GCS_MAVLink/GCS.h>
|
#include <GCS_MAVLink/GCS.h>
|
||||||
#include <SRV_Channel/SRV_Channel.h>
|
#include <SRV_Channel/SRV_Channel.h>
|
||||||
|
#include <AP_SerialManager/AP_SerialManager.h>
|
||||||
#include <ctype.h>
|
#include <ctype.h>
|
||||||
|
|
||||||
#if OSD_PARAM_ENABLED
|
#if OSD_PARAM_ENABLED
|
||||||
|
@ -99,6 +100,27 @@ const AP_Param::GroupInfo AP_OSD_ParamSetting::var_info[] = {
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
||||||
|
#if HAL_GCS_ENABLED
|
||||||
|
// ensure that our OSD_PARAM type enumeration is 1:1 with the mavlink
|
||||||
|
// numbers. This allows us to do a simple cast from one to the other
|
||||||
|
// when sending mavlink messages, rather than having some sort of
|
||||||
|
// mapping function from our internal enumeration into the mavlink
|
||||||
|
// enumeration. Doing things this way has two advantages - in the
|
||||||
|
// future we could add that mapping function and change our
|
||||||
|
// enumeration, and the other is that it allows us to build the GPS
|
||||||
|
// library without having the mavlink headers built (for example, in
|
||||||
|
// AP_Periph we shouldn't need mavlink headers).
|
||||||
|
static_assert((uint32_t)AP_OSD_ParamSetting::Type::NONE == (uint32_t)OSD_PARAM_NONE, "OSD_PARAM_NONE incorrect");
|
||||||
|
static_assert((uint32_t)AP_OSD_ParamSetting::Type::SERIAL_PROTOCOL == (uint32_t)OSD_PARAM_SERIAL_PROTOCOL, "OSD_PARAM_SERIAL_PROTOCOL incorrect");
|
||||||
|
static_assert((uint32_t)AP_OSD_ParamSetting::Type::SERVO_FUNCTION == (uint32_t)OSD_PARAM_SERVO_FUNCTION, "OSD_PARAM_SERVO_FUNCTION incorrect");
|
||||||
|
static_assert((uint32_t)AP_OSD_ParamSetting::Type::AUX_FUNCTION == (uint32_t)OSD_PARAM_AUX_FUNCTION, "OSD_PARAM_AUX_FUNCTION incorrect");
|
||||||
|
static_assert((uint32_t)AP_OSD_ParamSetting::Type::FLIGHT_MODE == (uint32_t)OSD_PARAM_FLIGHT_MODE, "OSD_PARAM_FLIGHT_MODE incorrect");
|
||||||
|
static_assert((uint32_t)AP_OSD_ParamSetting::Type::FAILSAFE_ACTION == (uint32_t)OSD_PARAM_FAILSAFE_ACTION, "OSD_PARAM_FAILSAFE_ACTION incorrect");
|
||||||
|
static_assert((uint32_t)AP_OSD_ParamSetting::Type::FAILSAFE_ACTION_1 == (uint32_t)OSD_PARAM_FAILSAFE_ACTION_1, "OSD_PARAM_FAILSAFE_ACTION_1 incorrect");
|
||||||
|
static_assert((uint32_t)AP_OSD_ParamSetting::Type::FAILSAFE_ACTION_2 == (uint32_t)OSD_PARAM_FAILSAFE_ACTION_2, "OSD_PARAM_FAILSAFE_ACTION_2 incorrect");
|
||||||
|
static_assert((uint32_t)AP_OSD_ParamSetting::Type::NUM_TYPES == (uint32_t)AP_OSD_ParamSetting::Type::NUM_TYPES, "AP_OSD_ParamSetting::Type::NUM_TYPES incorrect");
|
||||||
|
#endif // HAL_GCS_ENABLED
|
||||||
|
|
||||||
#define PARAM_COMPOSITE_INDEX(key, idx, group) (uint32_t((uint32_t(key) << 23) | (uint32_t(idx) << 18) | uint32_t(group)))
|
#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
|
#define OSD_PARAM_DEBUG 0
|
||||||
|
@ -175,7 +197,7 @@ static const char* FS_LNG_ACTNS[] = {
|
||||||
};
|
};
|
||||||
|
|
||||||
// plane parameters
|
// plane parameters
|
||||||
const AP_OSD_ParamSetting::ParamMetadata AP_OSD_ParamSetting::_param_metadata[OSD_PARAM_NUM_TYPES] = {
|
const AP_OSD_ParamSetting::ParamMetadata AP_OSD_ParamSetting::_param_metadata[unsigned(AP_OSD_ParamSetting::Type::NUM_TYPES)] = {
|
||||||
{ -1, AP_SerialManager::SerialProtocol_NumProtocols - 1, 1, ARRAY_SIZE(SERIAL_PROTOCOL_VALUES), SERIAL_PROTOCOL_VALUES }, // OSD_PARAM_SERIAL_PROTOCOL
|
{ -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, 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, 105, 1, ARRAY_SIZE(AUX_OPTIONS), AUX_OPTIONS }, // OSD_PARAM_AUX_FUNCTION
|
||||||
|
@ -222,7 +244,7 @@ static const char* FS_ACT[] = {
|
||||||
};
|
};
|
||||||
|
|
||||||
// copter parameters
|
// copter parameters
|
||||||
const AP_OSD_ParamSetting::ParamMetadata AP_OSD_ParamSetting::_param_metadata[OSD_PARAM_NUM_TYPES] = {
|
const AP_OSD_ParamSetting::ParamMetadata AP_OSD_ParamSetting::_param_metadata[unsigned(AP_OSD_ParamSetting::Type::NUM_TYPES)] = {
|
||||||
{ -1, AP_SerialManager::SerialProtocol_NumProtocols - 1, 1, ARRAY_SIZE(SERIAL_PROTOCOL_VALUES), SERIAL_PROTOCOL_VALUES }, // OSD_PARAM_SERIAL_PROTOCOL
|
{ -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, 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, 105, 1, ARRAY_SIZE(AUX_OPTIONS), AUX_OPTIONS }, // OSD_PARAM_AUX_FUNCTION
|
||||||
|
@ -233,7 +255,7 @@ const AP_OSD_ParamSetting::ParamMetadata AP_OSD_ParamSetting::_param_metadata[OS
|
||||||
};
|
};
|
||||||
|
|
||||||
#else
|
#else
|
||||||
const AP_OSD_ParamSetting::ParamMetadata AP_OSD_ParamSetting::_param_metadata[OSD_PARAM_NUM_TYPES] = {};
|
const AP_OSD_ParamSetting::ParamMetadata AP_OSD_ParamSetting::_param_metadata[unsigned(AP_OSD_ParamSetting::Type::NUM_TYPES)] = {};
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
@ -257,7 +279,7 @@ AP_OSD_ParamSetting::AP_OSD_ParamSetting(const Initializer& initializer) :
|
||||||
default_param_group(initializer.token.group_element),
|
default_param_group(initializer.token.group_element),
|
||||||
default_param_idx(initializer.token.idx),
|
default_param_idx(initializer.token.idx),
|
||||||
default_param_key(initializer.token.key),
|
default_param_key(initializer.token.key),
|
||||||
default_type(initializer.type)
|
default_type(float(initializer.type))
|
||||||
{
|
{
|
||||||
AP_Param::setup_object_defaults(this, var_info);
|
AP_Param::setup_object_defaults(this, var_info);
|
||||||
}
|
}
|
||||||
|
@ -305,7 +327,7 @@ bool AP_OSD_ParamSetting::set_by_name(const char* name, uint8_t config_type, flo
|
||||||
|
|
||||||
_type.set_and_save_ifchanged(config_type);
|
_type.set_and_save_ifchanged(config_type);
|
||||||
|
|
||||||
if (config_type == OSD_PARAM_NONE && !is_zero(pincr)) {
|
if (config_type == uint8_t(Type::NONE) && !is_zero(pincr)) {
|
||||||
// ranges
|
// ranges
|
||||||
_param_min.set_and_save_ifchanged(pmin);
|
_param_min.set_and_save_ifchanged(pmin);
|
||||||
_param_max.set_and_save_ifchanged(pmax);
|
_param_max.set_and_save_ifchanged(pmax);
|
||||||
|
@ -430,7 +452,7 @@ void AP_OSD_ParamSetting::copy_name_camel_case(char* name, size_t len) const
|
||||||
bool AP_OSD_ParamSetting::set_from_metadata()
|
bool AP_OSD_ParamSetting::set_from_metadata()
|
||||||
{
|
{
|
||||||
// check for statically configured setting metadata
|
// check for statically configured setting metadata
|
||||||
if (_type > 0 && _type < OSD_PARAM_NUM_TYPES && _param_metadata[_type - 1].values_max > 0) {
|
if (_type > 0 && _type < uint8_t(Type::NUM_TYPES) && _param_metadata[_type - 1].values_max > 0) {
|
||||||
_param_incr.set(_param_metadata[_type - 1].increment);
|
_param_incr.set(_param_metadata[_type - 1].increment);
|
||||||
_param_min.set(_param_metadata[_type - 1].min_value);
|
_param_min.set(_param_metadata[_type - 1].min_value);
|
||||||
_param_max.set(_param_metadata[_type - 1].max_value);
|
_param_max.set(_param_metadata[_type - 1].max_value);
|
||||||
|
|
Loading…
Reference in New Issue