Commit fe365c7d authored by DonLakeFlyer's avatar DonLakeFlyer

parent 412de39c
...@@ -3323,6 +3323,8 @@ void Vehicle::_sendMavCommandAgain() ...@@ -3323,6 +3323,8 @@ void Vehicle::_sendMavCommandAgain()
_mavCommandAckTimer.start(); _mavCommandAckTimer.start();
qCDebug(VehicleLog) << "_sendMavCommandAgain sending" << queuedCommand.command;
mavlink_message_t msg; mavlink_message_t msg;
if (queuedCommand.commandInt) { if (queuedCommand.commandInt) {
mavlink_command_int_t cmd; mavlink_command_int_t cmd;
...@@ -3428,6 +3430,8 @@ void Vehicle::_handleCommandAck(mavlink_message_t& message) ...@@ -3428,6 +3430,8 @@ void Vehicle::_handleCommandAck(mavlink_message_t& message)
mavlink_command_ack_t ack; mavlink_command_ack_t ack;
mavlink_msg_command_ack_decode(&message, &ack); mavlink_msg_command_ack_decode(&message, &ack);
qCDebug(VehicleLog) << QStringLiteral("_handleCommandAck command(%1) result(%2)").arg(ack.command).arg(ack.result);
if (ack.command == MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES && ack.result != MAV_RESULT_ACCEPTED) { if (ack.command == MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES && ack.result != MAV_RESULT_ACCEPTED) {
qCDebug(VehicleLog) << QStringLiteral("Vehicle responded to MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES with error(%1). Setting no capabilities.").arg(ack.result); qCDebug(VehicleLog) << QStringLiteral("Vehicle responded to MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES with error(%1). Setting no capabilities.").arg(ack.result);
_handleUnsupportedRequestAutopilotCapabilities(); _handleUnsupportedRequestAutopilotCapabilities();
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment