mavlink: fix PX4_DEBUG message formats

This commit is contained in:
Junwoo Hwang 2022-08-12 09:41:08 +02:00 committed by Beat Küng
parent 0c218e6628
commit d7a962b426
4 changed files with 10 additions and 10 deletions

View File

@ -559,7 +559,7 @@ MavlinkFTP::_workRead(PayloadHeader *payload)
return kErrInvalidSession;
}
PX4_DEBUG("FTP: read offset:%" PRIu32, payload->offset);
PX4_DEBUG("FTP: read offset:%ld" PRIu32, payload->offset);
// We have to test seek past EOF ourselves, lseek will allow seek past EOF
if (payload->offset >= _session_info.file_size) {
@ -567,7 +567,7 @@ MavlinkFTP::_workRead(PayloadHeader *payload)
return kErrEOF;
}
PX4_DEBUG("lseek with offset: %d", payload->offset);
PX4_DEBUG("lseek with offset: %ld", payload->offset);
if (lseek(_session_info.fd, payload->offset, SEEK_SET) < 0) {
_our_errno = errno;

View File

@ -486,7 +486,7 @@ MavlinkMissionManager::send()
_current_seq = mission_result.seq_current;
PX4_DEBUG("WPM: got mission result, new current_seq: %u", _current_seq);
PX4_DEBUG("WPM: got mission result, new current_seq: %ld", _current_seq);
if (mission_result.seq_total > 0) {
if (mission_result.seq_current < mission_result.seq_total) {
@ -505,7 +505,7 @@ MavlinkMissionManager::send()
_last_reached = mission_result.seq_reached;
_reached_sent_count = 0;
PX4_DEBUG("WPM: got mission result, new seq_reached: %d", _last_reached);
PX4_DEBUG("WPM: got mission result, new seq_reached: %ld", _last_reached);
if ((mission_result.seq_total > 0) && (_last_reached >= 0)) {
send_mission_item_reached((uint16_t)_last_reached);
@ -551,7 +551,7 @@ MavlinkMissionManager::send()
events::send(events::ID("mavlink_mission_op_timeout"), events::Log::Error,
"Operation timeout, aborting transfer");
PX4_DEBUG("WPM: Last operation (state=%u) timed out, changing state to MAVLINK_WPM_STATE_IDLE", _state);
PX4_DEBUG("WPM: Last operation (state=%d) timed out, changing state to MAVLINK_WPM_STATE_IDLE", _state);
switch_to_idle_state();
@ -1054,7 +1054,7 @@ MavlinkMissionManager::handle_mission_item_both(const mavlink_message_t *msg)
if (CHECK_SYSID_COMPID_MISSION(wp)) {
if (wp.mission_type != _mission_type) {
PX4_WARN("WPM: Unexpected mission type (%u %u)", (int)wp.mission_type, (int)_mission_type);
PX4_WARN("WPM: Unexpected mission type (%d %d)", (int)wp.mission_type, (int)_mission_type);
send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ERROR);
return;
}
@ -1219,7 +1219,7 @@ MavlinkMissionManager::handle_mission_item_both(const mavlink_message_t *msg)
if (_transfer_seq == _transfer_count) {
/* got all new mission items successfully */
PX4_DEBUG("WPM: MISSION_ITEM got all %u items, current_seq=%u, changing state to MAVLINK_WPM_STATE_IDLE",
PX4_DEBUG("WPM: MISSION_ITEM got all %u items, current_seq=%ld, changing state to MAVLINK_WPM_STATE_IDLE",
_transfer_count, _transfer_current_seq);
ret = 0;

View File

@ -84,13 +84,13 @@ private:
&& (cmd.source_component == cmd.target_component);
if (!cmd.from_external && !px4_internal_cmd && !target_system_internal) {
PX4_DEBUG("sending command %d to %d/%d", cmd.command, cmd.target_system, cmd.target_component);
PX4_DEBUG("sending command %ld to %d/%d", cmd.command, cmd.target_system, cmd.target_component);
MavlinkCommandSender::instance().handle_vehicle_command(cmd, _mavlink->get_channel());
sent = true;
} else {
PX4_DEBUG("not forwarding command %d to %d/%d", cmd.command, cmd.target_system, cmd.target_component);
PX4_DEBUG("not forwarding command %ld to %d/%d", cmd.command, cmd.target_system, cmd.target_component);
}
}
}

View File

@ -81,7 +81,7 @@ private:
if (_mavlink_log_sub.get_last_generation() != (last_generation + 1)) {
perf_count(_missed_msg_count_perf);
PX4_DEBUG("channel %d has missed %d mavlink log messages", _mavlink->get_channel(),
PX4_DEBUG("channel %d has missed %lld mavlink log messages", _mavlink->get_channel(),
perf_event_count(_missed_msg_count_perf));
}