AP_Radio: fixed build warnings

This commit is contained in:
Andrew Tridgell 2018-02-08 09:34:51 +11:00
parent 598c2b9eb1
commit f928bd9420
2 changed files with 13 additions and 13 deletions

View File

@ -153,7 +153,7 @@ uint8_t AP_Radio_cc2500::num_channels(void)
t_status.pps = stats.recv_packets - last_stats.recv_packets;
last_stats = stats;
if (lost != 0 || timeouts != 0) {
Debug(3,"lost=%u timeouts=%u TS=%u\n", lost, timeouts, sizeof(struct telem_packet_cc2500));
Debug(3,"lost=%u timeouts=%u TS=%u\n", unsigned(lost), unsigned(timeouts), sizeof(struct telem_packet_cc2500));
}
lost=0;
timeouts=0;
@ -341,7 +341,7 @@ void AP_Radio_cc2500::handle_data_packet(mavlink_channel_t chan, const mavlink_d
{
uint32_t ofs=0;
memcpy(&ofs, &m.data[0], 4);
Debug(4, "got data96 of len %u from chan %u at offset %u\n", m.len, chan, ofs);
Debug(4, "got data96 of len %u from chan %u at offset %u\n", m.len, chan, unsigned(ofs));
if (sem->take_nonblocking()) {
fwupload.chan = chan;
fwupload.need_ack = false;
@ -463,7 +463,7 @@ bool AP_Radio_cc2500::handle_SRT_packet(const uint8_t *packet)
case PKTYPE_FW_ACK: {
// got an fw upload ack
Debug(4, "ack %u seq=%u acked=%u length=%u len=%u\n",
data, fwupload.sequence, fwupload.acked, fwupload.length, fwupload.len);
data, fwupload.sequence, unsigned(fwupload.acked), unsigned(fwupload.length), fwupload.len);
if (fwupload.sequence == data && sem->take_nonblocking()) {
fwupload.sequence++;
fwupload.acked += fwupload.len;
@ -666,7 +666,7 @@ void AP_Radio_cc2500::irq_timeout(void)
uint32_t now = AP_HAL::micros();
if (now - packet_timer > 50*sync_time_us) {
Debug(3,"searching %u\n", now - packet_timer);
Debug(3,"searching %u\n", unsigned(now - packet_timer));
cc2500.Strobe(CC2500_SIDLE);
cc2500.Strobe(CC2500_SFRX);
nextChannel(1);

View File

@ -356,13 +356,13 @@ void AP_Radio_cypress::update(void)
void AP_Radio_cypress::print_debug_info(void)
{
Debug(2, "recv:%3u bad:%3u to:%3u re:%u N:%2u TXI:%u TX:%u 1:%4u 2:%4u 3:%4u 4:%4u 5:%4u 6:%4u 7:%4u 8:%4u 14:%u\n",
stats.recv_packets - last_stats.recv_packets,
stats.bad_packets - last_stats.bad_packets,
stats.timeouts - last_stats.timeouts,
stats.recv_errors - last_stats.recv_errors,
unsigned(stats.recv_packets - last_stats.recv_packets),
unsigned(stats.bad_packets - last_stats.bad_packets),
unsigned(stats.timeouts - last_stats.timeouts),
unsigned(stats.recv_errors - last_stats.recv_errors),
num_channels(),
dsm.send_irq_count,
dsm.send_count,
unsigned(dsm.send_irq_count),
unsigned(dsm.send_count),
dsm.pwm_channels[0], dsm.pwm_channels[1], dsm.pwm_channels[2], dsm.pwm_channels[3],
dsm.pwm_channels[4], dsm.pwm_channels[5], dsm.pwm_channels[6], dsm.pwm_channels[7],
dsm.pwm_channels[13]);
@ -807,7 +807,7 @@ bool AP_Radio_cypress::parse_dsm_channels(const uint8_t *data)
if (chan == 7 && key == 0) {
// got an ack from key 0
Debug(4, "ack %u seq=%u acked=%u length=%u len=%u\n",
v, fwupload.sequence, fwupload.acked, fwupload.length, fwupload.len);
v, fwupload.sequence, unsigned(fwupload.acked), unsigned(fwupload.length), fwupload.len);
if (fwupload.sequence == v && sem->take_nonblocking()) {
fwupload.sequence++;
fwupload.acked += fwupload.len;
@ -1404,7 +1404,7 @@ void AP_Radio_cypress::dsm_choose_channel(void)
state = STATE_AUTOBIND;
Debug(3,"recv autobind %u\n", now - dsm.last_autobind_send);
Debug(3,"recv autobind %u\n", unsigned(now - dsm.last_autobind_send));
dsm.last_autobind_send = now;
return;
}
@ -1701,7 +1701,7 @@ void AP_Radio_cypress::handle_data_packet(mavlink_channel_t chan, const mavlink_
{
uint32_t ofs=0;
memcpy(&ofs, &m.data[0], 4);
Debug(4, "got data96 of len %u from chan %u at offset %u\n", m.len, chan, ofs);
Debug(4, "got data96 of len %u from chan %u at offset %u\n", m.len, chan, unsigned(ofs));
if (sem->take_nonblocking()) {
fwupload.chan = chan;
fwupload.need_ack = false;