1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-13 11:29:58 +03:00

Make Cppcheck happier revived (#13566)

Co-authored-by: Štěpán Dalecký <daleckystepan@gmail.com>
This commit is contained in:
Mark Haslinghuis 2024-05-10 05:23:32 +02:00 committed by GitHub
parent d5af7d2254
commit 5a28ce5129
No known key found for this signature in database
GPG key ID: B5690EEEBB952194
63 changed files with 145 additions and 157 deletions

View file

@ -58,7 +58,7 @@ static void onClose(dyad_Event *e)
tcpPort_t* s = (tcpPort_t*)(e->udata);
s->clientCount--;
s->conn = NULL;
fprintf(stderr, "[CLS]UART%u: %d,%d\n", s->id + 1, s->connected, s->clientCount);
fprintf(stderr, "[CLS]UART%u: %d,%d\n", s->id + 1U, s->connected, s->clientCount);
if (s->clientCount == 0) {
s->connected = false;
}
@ -66,7 +66,7 @@ static void onClose(dyad_Event *e)
static void onAccept(dyad_Event *e)
{
tcpPort_t* s = (tcpPort_t*)(e->udata);
fprintf(stderr, "New connection on UART%u, %d\n", s->id + 1, s->clientCount);
fprintf(stderr, "New connection on UART%u, %d\n", s->id + 1U, s->clientCount);
s->connected = true;
if (s->clientCount > 0) {
@ -74,7 +74,7 @@ static void onAccept(dyad_Event *e)
return;
}
s->clientCount++;
fprintf(stderr, "[NEW]UART%u: %d,%d\n", s->id + 1, s->connected, s->clientCount);
fprintf(stderr, "[NEW]UART%u: %d,%d\n", s->id + 1U, s->connected, s->clientCount);
s->conn = e->remote;
dyad_setNoDelay(e->remote, 1);
dyad_setTimeout(e->remote, 120);