Skip to content

Commit

Permalink
AP_CANManager: remove redundant calls to snprintf
Browse files Browse the repository at this point in the history
these only differ by the constant substring, so pull that out as a variable
  • Loading branch information
peterbarker committed Mar 16, 2024
1 parent e983738 commit 5cd18db
Showing 1 changed file with 8 additions and 5 deletions.
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

0 comments on commit 5cd18db

Please sign in to comment.