From 4b2b88945d04efd6a693d59679a83530ef41db24 Mon Sep 17 00:00:00 2001 From: muramura <ma2maru@gmail.com> Date: Tue, 24 Sep 2024 11:39:24 +0900 Subject: [PATCH] Copter: Set the message buffer size to twice the message size --- ArduCopter/AP_Arming.cpp | 12 ++++++------ ArduCopter/motor_test.cpp | 2 +- 2 files changed, 7 insertions(+), 7 deletions(-) diff --git a/ArduCopter/AP_Arming.cpp b/ArduCopter/AP_Arming.cpp index d585f2108c..e33abf569d 100644 --- a/ArduCopter/AP_Arming.cpp +++ b/ArduCopter/AP_Arming.cpp @@ -44,7 +44,7 @@ bool AP_Arming_Copter::run_pre_arm_checks(bool display_failure) } // always check motors - char failure_msg[50] {}; + char failure_msg[100] {}; if (!copter.motors->arming_checks(ARRAY_SIZE(failure_msg), failure_msg)) { check_failed(display_failure, "Motors: %s", failure_msg); passed = false; @@ -224,7 +224,7 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure) } #if FRAME_CONFIG == HELI_FRAME - char fail_msg[50]; + char fail_msg[100]{}; // check input manager parameters if (!copter.input_manager.parameter_check(fail_msg, ARRAY_SIZE(fail_msg))) { check_failed(ARMING_CHECK_PARAMETERS, display_failure, "%s", fail_msg); @@ -291,7 +291,7 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure) #endif // ensure controllers are OK with us arming: - char failure_msg[50] = {}; + char failure_msg[100] = {}; if (!copter.pos_control->pre_arm_checks("PSC", failure_msg, ARRAY_SIZE(failure_msg))) { check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Bad parameter: %s", failure_msg); return false; @@ -308,7 +308,7 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure) bool AP_Arming_Copter::oa_checks(bool display_failure) { #if AP_OAPATHPLANNER_ENABLED - char failure_msg[50] = {}; + char failure_msg[100] = {}; if (copter.g2.oa.pre_arm_check(failure_msg, ARRAY_SIZE(failure_msg))) { return true; } @@ -439,7 +439,7 @@ bool AP_Arming_Copter::mandatory_gps_checks(bool display_failure) // always check if inertial nav has started and is ready const auto &ahrs = AP::ahrs(); - char failure_msg[50] = {}; + char failure_msg[100] = {}; if (!ahrs.pre_arm_check(mode_requires_gps, failure_msg, sizeof(failure_msg))) { check_failed(display_failure, "AHRS: %s", failure_msg); return false; @@ -528,7 +528,7 @@ bool AP_Arming_Copter::winch_checks(bool display_failure) const if (winch == nullptr) { return true; } - char failure_msg[50] = {}; + char failure_msg[100] = {}; if (!winch->pre_arm_check(failure_msg, sizeof(failure_msg))) { check_failed(display_failure, "%s", failure_msg); return false; diff --git a/ArduCopter/motor_test.cpp b/ArduCopter/motor_test.cpp index 5c5deae899..2313c30953 100644 --- a/ArduCopter/motor_test.cpp +++ b/ArduCopter/motor_test.cpp @@ -102,7 +102,7 @@ bool Copter::mavlink_motor_control_check(const GCS_MAVLINK &gcs_chan, bool check } // Check Motor test is allowed - char failure_msg[50] {}; + char failure_msg[100] {}; if (!motors->motor_test_checks(ARRAY_SIZE(failure_msg), failure_msg)) { gcs_chan.send_text(MAV_SEVERITY_CRITICAL,"%s: %s", mode, failure_msg); return false;