mirror of https://github.com/ArduPilot/ardupilot
AP_PiccoloCAN: regularise CAN pre-arm failure messages
AP_Arming tacks on the sub-system bit. Remove PiccoloCAN's silly nullptr check Require the library to supply the failure message (no default message) Remove default cases so authors know to think about places they should add things.
This commit is contained in:
parent
a6246a6afa
commit
245b962d92
|
@ -536,14 +536,14 @@ bool AP_PiccoloCAN::pre_arm_check(char* reason, uint8_t reason_len)
|
|||
if (SRV_Channels::function_assigned(motor_function)) {
|
||||
|
||||
if (!is_esc_present(ii)) {
|
||||
snprintf(reason, reason_len, "PiccoloCAN: ESC %u not detected", ii + 1);
|
||||
snprintf(reason, reason_len, "ESC %u not detected", ii + 1);
|
||||
return false;
|
||||
}
|
||||
|
||||
PiccoloESC_Info_t &esc = _esc_info[ii];
|
||||
|
||||
if (esc.statusA.status.hwInhibit) {
|
||||
snprintf(reason, reason_len, "PiccoloCAN: ESC %u is hardware inhibited", (ii + 1));
|
||||
snprintf(reason, reason_len, "ESC %u is hardware inhibited", (ii + 1));
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue