Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_CANManager: remove redundant calls to snprintf #26536

Merged
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
13 changes: 8 additions & 5 deletions libraries/AP_CANManager/AP_CANManager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -377,27 +377,30 @@ void AP_CANManager::log_text(AP_CANManager::LogLevel loglevel, const char *tag,
_log_pos = 0;
}
//Tag Log Message
const char *log_level_tag = "";
switch (loglevel) {
case AP_CANManager::LOG_DEBUG :
_log_pos += hal.util->snprintf(&_log_buf[_log_pos], LOG_BUFFER_SIZE - _log_pos, "\n%s DEBUG :", tag);
log_level_tag = "DEBUG";
break;

case AP_CANManager::LOG_INFO :
_log_pos += hal.util->snprintf(&_log_buf[_log_pos], LOG_BUFFER_SIZE - _log_pos, "\n%s INFO :", tag);
log_level_tag = "INFO";
break;

case AP_CANManager::LOG_WARNING :
_log_pos += hal.util->snprintf(&_log_buf[_log_pos], LOG_BUFFER_SIZE - _log_pos, "\n%s WARN :", tag);
log_level_tag = "WARN";
break;

case AP_CANManager::LOG_ERROR :
_log_pos += hal.util->snprintf(&_log_buf[_log_pos], LOG_BUFFER_SIZE - _log_pos, "\n%s ERROR :", tag);
log_level_tag = "ERROR";
break;

default :
case AP_CANManager::LOG_NONE:
return;
}

_log_pos += hal.util->snprintf(&_log_buf[_log_pos], LOG_BUFFER_SIZE - _log_pos, "\n%s %s :", log_level_tag, tag);

va_list arg_list;
va_start(arg_list, fmt);
_log_pos += hal.util->vsnprintf(&_log_buf[_log_pos], LOG_BUFFER_SIZE - _log_pos, fmt, arg_list);
Expand Down
Loading