Skip to content

Commit

Permalink
Copter: Change the initialization of the string buffer
Browse files Browse the repository at this point in the history
  • Loading branch information
muramura committed Jun 24, 2024
1 parent 5ab2aaf commit 6be9e80
Showing 1 changed file with 10 additions and 5 deletions.
15 changes: 10 additions & 5 deletions ArduCopter/AP_Arming.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,8 @@ bool AP_Arming_Copter::run_pre_arm_checks(bool display_failure)
}

// always check motors
char failure_msg[50] {};
char failure_msg[50];
failure_msg[0] = 0;
if (!copter.motors->arming_checks(ARRAY_SIZE(failure_msg), failure_msg)) {
check_failed(display_failure, "Motors: %s", failure_msg);
passed = false;
Expand Down Expand Up @@ -283,7 +284,8 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure)
#endif

// ensure controllers are OK with us arming:
char failure_msg[50] = {};
char failure_msg[50];
failure_msg[0] = 0;
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;
Expand All @@ -300,7 +302,8 @@ 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[50];
failure_msg[0] = 0;
if (copter.g2.oa.pre_arm_check(failure_msg, ARRAY_SIZE(failure_msg))) {
return true;
}
Expand Down Expand Up @@ -431,7 +434,8 @@ 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[50];
failure_msg[0] = 0;
if (!ahrs.pre_arm_check(mode_requires_gps, failure_msg, sizeof(failure_msg))) {
check_failed(display_failure, "AHRS: %s", failure_msg);
return false;
Expand Down Expand Up @@ -520,7 +524,8 @@ bool AP_Arming_Copter::winch_checks(bool display_failure) const
if (winch == nullptr) {
return true;
}
char failure_msg[50] = {};
char failure_msg[50];
failure_msg[0] = 0;
if (!winch->pre_arm_check(failure_msg, sizeof(failure_msg))) {
check_failed(display_failure, "%s", failure_msg);
return false;
Expand Down

0 comments on commit 6be9e80

Please sign in to comment.