mirror of https://github.com/ArduPilot/ardupilot
Tools: Replay: correct format strings
This commit is contained in:
parent
fb284ff26a
commit
5ab000376b
|
@ -2,6 +2,8 @@
|
|||
#include "LogReader.h"
|
||||
#include "Replay.h"
|
||||
|
||||
#include <cinttypes>
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
LR_MsgHandler::LR_MsgHandler(struct log_Format &_f,
|
||||
|
@ -427,7 +429,7 @@ void LR_MsgHandler_PM::process_message(uint8_t *msg)
|
|||
uint32_t new_logdrop;
|
||||
if (field_value(msg, "LogDrop", new_logdrop) &&
|
||||
new_logdrop != 0) {
|
||||
printf("PM.LogDrop: %u dropped at timestamp %lu\n", new_logdrop, last_timestamp_usec);
|
||||
printf("PM.LogDrop: %u dropped at timestamp %" PRIu64 "\n", new_logdrop, last_timestamp_usec);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -803,12 +803,12 @@ void Replay::show_packet_counts()
|
|||
for(uint16_t i=0;i<LOGREADER_MAX_FORMATS;i++) {
|
||||
if (counts[i] != 0) {
|
||||
logreader.format_type(i, format_type);
|
||||
printf("%10ld %s\n", counts[i], format_type);
|
||||
printf("%10" PRIu64 " %s\n", counts[i], format_type);
|
||||
total += counts[i];
|
||||
}
|
||||
}
|
||||
|
||||
printf("%ld total\n", total);
|
||||
printf("%" PRIu64 " total\n", total);
|
||||
}
|
||||
|
||||
void Replay::loop()
|
||||
|
@ -830,7 +830,7 @@ void Replay::loop()
|
|||
if (last_timestamp != 0) {
|
||||
uint64_t gap = AP_HAL::micros64() - last_timestamp;
|
||||
if (gap > 40000) {
|
||||
::printf("Gap in log at timestamp=%lu of length %luus\n",
|
||||
::printf("Gap in log at timestamp=%" PRIu64 " of length %" PRIu64 "us\n",
|
||||
last_timestamp, gap);
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue