Skip to content

Commit f5d517e

Browse files
authored
Merge pull request #2625 from mavlink/pr-noisy-commands
core: make command sender less verbose
2 parents 6d6d671 + d7f7652 commit f5d517e

File tree

1 file changed

+18
-11
lines changed

1 file changed

+18
-11
lines changed

src/mavsdk/core/mavlink_command_sender.cpp

Lines changed: 18 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -333,13 +333,15 @@ void MavlinkCommandSender::receive_timeout(const CommandIdentification& identifi
333333

334334
if (work->retries_to_do > 0) {
335335
// We're not sure the command arrived, let's retransmit.
336-
LogWarn() << "sending again after "
337-
<< _system_impl.get_time().elapsed_since_s(work->time_started)
338-
<< " s, retries to do: " << work->retries_to_do << " ("
339-
<< work->identification.command << ").";
336+
if (_command_debugging) {
337+
LogWarn() << "sending again after "
338+
<< _system_impl.get_time().elapsed_since_s(work->time_started)
339+
<< " s, retries to do: " << work->retries_to_do << " ("
340+
<< work->identification.command << ").";
340341

341-
if (work->identification.command == MAV_CMD_REQUEST_MESSAGE) {
342-
LogWarn() << "Request was for msg ID: " << work->identification.maybe_param1;
342+
if (work->identification.command == MAV_CMD_REQUEST_MESSAGE) {
343+
LogWarn() << "Request was for msg ID: " << work->identification.maybe_param1;
344+
}
343345
}
344346

345347
if (!send_mavlink_message(work->command)) {
@@ -372,12 +374,17 @@ void MavlinkCommandSender::receive_timeout(const CommandIdentification& identifi
372374
LogErr() << "No command, that's awkward";
373375
continue;
374376
}
375-
LogWarn() << "Retrying failed for REQUEST_MESSAGE command for message: "
376-
<< work->identification.maybe_param1 << ", to ("
377-
<< std::to_string(target_sysid) << "/" << std::to_string(target_compid)
378-
<< ")";
377+
if (_command_debugging) {
378+
LogWarn() << "Retrying failed for REQUEST_MESSAGE command for message: "
379+
<< work->identification.maybe_param1 << ", to ("
380+
<< std::to_string(target_sysid) << "/"
381+
<< std::to_string(target_compid) << ")";
382+
}
379383
} else {
380-
LogWarn() << "Retrying failed for command: " << work->identification.command << ")";
384+
if (_command_debugging) {
385+
LogWarn() << "Retrying failed for command: " << work->identification.command
386+
<< ")";
387+
}
381388
}
382389

383390
temp_callback = work->callback;

0 commit comments

Comments
 (0)