Skip to content

Commit

Permalink
AP_Arming: Set the message buffer size to twice the message size
Browse files Browse the repository at this point in the history
  • Loading branch information
muramura committed Sep 24, 2024
1 parent 7513c62 commit a45a3c4
Showing 1 changed file with 5 additions and 5 deletions.
10 changes: 5 additions & 5 deletions libraries/AP_Arming/AP_Arming.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -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);
Expand Down Expand Up @@ -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();

Expand Down Expand Up @@ -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;
Expand All @@ -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;
Expand Down

0 comments on commit a45a3c4

Please sign in to comment.