mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
mavlink:Use inttypes
This commit is contained in:
parent
5faa116681
commit
65d026d45c
@ -1,6 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2017 PX4 Development Team. All rights reserved.
|
||||
* Copyright (c) 2017, 2021 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
@ -73,7 +73,7 @@ int MavlinkCommandSender::handle_vehicle_command(const vehicle_command_s &comman
|
||||
}
|
||||
|
||||
lock();
|
||||
CMD_DEBUG("new command: %d (channel: %d)", command.command, channel);
|
||||
CMD_DEBUG("new command: %" PRIu32 " (channel: %d)", command.command, channel);
|
||||
|
||||
mavlink_command_long_t msg = {};
|
||||
msg.target_system = command.target_system;
|
||||
@ -119,7 +119,7 @@ int MavlinkCommandSender::handle_vehicle_command(const vehicle_command_s &comman
|
||||
void MavlinkCommandSender::handle_mavlink_command_ack(const mavlink_command_ack_t &ack,
|
||||
uint8_t from_sysid, uint8_t from_compid, uint8_t channel)
|
||||
{
|
||||
CMD_DEBUG("handling result %d for command %d (from %d:%d)",
|
||||
CMD_DEBUG("handling result %" PRIu8 " for command %" PRIu16 " (from %" PRIu8 ":%" PRIu8 ")",
|
||||
ack.result, ack.command, from_sysid, from_compid);
|
||||
lock();
|
||||
|
||||
@ -197,7 +197,7 @@ void MavlinkCommandSender::check_timeout(mavlink_channel_t channel)
|
||||
item->command.confirmation = ++item->num_sent_per_channel[channel];
|
||||
mavlink_msg_command_long_send_struct(channel, &item->command);
|
||||
|
||||
CMD_DEBUG("command %d sent (not first, retries: %d/%d, channel: %d)",
|
||||
CMD_DEBUG("command %" PRIu16 " sent (not first, retries: %" PRIu8 "/%" PRIi8 ", channel: %d)",
|
||||
item->command.command,
|
||||
item->num_sent_per_channel[channel],
|
||||
max_sent,
|
||||
@ -209,7 +209,7 @@ void MavlinkCommandSender::check_timeout(mavlink_channel_t channel)
|
||||
// If the next retry would be above the needed retries anyway, we can
|
||||
// drop the item, and continue with other items.
|
||||
if (item->num_sent_per_channel[channel] + 1 > RETRIES) {
|
||||
CMD_DEBUG("command %d dropped", item->command.command);
|
||||
CMD_DEBUG("command %" PRIu16 " dropped", item->command.command);
|
||||
_commands.drop_current();
|
||||
continue;
|
||||
}
|
||||
@ -220,7 +220,7 @@ void MavlinkCommandSender::check_timeout(mavlink_channel_t channel)
|
||||
// Therefore, we are the ones setting the timestamp of this retry round.
|
||||
item->last_time_sent_us = hrt_absolute_time();
|
||||
|
||||
CMD_DEBUG("command %d sent (first, retries: %d/%d, channel: %d)",
|
||||
CMD_DEBUG("command %" PRIu16 " sent (first, retries: %" PRId8 "/%" PRId8 ", channel: %d)",
|
||||
item->command.command,
|
||||
item->num_sent_per_channel[channel],
|
||||
max_sent,
|
||||
|
||||
@ -1,6 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2014-2020 PX4 Development Team. All rights reserved.
|
||||
* Copyright (c) 2014-2021 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
@ -190,7 +190,8 @@ MavlinkFTP::_process_request(
|
||||
|
||||
|
||||
#ifdef MAVLINK_FTP_DEBUG
|
||||
PX4_INFO("ftp: channel %u opc %u size %u offset %u", _getServerChannel(), payload->opcode, payload->size,
|
||||
PX4_INFO("ftp: channel %" PRIu8 " opc %" PRIu8 " size %" PRIu8 " offset %" PRIu32, _getServerChannel(), payload->opcode,
|
||||
payload->size,
|
||||
payload->offset);
|
||||
#endif
|
||||
|
||||
@ -336,7 +337,7 @@ MavlinkFTP::_reply(mavlink_file_transfer_protocol_t *ftp_req)
|
||||
}
|
||||
|
||||
#ifdef MAVLINK_FTP_DEBUG
|
||||
PX4_INFO("FTP: %s seq_number: %d", payload->opcode == kRspAck ? "Ack" : "Nak", payload->seq_number);
|
||||
PX4_INFO("FTP: %s seq_number: %" PRIu16, payload->opcode == kRspAck ? "Ack" : "Nak", payload->seq_number);
|
||||
#endif
|
||||
|
||||
#ifdef MAVLINK_FTP_UNIT_TEST
|
||||
@ -368,7 +369,7 @@ MavlinkFTP::_workList(PayloadHeader *payload)
|
||||
}
|
||||
|
||||
#ifdef MAVLINK_FTP_DEBUG
|
||||
PX4_INFO("FTP: list %s offset %d", _work_buffer1, payload->offset);
|
||||
PX4_INFO("FTP: list %s offset %" PRIu32, _work_buffer1, payload->offset);
|
||||
#endif
|
||||
|
||||
struct dirent *result = nullptr;
|
||||
@ -461,7 +462,7 @@ MavlinkFTP::_workList(PayloadHeader *payload)
|
||||
|
||||
} else if (direntType == kDirentFile) {
|
||||
// Files send filename and file length
|
||||
int ret = snprintf(_work_buffer2, _work_buffer2_len, "%s\t%d", result->d_name, fileSize);
|
||||
int ret = snprintf(_work_buffer2, _work_buffer2_len, "%s\t%" PRIu32, result->d_name, fileSize);
|
||||
bool buf_is_ok = ((ret > 0) && (ret < _work_buffer2_len));
|
||||
|
||||
if (!buf_is_ok) {
|
||||
@ -554,7 +555,7 @@ MavlinkFTP::_workRead(PayloadHeader *payload)
|
||||
}
|
||||
|
||||
#ifdef MAVLINK_FTP_DEBUG
|
||||
PX4_INFO("FTP: read offset:%d", payload->offset);
|
||||
PX4_INFO("FTP: read offset:%" PRIu32, payload->offset);
|
||||
#endif
|
||||
|
||||
// We have to test seek past EOF ourselves, lseek will allow seek past EOF
|
||||
@ -590,7 +591,7 @@ MavlinkFTP::_workBurst(PayloadHeader *payload, uint8_t target_system_id, uint8_t
|
||||
}
|
||||
|
||||
#ifdef MAVLINK_FTP_DEBUG
|
||||
PX4_INFO("FTP: burst offset:%d", payload->offset);
|
||||
PX4_INFO("FTP: burst offset:%" PRIu32, payload->offset);
|
||||
#endif
|
||||
// Setup for streaming sends
|
||||
_session_info.stream_download = true;
|
||||
@ -993,7 +994,7 @@ void MavlinkFTP::send()
|
||||
// Skip send if not enough room
|
||||
unsigned max_bytes_to_send = _mavlink->get_free_tx_buf();
|
||||
#ifdef MAVLINK_FTP_DEBUG
|
||||
PX4_INFO("MavlinkFTP::send max_bytes_to_send(%d) get_free_tx_buf(%d)", max_bytes_to_send, _mavlink->get_free_tx_buf());
|
||||
PX4_INFO("MavlinkFTP::send max_bytes_to_send(%u) get_free_tx_buf(%u)", max_bytes_to_send, _mavlink->get_free_tx_buf());
|
||||
#endif
|
||||
|
||||
if (max_bytes_to_send < get_size()) {
|
||||
@ -1022,7 +1023,7 @@ void MavlinkFTP::send()
|
||||
_session_info.stream_seq_number++;
|
||||
|
||||
#ifdef MAVLINK_FTP_DEBUG
|
||||
PX4_INFO("stream send: offset %d", _session_info.stream_offset);
|
||||
PX4_INFO("stream send: offset %" PRIu32, _session_info.stream_offset);
|
||||
#endif
|
||||
|
||||
// We have to test seek past EOF ourselves, lseek will allow seek past EOF
|
||||
|
||||
@ -1,6 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2014-2020 PX4 Development Team. All rights reserved.
|
||||
* Copyright (c) 2014-2021 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
@ -172,7 +172,7 @@ MavlinkLogHandler::_log_request_list(const mavlink_message_t *msg)
|
||||
_log_count - 1;
|
||||
}
|
||||
|
||||
PX4LOG_WARN("\nMavlinkLogHandler::_log_request_list: start: %u last: %u count: %u",
|
||||
PX4LOG_WARN("\nMavlinkLogHandler::_log_request_list: start: %d last: %d count: %d",
|
||||
_next_entry,
|
||||
_last_entry,
|
||||
_log_count);
|
||||
@ -195,7 +195,7 @@ MavlinkLogHandler::_log_request_data(const mavlink_message_t *msg)
|
||||
|
||||
//-- Does the requested log exist?
|
||||
if (request.id >= _log_count) {
|
||||
PX4LOG_WARN("MavlinkLogHandler::_log_request_data Requested log %u but we only have %u.", request.id,
|
||||
PX4LOG_WARN("MavlinkLogHandler::_log_request_data Requested log %" PRIu16 " but we only have %u.", request.id,
|
||||
_log_count);
|
||||
return;
|
||||
}
|
||||
@ -282,7 +282,8 @@ MavlinkLogHandler::_log_send_listing()
|
||||
_next_entry++;
|
||||
}
|
||||
|
||||
PX4LOG_WARN("MavlinkLogHandler::_log_send_listing id: %u count: %u last: %u size: %u date: %u status: %d",
|
||||
PX4LOG_WARN("MavlinkLogHandler::_log_send_listing id: %" PRIu16 " count: %" PRIu16 " last: %" PRIu16 " size: %" PRIu32
|
||||
" date: %" PRIu32 " status: %" PRIu32,
|
||||
response.id,
|
||||
response.num_logs,
|
||||
response.last_log_num,
|
||||
@ -353,7 +354,7 @@ MavlinkLogHandler::_get_entry(int idx, uint32_t &size, uint32_t &date, char *fil
|
||||
if (count++ == idx) {
|
||||
char file[160];
|
||||
|
||||
if (sscanf(line, "%u %u %s", &date, &size, file) == 3) {
|
||||
if (sscanf(line, "%" PRIu32 " %" PRIu32 " %s", &date, &size, file) == 3) {
|
||||
if (filename && filename_len > 0) {
|
||||
strncpy(filename, file, filename_len);
|
||||
filename[filename_len - 1] = 0; // ensure null-termination
|
||||
|
||||
@ -1,6 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-2020 PX4 Development Team. All rights reserved.
|
||||
* Copyright (c) 2012-2021 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
@ -1024,7 +1024,7 @@ Mavlink::compute_broadcast_addr(const in_addr &host_addr, const in_addr &netmask
|
||||
void
|
||||
Mavlink::init_udp()
|
||||
{
|
||||
PX4_DEBUG("Setting up UDP with port %d", _network_port);
|
||||
PX4_DEBUG("Setting up UDP with port %hu", _network_port);
|
||||
|
||||
_myaddr.sin_family = AF_INET;
|
||||
_myaddr.sin_addr.s_addr = htonl(INADDR_ANY);
|
||||
@ -2139,7 +2139,7 @@ Mavlink::task_main(int argc, char *argv[])
|
||||
|
||||
else if (get_protocol() == Protocol::UDP) {
|
||||
if (Mavlink::get_instance_for_network_port(_network_port) != nullptr) {
|
||||
PX4_ERR("port %d already occupied", _network_port);
|
||||
PX4_ERR("port %hu already occupied", _network_port);
|
||||
return PX4_ERROR;
|
||||
}
|
||||
|
||||
@ -2315,7 +2315,7 @@ Mavlink::task_main(int argc, char *argv[])
|
||||
|
||||
if (_vehicle_command_sub.update(&vehicle_cmd)) {
|
||||
if (_vehicle_command_sub.get_last_generation() != last_generation + 1) {
|
||||
PX4_ERR("vehicle_command lost, generation %d -> %d", last_generation, _vehicle_command_sub.get_last_generation());
|
||||
PX4_ERR("vehicle_command lost, generation %u -> %u", last_generation, _vehicle_command_sub.get_last_generation());
|
||||
}
|
||||
|
||||
if ((vehicle_cmd.command == vehicle_command_s::VEHICLE_CMD_CONTROL_HIGH_LATENCY) &&
|
||||
@ -2366,7 +2366,7 @@ Mavlink::task_main(int argc, char *argv[])
|
||||
|
||||
if (_vehicle_command_ack_sub.update(&command_ack)) {
|
||||
if (_vehicle_command_ack_sub.get_last_generation() != last_generation + 1) {
|
||||
PX4_ERR("vehicle_command_ack lost, generation %d -> %d", last_generation,
|
||||
PX4_ERR("vehicle_command_ack lost, generation %u -> %u", last_generation,
|
||||
_vehicle_command_ack_sub.get_last_generation());
|
||||
}
|
||||
|
||||
@ -2573,7 +2573,7 @@ void Mavlink::check_requested_subscriptions()
|
||||
#if defined(MAVLINK_UDP)
|
||||
|
||||
else if (get_protocol() == Protocol::UDP) {
|
||||
PX4_DEBUG("stream %s on UDP port %d set to default rate", _subscribe_to_stream, _network_port);
|
||||
PX4_DEBUG("stream %s on UDP port %hu set to default rate", _subscribe_to_stream, _network_port);
|
||||
}
|
||||
|
||||
#endif // MAVLINK_UDP
|
||||
@ -2593,7 +2593,7 @@ void Mavlink::check_requested_subscriptions()
|
||||
#if defined(MAVLINK_UDP)
|
||||
|
||||
else if (get_protocol() == Protocol::UDP) {
|
||||
PX4_DEBUG("stream %s on UDP port %d enabled with rate %.1f Hz", _subscribe_to_stream, _network_port,
|
||||
PX4_DEBUG("stream %s on UDP port %hu enabled with rate %.1f Hz", _subscribe_to_stream, _network_port,
|
||||
(double)_subscribe_to_stream_rate);
|
||||
}
|
||||
|
||||
@ -2608,7 +2608,7 @@ void Mavlink::check_requested_subscriptions()
|
||||
#if defined(MAVLINK_UDP)
|
||||
|
||||
else if (get_protocol() == Protocol::UDP) {
|
||||
PX4_DEBUG("stream %s on UDP port %d disabled", _subscribe_to_stream, _network_port);
|
||||
PX4_DEBUG("stream %s on UDP port %hu disabled", _subscribe_to_stream, _network_port);
|
||||
}
|
||||
|
||||
#endif // MAVLINK_UDP
|
||||
@ -2623,7 +2623,7 @@ void Mavlink::check_requested_subscriptions()
|
||||
#if defined(MAVLINK_UDP)
|
||||
|
||||
else if (get_protocol() == Protocol::UDP) {
|
||||
PX4_ERR("stream %s on UDP port %d not found", _subscribe_to_stream, _network_port);
|
||||
PX4_ERR("stream %s on UDP port %hu not found", _subscribe_to_stream, _network_port);
|
||||
}
|
||||
|
||||
#endif // MAVLINK_UDP
|
||||
@ -2668,7 +2668,7 @@ void Mavlink::configure_sik_radio()
|
||||
|
||||
if (_param_sik_radio_id.get() > 0) {
|
||||
/* set channel */
|
||||
fprintf(fs, "ATS3=%u\n", _param_sik_radio_id.get());
|
||||
fprintf(fs, "ATS3=%" PRIu32 "\n", _param_sik_radio_id.get());
|
||||
px4_usleep(200000);
|
||||
|
||||
} else {
|
||||
@ -2792,7 +2792,7 @@ Mavlink::display_status()
|
||||
printf("\tGCS heartbeat valid\n");
|
||||
}
|
||||
|
||||
printf("\tmavlink chan: #%u\n", _channel);
|
||||
printf("\tmavlink chan: #%u\n", static_cast<unsigned>(_channel));
|
||||
|
||||
if (_tstatus.timestamp > 0) {
|
||||
|
||||
@ -2800,13 +2800,13 @@ Mavlink::display_status()
|
||||
|
||||
if (_radio_status_available) {
|
||||
printf("RADIO Link\n");
|
||||
printf("\t rssi:\t\t%d\n", _rstatus.rssi);
|
||||
printf("\t remote rssi:\t%u\n", _rstatus.remote_rssi);
|
||||
printf("\t txbuf:\t%u\n", _rstatus.txbuf);
|
||||
printf("\t noise:\t%d\n", _rstatus.noise);
|
||||
printf("\t remote noise:\t%u\n", _rstatus.remote_noise);
|
||||
printf("\t rx errors:\t%u\n", _rstatus.rxerrors);
|
||||
printf("\t fixed:\t%u\n", _rstatus.fix);
|
||||
printf("\t rssi:\t\t%" PRIu8 "\n", _rstatus.rssi);
|
||||
printf("\t remote rssi:\t%" PRIu8 "\n", _rstatus.remote_rssi);
|
||||
printf("\t txbuf:\t%" PRIu8 "\n", _rstatus.txbuf);
|
||||
printf("\t noise:\t%" PRIu8 "\n", _rstatus.noise);
|
||||
printf("\t remote noise:\t%" PRIu8 "\n", _rstatus.remote_noise);
|
||||
printf("\t rx errors:\t%" PRIu16 "\n", _rstatus.rxerrors);
|
||||
printf("\t fixed:\t%" PRIu16 "\n", _rstatus.fix);
|
||||
|
||||
} else if (_is_usb_uart) {
|
||||
printf("USB CDC\n");
|
||||
@ -2838,7 +2838,7 @@ Mavlink::display_status()
|
||||
_ftp_on ? "YES" : "NO",
|
||||
_transmitting_enabled ? "YES" : "NO");
|
||||
printf("\tmode: %s\n", mavlink_mode_str(_mode));
|
||||
printf("\tMAVLink version: %i\n", _protocol_version);
|
||||
printf("\tMAVLink version: %" PRId32 "\n", _protocol_version);
|
||||
|
||||
printf("\ttransport protocol: ");
|
||||
|
||||
@ -2846,7 +2846,7 @@ Mavlink::display_status()
|
||||
#if defined(MAVLINK_UDP)
|
||||
|
||||
case Protocol::UDP:
|
||||
printf("UDP (%i, remote port: %i)\n", _network_port, _remote_port);
|
||||
printf("UDP (%hu, remote port: %hu)\n", _network_port, _remote_port);
|
||||
printf("\tBroadcast enabled: %s\n",
|
||||
broadcast_enabled() ? "YES" : "NO");
|
||||
#if defined(CONFIG_NET_IGMP) && defined(CONFIG_NET_ROUTE)
|
||||
@ -2874,7 +2874,7 @@ Mavlink::display_status()
|
||||
printf("\t mean: %0.2f ms\n", (double)_ping_stats.mean_rtt);
|
||||
printf("\t max: %0.2f ms\n", (double)_ping_stats.max_rtt);
|
||||
printf("\t min: %0.2f ms\n", (double)_ping_stats.min_rtt);
|
||||
printf("\t dropped packets: %u\n", _ping_stats.dropped_packets);
|
||||
printf("\t dropped packets: %" PRIi32 "\n", _ping_stats.dropped_packets);
|
||||
}
|
||||
}
|
||||
|
||||
@ -2904,7 +2904,7 @@ Mavlink::display_status_streams()
|
||||
printf("\t%-30s%-16s", stream->get_name(), rate_str);
|
||||
|
||||
if (size > 0) {
|
||||
printf(" %3i\n", size);
|
||||
printf(" %3u\n", size);
|
||||
|
||||
} else {
|
||||
printf("\n");
|
||||
|
||||
@ -562,7 +562,7 @@ void MavlinkReceiver::handle_message_command_both(mavlink_message_t *msg, const
|
||||
send_ack = false;
|
||||
|
||||
if (msg->sysid == mavlink_system.sysid && msg->compid == mavlink_system.compid) {
|
||||
PX4_WARN("ignoring CMD with same SYS/COMP (%d/%d) ID", mavlink_system.sysid, mavlink_system.compid);
|
||||
PX4_WARN("ignoring CMD with same SYS/COMP (%" PRIu8 "/%" PRIu8 ") ID", mavlink_system.sysid, mavlink_system.compid);
|
||||
return;
|
||||
}
|
||||
|
||||
@ -656,7 +656,7 @@ MavlinkReceiver::handle_message_command_ack(mavlink_message_t *msg)
|
||||
// TODO: move it to the same place that sent the command
|
||||
if (ack.result != MAV_RESULT_ACCEPTED && ack.result != MAV_RESULT_IN_PROGRESS) {
|
||||
if (msg->compid == MAV_COMP_ID_CAMERA) {
|
||||
PX4_WARN("Got unsuccessful result %d from camera", ack.result);
|
||||
PX4_WARN("Got unsuccessful result %" PRIu8 " from camera", ack.result);
|
||||
}
|
||||
}
|
||||
}
|
||||
@ -946,7 +946,7 @@ MavlinkReceiver::handle_message_set_position_target_local_ned(mavlink_message_t
|
||||
setpoint.z = NAN;
|
||||
|
||||
} else {
|
||||
mavlink_log_critical(&_mavlink_log_pub, "SET_POSITION_TARGET_LOCAL_NED coordinate frame %d unsupported",
|
||||
mavlink_log_critical(&_mavlink_log_pub, "SET_POSITION_TARGET_LOCAL_NED coordinate frame %" PRIu8 " unsupported",
|
||||
target_local_ned.coordinate_frame);
|
||||
return;
|
||||
}
|
||||
@ -1054,7 +1054,7 @@ MavlinkReceiver::handle_message_set_position_target_global_int(mavlink_message_t
|
||||
}
|
||||
|
||||
} else {
|
||||
mavlink_log_critical(&_mavlink_log_pub, "SET_POSITION_TARGET_GLOBAL_INT invalid coordinate frame %d",
|
||||
mavlink_log_critical(&_mavlink_log_pub, "SET_POSITION_TARGET_GLOBAL_INT invalid coordinate frame %" PRIu8,
|
||||
target_global_int.coordinate_frame);
|
||||
return;
|
||||
}
|
||||
@ -1299,7 +1299,7 @@ MavlinkReceiver::handle_message_odometry(mavlink_message_t *msg)
|
||||
}
|
||||
|
||||
} else {
|
||||
PX4_ERR("Body frame %u not supported. Unable to publish velocity", odom.child_frame_id);
|
||||
PX4_ERR("Body frame %" PRIu8 " not supported. Unable to publish velocity", odom.child_frame_id);
|
||||
}
|
||||
|
||||
/**
|
||||
@ -1330,11 +1330,11 @@ MavlinkReceiver::handle_message_odometry(mavlink_message_t *msg)
|
||||
_mocap_odometry_pub.publish(odometry);
|
||||
|
||||
} else {
|
||||
PX4_ERR("Estimator source %u not supported. Unable to publish pose and velocity", odom.estimator_type);
|
||||
PX4_ERR("Estimator source %" PRIu8 " not supported. Unable to publish pose and velocity", odom.estimator_type);
|
||||
}
|
||||
|
||||
} else {
|
||||
PX4_ERR("Local frame %u not supported. Unable to publish pose and velocity", odom.frame_id);
|
||||
PX4_ERR("Local frame %" PRIu8 " not supported. Unable to publish pose and velocity", odom.frame_id);
|
||||
}
|
||||
}
|
||||
|
||||
@ -1690,7 +1690,7 @@ MavlinkReceiver::handle_message_play_tune_v2(mavlink_message_t *msg)
|
||||
(mavlink_system.compid == play_tune_v2.target_component || play_tune_v2.target_component == 0)) {
|
||||
|
||||
if (play_tune_v2.format != TUNE_FORMAT_QBASIC1_1) {
|
||||
PX4_ERR("Tune format %d not supported", play_tune_v2.format);
|
||||
PX4_ERR("Tune format %" PRIu32 " not supported", play_tune_v2.format);
|
||||
return;
|
||||
}
|
||||
|
||||
@ -2016,7 +2016,8 @@ MavlinkReceiver::handle_message_heartbeat(mavlink_message_t *msg)
|
||||
break;
|
||||
|
||||
default:
|
||||
PX4_DEBUG("unhandled HEARTBEAT MAV_TYPE: %d from SYSID: %d, COMPID: %d", hb.type, msg->sysid, msg->compid);
|
||||
PX4_DEBUG("unhandled HEARTBEAT MAV_TYPE: %" PRIu8 " from SYSID: %" PRIu8 ", COMPID: %" PRIu8, hb.type, msg->sysid,
|
||||
msg->compid);
|
||||
}
|
||||
|
||||
|
||||
@ -2055,7 +2056,8 @@ MavlinkReceiver::handle_message_heartbeat(mavlink_message_t *msg)
|
||||
break;
|
||||
|
||||
default:
|
||||
PX4_DEBUG("unhandled HEARTBEAT MAV_TYPE: %d from SYSID: %d, COMPID: %d", hb.type, msg->sysid, msg->compid);
|
||||
PX4_DEBUG("unhandled HEARTBEAT MAV_TYPE: %" PRIu8 " from SYSID: %" PRIu8 ", COMPID: %" PRIu8, hb.type, msg->sysid,
|
||||
msg->compid);
|
||||
}
|
||||
|
||||
CheckHeartbeats(now, true);
|
||||
@ -2313,7 +2315,7 @@ MavlinkReceiver::handle_message_landing_target(mavlink_message_t *msg)
|
||||
|
||||
} else if (landing_target.position_valid) {
|
||||
// We only support MAV_FRAME_LOCAL_NED. In this case, the frame was unsupported.
|
||||
mavlink_log_critical(&_mavlink_log_pub, "landing target: coordinate frame %d unsupported",
|
||||
mavlink_log_critical(&_mavlink_log_pub, "landing target: coordinate frame %" PRIu8 " unsupported",
|
||||
landing_target.frame);
|
||||
|
||||
} else {
|
||||
@ -2792,7 +2794,8 @@ void MavlinkReceiver::handle_message_statustext(mavlink_message_t *msg)
|
||||
log_message.timestamp = hrt_absolute_time();
|
||||
|
||||
snprintf(log_message.text, sizeof(log_message.text),
|
||||
"[mavlink: component %d] %." STRINGIFY(MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN) "s", msg->compid, statustext.text);
|
||||
"[mavlink: component %" PRIu8 "] %." STRINGIFY(MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN) "s", msg->compid,
|
||||
statustext.text);
|
||||
|
||||
_log_message_pub.publish(log_message);
|
||||
}
|
||||
@ -3190,7 +3193,8 @@ void MavlinkReceiver::print_detailed_rx_stats() const
|
||||
// TODO: add mutex around shared data.
|
||||
for (unsigned i = 0; i < MAX_REMOTE_COMPONENTS; ++i) {
|
||||
if (_component_states[i].received_messages > 0) {
|
||||
printf("\t received from sysid: %u compid: %u: %u, lost: %u, last %u ms ago\n",
|
||||
printf("\t received from sysid: %" PRIu8 " compid: %" PRIu8 ": %" PRIu32 ", lost: %" PRIu32 ", last %" PRIu32
|
||||
" ms ago\n",
|
||||
_component_states[i].system_id,
|
||||
_component_states[i].component_id,
|
||||
_component_states[i].received_messages,
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user