From fcab0c70a2eac67706ddf44fbfccd174dc6568c7 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Wed, 27 Jul 2022 18:23:08 +0100 Subject: [PATCH] AP_Param: allow init of all Vector3f values to single float --- libraries/AP_Param/AP_Param.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/libraries/AP_Param/AP_Param.cpp b/libraries/AP_Param/AP_Param.cpp index dc6a609519..7952f5bf72 100644 --- a/libraries/AP_Param/AP_Param.cpp +++ b/libraries/AP_Param/AP_Param.cpp @@ -1461,6 +1461,11 @@ void AP_Param::setup_object_defaults(const void *object_pointer, const struct Gr void *ptr = (void *)(base + group_info[i].offset); set_value((enum ap_var_type)type, ptr, get_default_value((const AP_Param *)ptr, &group_info[i].def_value)); + } else if (type == AP_PARAM_VECTOR3F) { + // Single default for all components + void *ptr = (void *)(base + group_info[i].offset); + const float default_val = get_default_value((const AP_Param *)ptr, &group_info[i].def_value); + ((AP_Vector3f *)ptr)->set(Vector3f{default_val, default_val, default_val}); } } }