AP_KDECAN: slightly improve pre-arm check messages

This commit is contained in:
Randy Mackay 2021-04-12 14:50:43 +09:00 committed by Andrew Tridgell
parent 09fb9a8e58
commit 6c93039d84
1 changed files with 5 additions and 6 deletions

View File

@ -628,13 +628,12 @@ void AP_KDECAN::update()
bool AP_KDECAN::pre_arm_check(char* reason, uint8_t reason_len)
{
if (!_enum_sem.take(1)) {
debug_can(AP_CANManager::LOG_DEBUG, "failed to get enumeration semaphore on read");
snprintf(reason, reason_len ,"Enumeration state unknown");
snprintf(reason, reason_len ,"enumeration state unknown");
return false;
}
if (_enumeration_state != ENUMERATION_STOPPED) {
snprintf(reason, reason_len ,"Enumeration running");
snprintf(reason, reason_len, "enumeration running");
_enum_sem.give();
return false;
}
@ -652,17 +651,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, "Too few ESCs detected");
snprintf(reason, reason_len, "too few ESCs detected (%u of %u)", (int)num_present_escs, (int)num_expected_motors);
return false;
}
if (num_present_escs > num_expected_motors) {
snprintf(reason, reason_len, "Too many ESCs detected");
snprintf(reason, reason_len, "too many ESCs detected (%u > %u)", (int)num_present_escs, (int)num_expected_motors);
return false;
}
if (_esc_max_node_id != num_expected_motors) {
snprintf(reason, reason_len, "Wrong node IDs, run enumeration");
snprintf(reason, reason_len, "wrong node IDs (%u!=%u), run enumeration", (int)_esc_max_node_id, (int)num_expected_motors);
return false;
}