diff --git a/ArduCopter/AP_Arming.cpp b/ArduCopter/AP_Arming.cpp index dc1e165f739ef..189c6f6611b31 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 5c5deae8995cd..2313c30953d5d 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; diff --git a/libraries/AP_Arming/AP_Arming.cpp b/libraries/AP_Arming/AP_Arming.cpp index 76f8159804ec4..9a99c614639d0 100644 --- a/libraries/AP_Arming/AP_Arming.cpp +++ b/libraries/AP_Arming/AP_Arming.cpp @@ -543,7 +543,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; @@ -602,7 +602,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); @@ -1205,7 +1205,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(); @@ -1494,7 +1494,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; @@ -1509,7 +1509,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;