From 4c2925d693e6133b29e0fb76f267b1c334f2cace Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 29 Mar 2018 10:57:17 +1100 Subject: [PATCH] AP_Compass: remove pointless initialisations If you are allocating one of these on the stack you're doing something wrong. --- libraries/AP_Compass/AP_Compass.cpp | 20 +------------------- libraries/AP_Compass/AP_Compass.h | 2 +- 2 files changed, 2 insertions(+), 20 deletions(-) diff --git a/libraries/AP_Compass/AP_Compass.cpp b/libraries/AP_Compass/AP_Compass.cpp index e096aa5cca..7d4e48e158 100644 --- a/libraries/AP_Compass/AP_Compass.cpp +++ b/libraries/AP_Compass/AP_Compass.cpp @@ -451,16 +451,7 @@ const AP_Param::GroupInfo Compass::var_info[] = { // Note that the Vector/Matrix constructors already implicitly zero // their values. // -Compass::Compass(void) : - _compass_cal_autoreboot(false), - _cal_complete_requires_reboot(false), - _cal_has_run(false), - _backend_count(0), - _compass_count(0), - _board_orientation(ROTATION_NONE), - _custom_rotation(nullptr), - _null_init_done(false), - _hil_mode(false) +Compass::Compass(void) { if (_singleton != nullptr) { #if CONFIG_HAL_BOARD == HAL_BOARD_SITL @@ -470,15 +461,6 @@ Compass::Compass(void) : } _singleton = this; AP_Param::setup_object_defaults(this, var_info); - for (uint8_t i=0; i