Browse Source

APM Mission fixes

QGC4.4
DonLakeFlyer 10 years ago
parent
commit
2390c57366
  1. 2
      src/MissionManager/MissionController.cc
  2. 5
      src/MissionManager/MissionManager.cc

2
src/MissionManager/MissionController.cc

@ -435,7 +435,7 @@ void MissionController::_initAllMissionItems(void)
homeItem->setCoordinate(_activeVehicle->homePosition()); homeItem->setCoordinate(_activeVehicle->homePosition());
homeItem->setHomePositionValid(_activeVehicle->homePositionAvailable()); homeItem->setHomePositionValid(_activeVehicle->homePositionAvailable());
} }
homeItem->setCommand(MavlinkQmlSingleton::MAV_CMD_NAV_LAST); homeItem->setCommand(MAV_CMD_NAV_WAYPOINT);
homeItem->setFrame(MAV_FRAME_GLOBAL_RELATIVE_ALT); homeItem->setFrame(MAV_FRAME_GLOBAL_RELATIVE_ALT);
homeItem->setSequenceNumber(0); homeItem->setSequenceNumber(0);
_missionItems->insert(0, homeItem); _missionItems->insert(0, homeItem);

5
src/MissionManager/MissionManager.cc

@ -368,7 +368,7 @@ void MissionManager::_handleMissionAck(const mavlink_message_t& message)
{ {
mavlink_mission_ack_t missionAck; mavlink_mission_ack_t missionAck;
// Save th retry ack before calling _stopAckTimeout since we'll need it to determine what // Save the retry ack before calling _stopAckTimeout since we'll need it to determine what
// type of a protocol sequence we are in. // type of a protocol sequence we are in.
AckType_t savedRetryAck = _retryAck; AckType_t savedRetryAck = _retryAck;
@ -418,7 +418,8 @@ void MissionManager::_handleMissionAck(const mavlink_message_t& message)
} else { } else {
qCDebug(MissionManagerLog) << "_handleMissionAck ack error:" << _missionResultToString((MAV_MISSION_RESULT)missionAck.type); qCDebug(MissionManagerLog) << "_handleMissionAck ack error:" << _missionResultToString((MAV_MISSION_RESULT)missionAck.type);
if (!_retrySequence(AckMissionRequest)) { if (!_retrySequence(AckMissionRequest)) {
_sendError(VehicleError, QString("Vehicle returned error: %1. Vehicle only has partial list of mission items.").arg(_missionResultToString((MAV_MISSION_RESULT)missionAck.type))); _sendError(VehicleError,
QString("Vehicle returned error: %1 on item %2. Vehicle only has partial list of mission items.").arg(_missionResultToString((MAV_MISSION_RESULT)missionAck.type)).arg(_expectedSequenceNumber));
} }
} }
break; break;

Loading…
Cancel
Save