diff --git a/libraries/AP_KDECAN/AP_KDECAN.cpp b/libraries/AP_KDECAN/AP_KDECAN.cpp index cdddc1a823..3ee0f75e67 100644 --- a/libraries/AP_KDECAN/AP_KDECAN.cpp +++ b/libraries/AP_KDECAN/AP_KDECAN.cpp @@ -642,12 +642,12 @@ bool AP_KDECAN::pre_arm_check(char* reason, uint8_t reason_len) { if (!_enum_sem.take(1)) { debug_can(2, "KDECAN: failed to get enumeration semaphore on read\n\r"); - snprintf(reason, reason_len ,"KDECAN enumeration state unknown"); + snprintf(reason, reason_len ,"Enumeration state unknown"); return false; } if (_enumeration_state != ENUMERATION_STOPPED) { - snprintf(reason, reason_len ,"KDECAN enumeration running"); + snprintf(reason, reason_len ,"Enumeration running"); _enum_sem.give(); return false; } @@ -665,17 +665,17 @@ bool AP_KDECAN::pre_arm_check(char* reason, uint8_t reason_len) uint8_t num_present_escs = __builtin_popcount(_esc_present_bitmask); if (num_present_escs < num_expected_motors) { - snprintf(reason, reason_len ,"Not enough KDECAN ESCs detected"); + snprintf(reason, reason_len, "Too few ESCs detected"); return false; } if (num_present_escs > num_expected_motors) { - snprintf(reason, reason_len ,"Too many KDECAN ESCs detected"); + snprintf(reason, reason_len, "Too many ESCs detected"); return false; } if (_esc_max_node_id != num_expected_motors) { - snprintf(reason, reason_len ,"Wrong KDECAN node IDs, run enumeration"); + snprintf(reason, reason_len, "Wrong node IDs, run enumeration"); return false; }