Copter: free allocations in case of allocation failure
[ardupilot.git] / libraries / AP_OSD / AP_OSD_ParamSetting.cpp
blob7ec03159e4c5991a4144c63efc27cc44f016ff03
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/>.
15 * AP_OSD partially based on betaflight and inav osd.c implemention.
16 * clarity.mcm font is taken from inav configurator.
17 * Many thanks to their authors.
21 parameter object for one setting in AP_OSD
24 #include "AP_OSD.h"
25 #include <AP_Vehicle/AP_Vehicle_Type.h>
26 #include <GCS_MAVLink/GCS.h>
27 #include <SRV_Channel/SRV_Channel.h>
28 #include <AP_SerialManager/AP_SerialManager.h>
29 #include <ctype.h>
31 #if OSD_PARAM_ENABLED
33 const AP_Param::GroupInfo AP_OSD_ParamSetting::var_info[] = {
34 // @Param: _EN
35 // @DisplayName: Enable
36 // @Description: Enable setting
37 // @Values: 0:Disabled,1:Enabled
38 // @User: Standard
39 AP_GROUPINFO_FLAGS_DEFAULT_POINTER("_EN", 1, AP_OSD_ParamSetting, enabled, default_enabled),
41 // @Param: _X
42 // @DisplayName: X position
43 // @Description: Horizontal position on screen
44 // @Range: 0 29
45 // @User: Standard
46 AP_GROUPINFO("_X", 2, AP_OSD_ParamSetting, xpos, 2),
48 // @Param: _Y
49 // @DisplayName: Y position
50 // @Description: Vertical position on screen
51 // @Range: 0 15
52 // @User: Standard
53 AP_GROUPINFO_FLAGS_DEFAULT_POINTER("_Y", 3, AP_OSD_ParamSetting, ypos, default_ypos),
55 // Parameter access keys. These default to -1 too allow user overrides
56 // to work properly
58 // @Param: _KEY
59 // @DisplayName: Parameter key
60 // @Description: Key of the parameter to be displayed and modified
61 // @User: Standard
62 AP_GROUPINFO_FLAGS_DEFAULT_POINTER("_KEY", 4, AP_OSD_ParamSetting, _param_key, default_param_key),
64 // @Param: _IDX
65 // @DisplayName: Parameter index
66 // @Description: Index of the parameter to be displayed and modified
67 // @User: Standard
68 AP_GROUPINFO_FLAGS_DEFAULT_POINTER("_IDX", 5, AP_OSD_ParamSetting, _param_idx, default_param_idx),
70 // @Param: _GRP
71 // @DisplayName: Parameter group
72 // @Description: Group of the parameter to be displayed and modified
73 // @User: Standard
74 AP_GROUPINFO_FLAGS_DEFAULT_POINTER("_GRP", 6, AP_OSD_ParamSetting, _param_group, default_param_group),
76 // @Param: _MIN
77 // @DisplayName: Parameter minimum
78 // @Description: Minimum value of the parameter to be displayed and modified
79 // @User: Standard
80 AP_GROUPINFO("_MIN", 7, AP_OSD_ParamSetting, _param_min, 0.0f),
82 // @Param: _MAX
83 // @DisplayName: Parameter maximum
84 // @Description: Maximum of the parameter to be displayed and modified
85 // @User: Standard
86 AP_GROUPINFO("_MAX", 8, AP_OSD_ParamSetting, _param_max, 1.0f),
88 // @Param: _INCR
89 // @DisplayName: Parameter increment
90 // @Description: Increment of the parameter to be displayed and modified
91 // @User: Standard
92 AP_GROUPINFO("_INCR", 9, AP_OSD_ParamSetting, _param_incr, 0.001f),
94 // @Param: _TYPE
95 // @DisplayName: Parameter type
96 // @Description: Type of the parameter to be displayed and modified
97 // @User: Standard
98 AP_GROUPINFO_FLAGS_DEFAULT_POINTER("_TYPE", 10, AP_OSD_ParamSetting, _type, default_type),
100 AP_GROUPEND
103 #if HAL_GCS_ENABLED
104 // ensure that our OSD_PARAM type enumeration is 1:1 with the mavlink
105 // numbers. This allows us to do a simple cast from one to the other
106 // when sending mavlink messages, rather than having some sort of
107 // mapping function from our internal enumeration into the mavlink
108 // enumeration. Doing things this way has two advantages - in the
109 // future we could add that mapping function and change our
110 // enumeration, and the other is that it allows us to build the GPS
111 // library without having the mavlink headers built (for example, in
112 // AP_Periph we shouldn't need mavlink headers).
113 static_assert((uint32_t)AP_OSD_ParamSetting::Type::NONE == (uint32_t)OSD_PARAM_NONE, "OSD_PARAM_NONE incorrect");
114 static_assert((uint32_t)AP_OSD_ParamSetting::Type::SERIAL_PROTOCOL == (uint32_t)OSD_PARAM_SERIAL_PROTOCOL, "OSD_PARAM_SERIAL_PROTOCOL incorrect");
115 static_assert((uint32_t)AP_OSD_ParamSetting::Type::SERVO_FUNCTION == (uint32_t)OSD_PARAM_SERVO_FUNCTION, "OSD_PARAM_SERVO_FUNCTION incorrect");
116 static_assert((uint32_t)AP_OSD_ParamSetting::Type::AUX_FUNCTION == (uint32_t)OSD_PARAM_AUX_FUNCTION, "OSD_PARAM_AUX_FUNCTION incorrect");
117 static_assert((uint32_t)AP_OSD_ParamSetting::Type::FLIGHT_MODE == (uint32_t)OSD_PARAM_FLIGHT_MODE, "OSD_PARAM_FLIGHT_MODE incorrect");
118 static_assert((uint32_t)AP_OSD_ParamSetting::Type::FAILSAFE_ACTION == (uint32_t)OSD_PARAM_FAILSAFE_ACTION, "OSD_PARAM_FAILSAFE_ACTION incorrect");
119 static_assert((uint32_t)AP_OSD_ParamSetting::Type::FAILSAFE_ACTION_1 == (uint32_t)OSD_PARAM_FAILSAFE_ACTION_1, "OSD_PARAM_FAILSAFE_ACTION_1 incorrect");
120 static_assert((uint32_t)AP_OSD_ParamSetting::Type::FAILSAFE_ACTION_2 == (uint32_t)OSD_PARAM_FAILSAFE_ACTION_2, "OSD_PARAM_FAILSAFE_ACTION_2 incorrect");
121 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");
122 #endif // HAL_GCS_ENABLED
124 #define PARAM_COMPOSITE_INDEX(key, idx, group) (uint32_t((uint32_t(key) << 23) | (uint32_t(idx) << 18) | uint32_t(group)))
126 #define OSD_PARAM_DEBUG 0
127 #if OSD_PARAM_DEBUG
128 #define debug(fmt, args ...) do { hal.console->printf("OSD: " fmt, args); } while (0)
129 #else
130 #define debug(fmt, args ...)
131 #endif
133 // at the cost of a little flash, we can create much better ranges and values for certain important settings
134 // common labels - all strings must be upper case
135 #if APM_BUILD_TYPE(APM_BUILD_ArduPlane) || APM_BUILD_COPTER_OR_HELI
137 static const char* SERIAL_PROTOCOL_VALUES[] = {
138 "", "MAV", "MAV2", "FSKY_D", "FSKY_S", "GPS", "", "ALEX", "STORM", "RNG",
139 "FSKY_TX", "LID360", "", "BEACN", "VOLZ", "SBUS", "ESC_TLM", "DEV_TLM", "OPTFLW", "RBTSRV",
140 "NMEA", "WNDVNE", "SLCAN", "RCIN", "MGSQRT", "LTM", "RUNCAM", "HOT_TLM", "SCRIPT", "CRSF",
141 "GEN", "WNCH", "MSP", "DJI", "AIRSPD", "ADSB", "AHRS", "AUDIO", "FETTEC", "TORQ",
142 "AIS", "CD_ESC", "MSP_DP", "MAV_HL", "TRAMP", "DDS", "IMUOUT", "IQ", "PPP", "IBUS_TLM"
144 static_assert(AP_SerialManager::SerialProtocol_NumProtocols == ARRAY_SIZE(SERIAL_PROTOCOL_VALUES), "Wrong size SerialProtocol_NumProtocols");
146 static const char* SERVO_FUNCTIONS[] = {
147 "NONE", "RCPASS", "FLAP", "FLAP_AUTO", "AIL", "", "MNT_PAN", "MNT_TLT", "MNT_RLL", "MNT_OPEN",
148 "CAM_TRG", "", "MNT2_PAN", "MNT2_TLT", "MNT2_RLL", "MNT2_OPEN", "DIF_SPL_L1", "DIF_SPL_R1", "", "ELE",
149 "", "RUD", "SPR_PMP", "SPR_SPIN", "FLPRON_L", "FLPRON_R", "GRND_STEER", "PARACHT", "GRIP", "GEAR",
150 "ENG_RUN_EN", "HELI_RSC", "HELI_TAIL_RSC", "MOT_1", "MOT_2", "MOT_3", "MOT_4", "MOT_5", "MOT_6", "MOT_7",
151 "MOT_8", "MOT_TLT", "", "", "", "", "", "", "", "",
152 "", "RCIN_1", "RCIN_2", "RCIN_3", "RCIN_4", "RCIN_5", "RCIN_6", "RCIN_7", "RCIN_8", "RCIN_9",
153 "RCIN_10", "RCIN_11", "RCIN_12", "RCIN_13", "RCIN_14", "RCIN_15", "RCIN_16", "IGN", "", "START",
154 "THR", "TRCK_YAW", "TRCK_PIT", "THR_L", "THR_R", "TLTMOT_L", "TLTMOT_R", "ELEVN_L", "ELEVN_R", "VTAIL_L",
155 "VTAIL_R", "BOOST_THR", "MOT_9", "MOT_10", "MOT_11", "MOT_12", "DIF_SPL_L2", "DIF_SPL_R2", "", "MAIN_SAIL",
156 "CAM_ISO", "CAM_APTR", "CAM_FOC", "CAM_SH_SPD", "SCRPT_1", "SCRPT_2", "SCRPT_3", "SCRPT_4", "SCRPT_5", "SCRPT_6",
157 "SCRPT_7", "SCRPT_8", "SCRPT_9", "SCRPT_10", "SCRPT_11", "SCRPT_12", "SCRPT_13", "SCRPT_14", "SCRPT_15", "SCRPT_16",
158 "", "", "", "", "", "", "", "", "", "",
159 "NEOPX_1", "NEOPX_2", "NEOPX_3", "NEOPX_4", "RAT_RLL", "RAT_PIT","RAT_THRST", "RAT_YAW", "WSAIL_EL", "PRLED_1",
160 "PRLED_2", "PRLED_3", "PRLED_CLK", "WNCH_CL"
163 #endif
165 #if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
167 static const char* AUX_OPTIONS[] = {
168 "NONE", "", "", "", "RTL", "", "", "", "", "CAM_TRG",
169 "", "", "", "", "", "", "AUTO", "", "", "",
170 "", "", "", "", "MIS_RST", "", "", "", "RLY", "LAND_GR",
171 "LOST_SND", "M_ESTOP", "", "", "", "RLY3", "RLY4", "", "OA_ADSB", "",
172 "", "ARM/DS", "", "INVERT", "", "", "RC_OVRD", "", "", "",
173 "", "MANUAL", "", "", "", "GUIDE", "LOIT", "", "CLR_WP", "",
174 "", "", "COMP_LRN", "", "REV_THR", "GPS_DIS", "RLY5", "RLY6", "", "",
175 "", "", "CIRCLE", "", "", "", "", "TAKEOFF", "RCAM_CTL", "RCAM_OSD",
176 "", "DSARM", "QASS3POS", "", "AIR", "GEN", "TER_AUTO", "CROW_SEL", "SOAR", "",
177 "", "", "", "", "", "", "", "", "", "",
178 "KILLIMU1", "KILLIMU2", "CAM_TOG", "", "", "GPSYAW_DIS"
181 static const char* FLTMODES[] = {
182 "MAN", "CIRC", "STAB", "TRAIN", "ACRO", "FBWA", "FBWB", "CRUISE", "ATUNE", "", "AUTO",
183 "RTL", "LOIT", "TKOF", "ADSB", "GUID", "", "QSTAB", "QHOV", "QLOIT", "QLAND",
184 "QRTL", "QTUNE", "QACRO", "THRML", "L2QLND"
187 static const char* FS_ACT[] = {
188 "NONE", "RTL", "LAND", "TERM", "QLAND", "PARA"
191 static const char* FS_SHRT_ACTNS[] = {
192 "CRC_NOCHNGE", "CIRC", "FBWA", "DSABLE"
195 static const char* FS_LNG_ACTNS[] = {
196 "CNTNUE", "RTL", "GLIDE", "PARACHT"
199 // plane parameters
200 const AP_OSD_ParamSetting::ParamMetadata AP_OSD_ParamSetting::_param_metadata[unsigned(AP_OSD_ParamSetting::Type::NUM_TYPES)] = {
201 { -1, AP_SerialManager::SerialProtocol_NumProtocols - 1, 1, ARRAY_SIZE(SERIAL_PROTOCOL_VALUES), SERIAL_PROTOCOL_VALUES }, // OSD_PARAM_SERIAL_PROTOCOL
202 { 0, SRV_Channel::k_nr_aux_servo_functions - 1, 1, ARRAY_SIZE(SERVO_FUNCTIONS), SERVO_FUNCTIONS }, // OSD_PARAM_SERVO_FUNCTION
203 { 0, 105, 1, ARRAY_SIZE(AUX_OPTIONS), AUX_OPTIONS }, // OSD_PARAM_AUX_FUNCTION
204 { 0, 25, 1, ARRAY_SIZE(FLTMODES), FLTMODES }, // OSD_PARAM_FLIGHT_MODE
205 { 0, 5, 1, ARRAY_SIZE(FS_ACT), FS_ACT }, // OSD_PARAM_FAILSAFE_ACTION
206 { 0, 3, 1, ARRAY_SIZE(FS_SHRT_ACTNS), FS_SHRT_ACTNS }, // OSD_PARAM_FAILSAFE_ACTION_1
207 { 0, 3, 1, ARRAY_SIZE(FS_LNG_ACTNS), FS_LNG_ACTNS }, // OSD_PARAM_FAILSAFE_ACTION_2
210 #elif APM_BUILD_COPTER_OR_HELI
212 static const char* AUX_OPTIONS[] = {
213 "NONE", "", "FLIP", "SIMP", "RTL", "SAV_TRM", "", "SAV_WP", "", "CAM_TRG",
214 "RNG", "FENCE", "", "SSIMP", "ACRO_TRN", "SPRAY", "AUTO", "AUTOTN", "LAND", "GRIP",
215 "", "CHUTE_EN", "CHUTE_RL", "CHUTE_3P", "MIS_RST", "ATT_FF", "ATT_ACC", "RET_MNT", "RLY", "LAND_GR",
216 "LOST_SND", "M_ESTOP", "M_ILOCK", "BRAKE", "RLY2", "RLY3", "RLY4", "THROW", "OA_ADSB", "PR_LOIT",
217 "OA_PROX", "ARM/DS", "SMRT_RTL", "INVERT", "", "", "RC_OVRD", "USR1", "USR2", "USR3",
218 "", "", "ACRO", "", "", "GUIDE", "LOIT", "FOLLOW", "CLR_WP", "",
219 "ZZAG", "ZZ_SVWP", "COMP_LRN", "", "", "GPS_DIS", "RLY5", "RLY6", "STAB", "PHOLD",
220 "AHOLD", "FHOLD", "CIRCLE", "DRIFT", "", "", "STANDBY", "", "RCAM_CTL", "RCAM_OSD",
221 "VISO_CAL", "DISARM", "", "ZZ_Auto", "AIR", "", "", "", "", "",
222 "", "", "", "", "", "", "", "", "", "",
223 "KILLIMU1", "KILLIMU2", "CAM_MOD_TOG", "", "", "GPSYAW_DIS"
226 static const char* FLTMODES[] = {
227 "STAB", "ACRO", "ALTHOLD", "AUTO", "GUIDED", "LOIT", "RTL", "CIRC", "", "LAND",
228 "", "DRFT", "", "SPORT", "FLIP", "ATUN", "POSHLD", "BRAKE", "THROW", "AVD_ADSB",
229 "GUID_NOGPS", "SMRTRTL", "FLOHOLD", "FOLLOW", "ZIGZAG", "SYSID", "HELI_ARO", "AUTORTL",
230 "TRTLE"
233 static const char* FS_OPTIONS[] = {
234 "NONE", "CONT_RCFS", "CONT_GCSFS", "CONT_RC/GCSFS", "CONT_GUID_RC", "", "", "", "CONT_LAND", "",
235 "", "", "", "", "", "CONT_CTRL_GCS", "", "", "CONTNUE"
238 static const char* THR_FS_ACT[] = {
239 "NONE", "RTL", "CONT", "LAND", "SRTL_RTL", "SRTL_LAND"
242 static const char* FS_ACT[] = {
243 "NONE", "LAND", "RTL", "SRTL_RTL", "SRTL_LAND", "TERM"
246 // copter parameters
247 const AP_OSD_ParamSetting::ParamMetadata AP_OSD_ParamSetting::_param_metadata[unsigned(AP_OSD_ParamSetting::Type::NUM_TYPES)] = {
248 { -1, AP_SerialManager::SerialProtocol_NumProtocols - 1, 1, ARRAY_SIZE(SERIAL_PROTOCOL_VALUES), SERIAL_PROTOCOL_VALUES }, // OSD_PARAM_SERIAL_PROTOCOL
249 { 0, SRV_Channel::k_nr_aux_servo_functions - 1, 1, ARRAY_SIZE(SERVO_FUNCTIONS), SERVO_FUNCTIONS }, // OSD_PARAM_SERVO_FUNCTION
250 { 0, 105, 1, ARRAY_SIZE(AUX_OPTIONS), AUX_OPTIONS }, // OSD_PARAM_AUX_FUNCTION
251 { 0, 28, 1, ARRAY_SIZE(FLTMODES), FLTMODES }, // OSD_PARAM_FLIGHT_MODE
252 { 0, 3, 1, ARRAY_SIZE(FS_OPTIONS), FS_OPTIONS }, // OSD_PARAM_FAILSAFE_ACTION
253 { 0, 5, 1, ARRAY_SIZE(FS_ACT), FS_ACT }, // OSD_PARAM_FAILSAFE_ACTION_1
254 { 0, 5, 1, ARRAY_SIZE(THR_FS_ACT), THR_FS_ACT }, // OSD_PARAM_FAILSAFE_ACTION_2
257 #else
258 const AP_OSD_ParamSetting::ParamMetadata AP_OSD_ParamSetting::_param_metadata[unsigned(AP_OSD_ParamSetting::Type::NUM_TYPES)] = {};
259 #endif
261 extern const AP_HAL::HAL& hal;
263 // default constructor that just sets some sensible defaults that exist on all platforms
264 AP_OSD_ParamSetting::AP_OSD_ParamSetting(uint8_t param_number) :
265 _param_number(param_number),
266 default_ypos(param_number + 1),
267 default_param_group(-1),
268 default_param_idx(-1),
269 default_param_key(-1)
271 AP_Param::setup_object_defaults(this, var_info);
274 // construct a setting from a compact static initializer structure
275 AP_OSD_ParamSetting::AP_OSD_ParamSetting(const Initializer& initializer) :
276 _param_number(initializer.index),
277 default_enabled(true),
278 default_ypos(initializer.index + 1),
279 default_param_group(initializer.token.group_element),
280 default_param_idx(initializer.token.idx),
281 default_param_key(initializer.token.key),
282 default_type(float(initializer.type))
284 AP_Param::setup_object_defaults(this, var_info);
287 // update the contained parameter
288 void AP_OSD_ParamSetting::update()
290 // if the user has not made any changes then skip the update
291 if (PARAM_TOKEN_INDEX(_current_token) == PARAM_COMPOSITE_INDEX(_param_key, _param_idx, _param_group) && _param_key >= 0) {
292 return;
294 // if a parameter was configured then use that
295 _current_token = AP_Param::ParamToken {};
296 // surely there is a more efficient way than brute-force search
297 for (_param = AP_Param::first(&_current_token, &_param_type);
298 _param && (AP_Param::get_persistent_key(_current_token.key) != uint16_t(_param_key.get())
299 || _current_token.idx != uint8_t(_param_idx.get())
300 || _current_token.group_element != uint32_t(_param_group.get()));
301 _param = AP_Param::next_scalar(&_current_token, &_param_type)) {
304 if (_param == nullptr) {
305 enabled.set(false);
306 } else {
307 guess_ranges();
311 // update parameter settings from the named parameter
312 bool AP_OSD_ParamSetting::set_by_name(const char* name, uint8_t config_type, float pmin, float pmax, float pincr)
314 AP_Param::ParamToken token = AP_Param::ParamToken {};
315 ap_var_type type;
316 AP_Param* param = AP_Param::find_by_name(name, &type, &token);
318 if (param == nullptr) {
319 // leave unchanged
320 return false;
321 } else {
322 _current_token = token;
323 _param_type = type;
324 _param = param;
325 enabled.set_and_save_ifchanged(true);
328 _type.set_and_save_ifchanged(config_type);
330 if (config_type == uint8_t(Type::NONE) && !is_zero(pincr)) {
331 // ranges
332 _param_min.set_and_save_ifchanged(pmin);
333 _param_max.set_and_save_ifchanged(pmax);
334 _param_incr.set_and_save_ifchanged(pincr);
335 } else {
336 guess_ranges(true);
339 _param_key.set_and_save_ifchanged(AP_Param::get_persistent_key(_current_token.key));
340 _param_idx.set_and_save_ifchanged(_current_token.idx);
341 _param_group.set_and_save_ifchanged(_current_token.group_element);
342 return true;
345 // guess the ranges and increment for the selected parameter
346 // only called when a change has been made
347 void AP_OSD_ParamSetting::guess_ranges(bool force)
349 if (_param->is_read_only()) {
350 return;
353 // check for statically configured setting metadata
354 if (set_from_metadata()) {
355 return;
358 // nothing statically configured so guess some appropriate values
359 float min = -1, max = 127, incr = 1;
361 if (_param != nullptr) {
362 switch (_param_type) {
363 case AP_PARAM_INT8:
364 break;
365 case AP_PARAM_INT16: {
366 AP_Int16* p = (AP_Int16*)_param;
367 min = -1;
368 uint8_t digits = 0;
369 for (int16_t int16p = p->get(); int16p > 0; int16p /= 10) {
370 digits++;
372 incr = MAX(1, powf(10, digits - 2));
373 max = powf(10, digits + 1);
374 debug("Guessing range for value %d as %f -> %f, %f\n", p->get(), min, max, incr);
375 break;
377 case AP_PARAM_INT32: {
378 AP_Int32* p = (AP_Int32*)_param;
379 min = -1;
380 uint8_t digits = 0;
381 for (int32_t int32p = p->get(); int32p > 0; int32p /= 10) {
382 digits++;
384 incr = MAX(1, powf(10, digits - 2));
385 max = powf(10, digits + 1);
386 debug("Guessing range for value %d as %f -> %f, %f\n", int(p->get()), min, max, incr);
387 break;
389 case AP_PARAM_FLOAT: {
390 AP_Float* p = (AP_Float*)_param;
392 uint8_t digits = 0;
393 for (float floatp = p->get(); floatp > 1.0f; floatp /= 10) {
394 digits++;
396 float floatp = p->get();
397 if (digits < 1) {
398 if (!is_zero(floatp)) {
399 incr = floatp * 0.01f; // move in 1% increments
400 } else {
401 incr = 0.01f; // move in absolute 1% increments
403 max = 1.0;
404 min = 0.0f;
405 } else {
406 if (!is_zero(floatp)) {
407 incr = floatp * 0.01f; // move in 1% increments
408 } else {
409 incr = MAX(1, powf(10, digits - 2));
411 max = powf(10, digits + 1);
412 min = 0.0f;
414 debug("Guessing range for value %f as %f -> %f, %f\n", p->get(), min, max, incr);
415 break;
417 case AP_PARAM_VECTOR3F:
418 case AP_PARAM_NONE:
419 case AP_PARAM_GROUP:
420 break;
423 if (force || !_param_min.configured()) {
424 _param_min.set(min);
426 if (force || !_param_max.configured()) {
427 _param_max.set(max);
429 if (force || !_param_incr.configured()) {
430 _param_incr.set(incr);
435 // copy the name converting FOO_BAR_BAZ to FooBarBaz
436 void AP_OSD_ParamSetting::copy_name_camel_case(char* name, size_t len) const
438 char buf[17];
439 _param->copy_name_token(_current_token, buf, 17);
440 buf[16] = 0;
441 name[0] = buf[0];
442 for (uint8_t i = 1, n = 1; i < len; i++, n++) {
443 if (buf[i] == '_') {
444 name[n] = buf[i+1];
445 i++;
446 } else {
447 name[n] = tolower(buf[i]);
452 bool AP_OSD_ParamSetting::set_from_metadata()
454 // check for statically configured setting metadata
455 if (_type > 0 && _type < uint8_t(Type::NUM_TYPES) && _param_metadata[_type - 1].values_max > 0) {
456 _param_incr.set(_param_metadata[_type - 1].increment);
457 _param_min.set(_param_metadata[_type - 1].min_value);
458 _param_max.set(_param_metadata[_type - 1].max_value);
459 return true;
461 return false;
464 // modify the selected parameter values
465 void AP_OSD_ParamSetting::save_as_new()
467 _param_group.save();
468 _param_key.save();
469 _param_idx.save();
470 // the user has configured the range and increment, but the parameter
471 // is no longer valid so reset these to guessed values
472 guess_ranges(true);
473 if (_param_min.configured()) {
474 _param_min.save();
476 if (_param_max.configured()) {
477 _param_max.save();
479 if (_param_incr.configured()) {
480 _param_incr.save();
484 #endif // OSD_PARAM_ENABLED