From 13a5dc8f71f9a25e6640f4a20d25cdfd0691eec0 Mon Sep 17 00:00:00 2001 From: muramura Date: Tue, 24 Sep 2024 11:39:57 +0900 Subject: [PATCH] AP_Arming: Set the message buffer size to twice the message size --- libraries/AP_Arming/AP_Arming.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/libraries/AP_Arming/AP_Arming.cpp b/libraries/AP_Arming/AP_Arming.cpp index a606a8be35202..69425e9b2b604 100644 --- a/libraries/AP_Arming/AP_Arming.cpp +++ b/libraries/AP_Arming/AP_Arming.cpp @@ -542,7 +542,7 @@ bool AP_Arming::compass_checks(bool report) if (!_compass.learn_offsets_enabled()) #endif { - char failure_msg[50] = {}; + char failure_msg[100] = {}; if (!_compass.configured(failure_msg, ARRAY_SIZE(failure_msg))) { check_failed(ARMING_CHECK_COMPASS, report, "%s", failure_msg); return false; @@ -601,7 +601,7 @@ 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[100] = {}; if (!AP::gps().pre_arm_checks(failure_msg, ARRAY_SIZE(failure_msg))) { if (failure_msg[0] != '\0') { check_failed(ARMING_CHECK_GPS, report, "%s", failure_msg); @@ -1204,7 +1204,7 @@ 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[100] = {}; (void)fail_msg; // might be left unused uint8_t num_drivers = AP::can().get_num_drivers(); @@ -1493,7 +1493,7 @@ bool AP_Arming::generator_checks(bool display_failure) const if (generator == nullptr) { return true; } - char failure_msg[50] = {}; + char failure_msg[100] = {}; if (!generator->pre_arm_check(failure_msg, sizeof(failure_msg))) { check_failed(display_failure, "Generator: %s", failure_msg); return false; @@ -1508,7 +1508,7 @@ bool AP_Arming::opendroneid_checks(bool display_failure) { auto &opendroneid = AP::opendroneid(); - char failure_msg[50] {}; + char failure_msg[100] {}; if (!opendroneid.pre_arm_check(failure_msg, sizeof(failure_msg))) { check_failed(display_failure, "OpenDroneID: %s", failure_msg); return false;