diff --git a/libraries/AP_Torqeedo/AP_Torqeedo.cpp b/libraries/AP_Torqeedo/AP_Torqeedo.cpp index c1fee80274..19da31067a 100644 --- a/libraries/AP_Torqeedo/AP_Torqeedo.cpp +++ b/libraries/AP_Torqeedo/AP_Torqeedo.cpp @@ -283,6 +283,50 @@ bool AP_Torqeedo::pre_arm_checks(char *failure_msg, uint8_t failure_msg_len) return true; } +// returns a human-readable string corresponding the the passed-in +// master error code (see page 93 of https://media.torqeedo.com/downloads/manuals/torqeedo-Travel-manual-DE-EN.pdf) +// If no conversion is available then nullptr is returned +const char * AP_Torqeedo::map_master_error_code_to_string(uint8_t code) const +{ + switch (code) { + case 2: + return "stator high temp"; + case 5: + return "propeller blocked"; + case 6: + return "motor low voltage"; + case 7: + return "motor high current"; + case 8: + return "pcb temp high"; + case 21: + return "tiller cal bad"; + case 22: + return "mag bad"; + case 23: + return "range incorrect"; + case 30: + return "motor comm error"; + case 32: + return "tiller comm error"; + case 33: + return "general comm error"; + case 41: + case 42: + return "charge voltage bad"; + case 43: + return "battery flat"; + case 45: + return "battery high current"; + case 46: + return "battery temp error"; + case 48: + return "charging temp error"; + } + + return nullptr; +} + // report changes in error codes to user void AP_Torqeedo::report_error_codes() { @@ -310,62 +354,19 @@ void AP_Torqeedo::report_error_codes() gcs().send_text(MAV_SEVERITY_CRITICAL, "%s batt nearly empty", msg_prefix); } if (_display_system_state.master_error_code > 0) { - char master_err_str_buff[22] = {}; - switch (_display_system_state.master_error_code) { - case 2: - strncpy(master_err_str_buff, "stator high temp", ARRAY_SIZE(master_err_str_buff)); - break; - case 5: - strncpy(master_err_str_buff, "propeller blocked", ARRAY_SIZE(master_err_str_buff)); - break; - case 6: - strncpy(master_err_str_buff, "motor low voltage", ARRAY_SIZE(master_err_str_buff)); - break; - case 7: - strncpy(master_err_str_buff, "motor high current", ARRAY_SIZE(master_err_str_buff)); - break; - case 8: - strncpy(master_err_str_buff, "pcb temp high", ARRAY_SIZE(master_err_str_buff)); - break; - case 21: - strncpy(master_err_str_buff, "tiller cal bad", ARRAY_SIZE(master_err_str_buff)); - break; - case 22: - strncpy(master_err_str_buff, "mag bad", ARRAY_SIZE(master_err_str_buff)); - break; - case 23: - strncpy(master_err_str_buff, "range incorrect", ARRAY_SIZE(master_err_str_buff)); - break; - case 30: - strncpy(master_err_str_buff, "motor comm error", ARRAY_SIZE(master_err_str_buff)); - break; - case 32: - strncpy(master_err_str_buff, "tiller comm error", ARRAY_SIZE(master_err_str_buff)); - break; - case 33: - strncpy(master_err_str_buff, "general comm error", ARRAY_SIZE(master_err_str_buff)); - break; - case 41: - case 42: - strncpy(master_err_str_buff, "charge voltage bad", ARRAY_SIZE(master_err_str_buff)); - break; - case 43: - strncpy(master_err_str_buff, "battery flat", ARRAY_SIZE(master_err_str_buff)); - break; - case 45: - strncpy(master_err_str_buff, "battery high current", ARRAY_SIZE(master_err_str_buff)); - break; - case 46: - strncpy(master_err_str_buff, "battery temp error", ARRAY_SIZE(master_err_str_buff)); - break; - case 48: - strncpy(master_err_str_buff, "charging temp error", ARRAY_SIZE(master_err_str_buff)); - break; - default: - // unknown error code - break; + const char *error_string = map_master_error_code_to_string(_display_system_state.master_error_code); + if (error_string != nullptr) { + gcs().send_text( + MAV_SEVERITY_CRITICAL, "%s err:%u %s", + msg_prefix, + _display_system_state.master_error_code, + error_string); + } else { + gcs().send_text( + MAV_SEVERITY_CRITICAL, "%s err:%u", + msg_prefix, + _display_system_state.master_error_code); } - gcs().send_text(MAV_SEVERITY_CRITICAL, "%s err:%u %s", msg_prefix, _display_system_state.master_error_code, master_err_str_buff); } // report motor status errors diff --git a/libraries/AP_Torqeedo/AP_Torqeedo.h b/libraries/AP_Torqeedo/AP_Torqeedo.h index fad1f9fdd7..2fa21ddf04 100644 --- a/libraries/AP_Torqeedo/AP_Torqeedo.h +++ b/libraries/AP_Torqeedo/AP_Torqeedo.h @@ -359,6 +359,11 @@ private: uint32_t _last_error_report_ms; // system time that flag changes were last reported (used to prevent spamming user) MotorStatus _motor_status_prev; // backup of motor status static AP_Torqeedo *_singleton; + + // returns a human-readable string corresponding the the passed-in + // master error code (see page 93 of https://media.torqeedo.com/downloads/manuals/torqeedo-Travel-manual-DE-EN.pdf) + // If no conversion is available then nullptr is returned + const char *map_master_error_code_to_string(uint8_t code) const; }; namespace AP {