Commit a1c653fe authored by Ban Siesta's avatar Ban Siesta

UASWaypointManager: accept single waypoint messages in order to update the...

UASWaypointManager: accept single waypoint messages in order to update the remaining DO_JUMP repetitions
parent 6fdce352
......@@ -220,6 +220,16 @@ void UASWaypointManager::handleWaypoint(quint8 systemId, quint8 compId, mavlink_
} else {
emit updateStatusString(tr("Waypoint ID mismatch, rejecting waypoint"));
}
} else if (systemId == current_partner_systemid
&& wp->seq < waypointsViewOnly.size() && waypointsViewOnly[wp->seq]->getAction()) {
// accept single sent waypoints because they can contain updates about remaining DO_JUMP repetitions
// but only update view only side
Waypoint *lwp_vo = new Waypoint(wp->seq, wp->x, wp->y, wp->z, wp->param1, wp->param2, wp->param3, wp->param4, wp->autocontinue, wp->current, (MAV_FRAME) wp->frame, (MAV_CMD) wp->command);
waypointsViewOnly.replace(wp->seq, lwp_vo);
emit waypointViewOnlyListChanged();
emit waypointViewOnlyListChanged(uasid);
} else {
qDebug("Rejecting waypoint message, check mismatch: current_state: %d == %d, system id %d == %d, comp id %d == %d", current_state, WP_GETLIST_GETWPS, current_partner_systemid, systemId, current_partner_compid, compId);
}
......
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