diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 4a33621ce2bee7ad941be7b84f815741238a4983..b01974e944d706edd860b9c169e6b867bf08bc12 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -488,6 +488,14 @@ void Vehicle::resetCounters() void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t message) { + // if the minimum supported version of MAVLink is already 2.0 + // set our max proto version to it. + unsigned mavlinkVersion = _mavlink->getCurrentVersion(); + if (_maxProtoVersion != mavlinkVersion && mavlinkVersion >= 200) { + _maxProtoVersion = _mavlink->getCurrentVersion(); + qCDebug(VehicleLog) << "Vehicle::_mavlinkMessageReceived setting _maxProtoVersion" << _maxProtoVersion; + } + if (message.sysid != _id && message.sysid != 0) { // We allow RADIO_STATUS messages which come from a link the vehicle is using to pass through and be handled if (!(message.msgid == MAVLINK_MSG_ID_RADIO_STATUS && _containsLink(link))) { @@ -497,12 +505,6 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes if (!_containsLink(link)) { _addLink(link); - - // if the minimum supported version of MAVLink is already 2.0 - // set our max proto version to it. - if (_mavlink->getCurrentVersion() >= 200) { - _maxProtoVersion = _mavlink->getCurrentVersion(); - } } //-- Check link status @@ -839,6 +841,7 @@ void Vehicle::_setMaxProtoVersion(unsigned version) { // Set only once or if we need to reduce the max version if (_maxProtoVersion == 0 || version < _maxProtoVersion) { + qCDebug(VehicleLog) << "_setMaxProtoVersion before:after" << _maxProtoVersion << version; _maxProtoVersion = version; emit requestProtocolVersion(_maxProtoVersion); @@ -873,60 +876,6 @@ void Vehicle::_handleHilActuatorControls(mavlink_message_t &message) hil.mode); } -void Vehicle::_handleCommandAck(mavlink_message_t& message) -{ - bool showError = false; - - mavlink_command_ack_t ack; - mavlink_msg_command_ack_decode(&message, &ack); - - if (ack.command == MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES && ack.result != MAV_RESULT_ACCEPTED) { - // We aren't going to get a response back for capabilities, so stop waiting for it before we ask for mission items - qCDebug(VehicleLog) << "Vehicle failed to responded to MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES with error. Starting mission request."; - _setCapabilities(0); - } - - if (ack.command == MAV_CMD_REQUEST_PROTOCOL_VERSION && ack.result != MAV_RESULT_ACCEPTED) { - // The autopilot does not understand the request and consequently is likely handling only - // MAVLink 1 - if (_maxProtoVersion == 0) { - _setMaxProtoVersion(100); - } - } - - if (_mavCommandQueue.count() && ack.command == _mavCommandQueue[0].command) { - _mavCommandAckTimer.stop(); - showError = _mavCommandQueue[0].showError; - _mavCommandQueue.removeFirst(); - } - - emit mavCommandResult(_id, message.compid, ack.command, ack.result, false /* noResponsefromVehicle */); - - if (showError) { - QString commandName = _toolbox->missionCommandTree()->friendlyName((MAV_CMD)ack.command); - - switch (ack.result) { - case MAV_RESULT_TEMPORARILY_REJECTED: - qgcApp()->showMessage(tr("%1 command temporarily rejected").arg(commandName)); - break; - case MAV_RESULT_DENIED: - qgcApp()->showMessage(tr("%1 command denied").arg(commandName)); - break; - case MAV_RESULT_UNSUPPORTED: - qgcApp()->showMessage(tr("%1 command not supported").arg(commandName)); - break; - case MAV_RESULT_FAILED: - qgcApp()->showMessage(tr("%1 command failed").arg(commandName)); - break; - default: - // Do nothing - break; - } - } - - _sendNextQueuedMavCommand(); -} - void Vehicle::_handleCommandLong(mavlink_message_t& message) { #ifdef __ios__ @@ -2369,6 +2318,7 @@ void Vehicle::_sendMavCommandAgain(void) if (_mavCommandRetryCount++ > _mavCommandMaxRetryCount) { if (queuedCommand.command == MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES) { // We aren't going to get a response back for capabilities, so stop waiting for it before we ask for mission items + qCDebug(VehicleLog) << "Vehicle failed to responded to MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES. Setting no capabilities. Starting Plan request."; _setCapabilities(0); _startPlanRequest(); } @@ -2376,8 +2326,12 @@ void Vehicle::_sendMavCommandAgain(void) if (queuedCommand.command == MAV_CMD_REQUEST_PROTOCOL_VERSION) { // We aren't going to get a response back for the protocol version, so assume v1 is all we can do. // If the max protocol version is uninitialized, fall back to v1. + qCDebug(VehicleLog) << "Vehicle failed to responded to MAV_CMD_REQUEST_PROTOCOL_VERSION. Starting Plan request."; if (_maxProtoVersion == 0) { + qCDebug(VehicleLog) << "Setting _maxProtoVersion to 100 since not yet set."; _setMaxProtoVersion(100); + } else { + qCDebug(VehicleLog) << "Leaving _maxProtoVersion at current value" << _maxProtoVersion; } } @@ -2449,6 +2403,66 @@ void Vehicle::_sendNextQueuedMavCommand(void) } +void Vehicle::_handleCommandAck(mavlink_message_t& message) +{ + bool showError = false; + + mavlink_command_ack_t ack; + mavlink_msg_command_ack_decode(&message, &ack); + + if (ack.command == MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES && ack.result != MAV_RESULT_ACCEPTED) { + // We aren't going to get a response back for capabilities, so stop waiting for it before we ask for mission items + qCDebug(VehicleLog) << QStringLiteral("Vehicle responded to MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES with error(%1). Setting no capabilities. Starting Plan request.").arg(ack.result); + _setCapabilities(0); + } + + if (ack.command == MAV_CMD_REQUEST_PROTOCOL_VERSION && ack.result != MAV_RESULT_ACCEPTED) { + // The autopilot does not understand the request and consequently is likely handling only + // MAVLink 1 + qCDebug(VehicleLog) << QStringLiteral("Vehicle responded to MAV_CMD_REQUEST_PROTOCOL_VERSION with error(%1).").arg(ack.result); + if (_maxProtoVersion == 0) { + qCDebug(VehicleLog) << "Setting _maxProtoVersion to 100 since not yet set."; + _setMaxProtoVersion(100); + } else { + qCDebug(VehicleLog) << "Leaving _maxProtoVersion at current value" << _maxProtoVersion; + } + // FIXME: Is this missing here. I believe it is a bug. Debug to verify. May need to go into Stable. + //_startPlanRequest(); + } + + if (_mavCommandQueue.count() && ack.command == _mavCommandQueue[0].command) { + _mavCommandAckTimer.stop(); + showError = _mavCommandQueue[0].showError; + _mavCommandQueue.removeFirst(); + } + + emit mavCommandResult(_id, message.compid, ack.command, ack.result, false /* noResponsefromVehicle */); + + if (showError) { + QString commandName = _toolbox->missionCommandTree()->friendlyName((MAV_CMD)ack.command); + + switch (ack.result) { + case MAV_RESULT_TEMPORARILY_REJECTED: + qgcApp()->showMessage(tr("%1 command temporarily rejected").arg(commandName)); + break; + case MAV_RESULT_DENIED: + qgcApp()->showMessage(tr("%1 command denied").arg(commandName)); + break; + case MAV_RESULT_UNSUPPORTED: + qgcApp()->showMessage(tr("%1 command not supported").arg(commandName)); + break; + case MAV_RESULT_FAILED: + qgcApp()->showMessage(tr("%1 command failed").arg(commandName)); + break; + default: + // Do nothing + break; + } + } + + _sendNextQueuedMavCommand(); +} + void Vehicle::setPrearmError(const QString& prearmError) { _prearmError = prearmError; diff --git a/src/comm/MAVLinkProtocol.cc b/src/comm/MAVLinkProtocol.cc index 6175a52ef97ae077b56a66100ab902cfd72696b3..da4fe7d7fb11559afee5efe7cbdffb42376ae243 100644 --- a/src/comm/MAVLinkProtocol.cc +++ b/src/comm/MAVLinkProtocol.cc @@ -382,8 +382,6 @@ void MAVLinkProtocol::_vehicleCountChanged(void) if (count == 0) { // Last vehicle is gone, close out logging _stopLogging(); - // Reset protocol version handling - _current_version = 0; _radio_version_mismatch_count = 0; } }