Skip to content

Commit b2e24d7

Browse files
rubenp02DonLakeFlyer
authored andcommitted
Add Go here circle visuals if in forward flight
Added circle visuals to the Go here map item to show the orbit pattern that aircraft in forward flight will follow upon reaching the position. This feature is already available in firmware that supports the ORBIT_EXECUTION_STATUS MAVLink message, so this is only shown for vehicles operating on firmware that lacks this support.
1 parent dd48f38 commit b2e24d7

File tree

1 file changed

+38
-0
lines changed

1 file changed

+38
-0
lines changed

src/FlightDisplay/FlyViewMap.qml

Lines changed: 38 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -368,6 +368,44 @@ FlightMap {
368368
}
369369
}
370370

371+
// GoTo Location forward flight circle visuals
372+
QGCMapCircleVisuals {
373+
id: fwdFlightGotoMapCircle
374+
mapControl: parent
375+
mapCircle: _fwdFlightGotoMapCircle
376+
visible: gotoLocationItem.visible && _activeVehicle &&
377+
_activeVehicle.inFwdFlight &&
378+
!_activeVehicle.orbitActive
379+
380+
Connections {
381+
target: QGroundControl.multiVehicleManager
382+
function onActiveVehicleChanged(activeVehicle) {
383+
if (!activeVehicle) {
384+
visible = false
385+
}
386+
}
387+
}
388+
389+
Binding {
390+
target: _fwdFlightGotoMapCircle
391+
property: "center"
392+
value: gotoLocationItem.coordinate
393+
}
394+
395+
QGCMapCircle {
396+
id: _fwdFlightGotoMapCircle
397+
interactive: false
398+
showRotation: true
399+
clockwiseRotation: true
400+
401+
property real _defaultLoiterRadius: _flyViewSettings.forwardFlightGoToLocationLoiterRad.value
402+
403+
onCenterChanged: {
404+
radius.rawValue = _defaultLoiterRadius
405+
}
406+
}
407+
}
408+
371409
// GoTo Location visuals
372410
MapQuickItem {
373411
id: gotoLocationItem

0 commit comments

Comments
 (0)