@@ -333,13 +333,15 @@ void MavlinkCommandSender::receive_timeout(const CommandIdentification& identifi
333
333
334
334
if (work->retries_to_do > 0 ) {
335
335
// 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 << " )." ;
340
341
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
+ }
343
345
}
344
346
345
347
if (!send_mavlink_message (work->command )) {
@@ -372,12 +374,17 @@ void MavlinkCommandSender::receive_timeout(const CommandIdentification& identifi
372
374
LogErr () << " No command, that's awkward" ;
373
375
continue ;
374
376
}
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
+ }
379
383
} 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
+ }
381
388
}
382
389
383
390
temp_callback = work->callback ;
0 commit comments