From 45887592fc697266babadc52191e14d6ba068788 Mon Sep 17 00:00:00 2001 From: muramura Date: Tue, 25 Jun 2024 07:00:03 +0900 Subject: [PATCH] AP_Arming: Change the initialization of the string buffer --- libraries/AP_Arming/AP_Arming.cpp | 15 ++++++++++----- 1 file changed, 10 insertions(+), 5 deletions(-) diff --git a/libraries/AP_Arming/AP_Arming.cpp b/libraries/AP_Arming/AP_Arming.cpp index dabe449715d5dc..a675c3905a0c49 100644 --- a/libraries/AP_Arming/AP_Arming.cpp +++ b/libraries/AP_Arming/AP_Arming.cpp @@ -543,7 +543,8 @@ bool AP_Arming::compass_checks(bool report) if (!_compass.learn_offsets_enabled()) #endif { - char failure_msg[50] = {}; + char failure_msg[50]; + failure_msg[0] = 0; if (!_compass.configured(failure_msg, ARRAY_SIZE(failure_msg))) { check_failed(ARMING_CHECK_COMPASS, report, "%s", failure_msg); return false; @@ -602,7 +603,8 @@ bool AP_Arming::gps_checks(bool report) if (check_enabled(ARMING_CHECK_GPS)) { // Any failure messages from GPS backends - char failure_msg[50] = {}; + char failure_msg[50]; + failure_msg[0] = 0; if (!AP::gps().backends_healthy(failure_msg, ARRAY_SIZE(failure_msg))) { if (failure_msg[0] != '\0') { check_failed(ARMING_CHECK_GPS, report, "%s", failure_msg); @@ -1209,7 +1211,8 @@ bool AP_Arming::proximity_checks(bool report) const bool AP_Arming::can_checks(bool report) { if (check_enabled(ARMING_CHECK_SYSTEM)) { - char fail_msg[50] = {}; + char fail_msg[50]; + fail_msg[0] = 0; (void)fail_msg; // might be left unused uint8_t num_drivers = AP::can().get_num_drivers(); @@ -1502,7 +1505,8 @@ bool AP_Arming::generator_checks(bool display_failure) const if (generator == nullptr) { return true; } - char failure_msg[50] = {}; + char failure_msg[50]; + failure_msg[0] = 0; if (!generator->pre_arm_check(failure_msg, sizeof(failure_msg))) { check_failed(display_failure, "Generator: %s", failure_msg); return false; @@ -1517,7 +1521,8 @@ bool AP_Arming::opendroneid_checks(bool display_failure) { auto &opendroneid = AP::opendroneid(); - char failure_msg[50] {}; + char failure_msg[50]; + failure_msg[0] = 0; if (!opendroneid.pre_arm_check(failure_msg, sizeof(failure_msg))) { check_failed(display_failure, "OpenDroneID: %s", failure_msg); return false;