Unverified Commit 141239cc authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #6659 from DonLakeFlyer/PlanToolOrbitFix

Fix broken Plan tools, fix broken orbit location
parents 3a839770 3d929513
......@@ -369,7 +369,7 @@ FlightMap {
clickMenu.coord = clickCoord
clickMenu.popup()
} else if (guidedActionsController.showGotoLocation) {
_guidedLocationCoordinate = clickCoord
gotoLocationItem.show(clickCoord)
guidedActionsController.confirmAction(guidedActionsController.actionGoto, clickCoord)
} else if (guidedActionsController.showOrbit) {
orbitMapCircle.show(clickCoord)
......
......@@ -572,15 +572,15 @@ QGCView {
onClicked: {
switch (index) {
case 0:
case 1:
_addWaypointOnClick = checked
_addROIOnClick = false
break
case 1:
case 2:
_addROIOnClick = checked
_addWaypointOnClick = false
break
case 2:
case 3:
if (_singleComplexItem) {
addComplexItem(_missionController.complexMissionItemNames[0])
}
......
......@@ -2780,15 +2780,6 @@ void Vehicle::guidedModeOrbit(const QGeoCoordinate& centerCoord, double radius,
return;
}
double lat, lon, alt;
if (centerCoord.isValid()) {
lat = lon = alt = qQNaN();
} else {
lat = centerCoord.latitude();
lon = centerCoord.longitude();
alt = amslAltitude;
}
if (capabilityBits() && MAV_PROTOCOL_CAPABILITY_COMMAND_INT) {
sendMavCommandInt(defaultComponentId(),
MAV_CMD_DO_ORBIT,
......@@ -2798,7 +2789,7 @@ void Vehicle::guidedModeOrbit(const QGeoCoordinate& centerCoord, double radius,
qQNaN(), // Use default velocity
0, // Vehicle points to center
qQNaN(), // reserved
lat, lon, alt);
centerCoord.latitude(), centerCoord.longitude(), amslAltitude);
} else {
sendMavCommand(defaultComponentId(),
MAV_CMD_DO_ORBIT,
......@@ -2807,7 +2798,7 @@ void Vehicle::guidedModeOrbit(const QGeoCoordinate& centerCoord, double radius,
qQNaN(), // Use default velocity
0, // Vehicle points to center
qQNaN(), // reserved
lat, lon, alt);
centerCoord.latitude(), centerCoord.longitude(), amslAltitude);
}
}
......
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