Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion src/FlyView/FlyViewMap.qml
Original file line number Diff line number Diff line change
Expand Up @@ -709,7 +709,7 @@ FlightMap {
visible: globals.guidedControllerFlyView.showROI
onClicked: {
mapClickDropPanel.close()
globals.guidedControllerFlyView.executeAction(globals.guidedControllerFlyView.actionROI, mapClickCoord, 0, false)
globals.guidedControllerFlyView.confirmAction(globals.guidedControllerFlyView.actionROI, mapClickCoord)
}
}

Expand Down
9 changes: 7 additions & 2 deletions src/FlyView/GuidedActionsController.qml
Original file line number Diff line number Diff line change
Expand Up @@ -225,7 +225,7 @@ Item {
} else {
console.error("setupSlider called for inapproproate change speed action", _vehicleInFwdFlight, _activeVehicle.haveMRSpeedLimits)
}
} else if (actionCode === actionChangeAlt || actionCode === actionOrbit || actionCode === actionGoto || actionCode === actionPause) {
} else if (actionCode === actionChangeAlt || actionCode === actionOrbit || actionCode === actionROI || actionCode === actionGoto || actionCode === actionPause) {
guidedValueSlider.setupSlider(
GuidedValueSlider.SliderType.Altitude,
_flyViewSettings.guidedMinimumAltitude.value,
Expand Down Expand Up @@ -656,7 +656,12 @@ Item {
}
break
case actionROI:
_activeVehicle.guidedModeROI(actionData)
var roiCoordinate = actionData
var valueInMeters = _unitsConversion.appSettingsVerticalDistanceUnitsToMeters(sliderOutputValue)
if (!isNaN(valueInMeters)) {
roiCoordinate = QtPositioning.coordinate(actionData.latitude, actionData.longitude, valueInMeters)
}
_activeVehicle.guidedModeROI(roiCoordinate)
break
case actionChangeSpeed:
if (_activeVehicle) {
Expand Down
12 changes: 10 additions & 2 deletions src/Vehicle/TerrainQueryCoordinator.cc
Original file line number Diff line number Diff line change
Expand Up @@ -84,7 +84,7 @@ void TerrainQueryCoordinator::_doSetHomeTerrainReceived(bool success, QList<doub
_doSetHomeCoordinate = QGeoCoordinate(); // Invalidate for extra safety
}

void TerrainQueryCoordinator::roiWithTerrain(const QGeoCoordinate& coord)
void TerrainQueryCoordinator::roiWithTerrain(const QGeoCoordinate& coord, double relativeAltitude)
{
if (!coord.isValid()) {
return;
Expand All @@ -97,6 +97,7 @@ void TerrainQueryCoordinator::roiWithTerrain(const QGeoCoordinate& coord)
}

_roiCoordinate = coord;
_roiRelativeAltitude = relativeAltitude;

_roiQuery = new TerrainAtCoordinateQuery(true /* autoDelete */);
connect(_roiQuery, &TerrainAtCoordinateQuery::terrainDataReceived,
Expand All @@ -112,6 +113,7 @@ void TerrainQueryCoordinator::_roiTerrainReceived(bool success, QList<double> he
_roiQuery = nullptr;

if (!_roiCoordinate.isValid()) {
_roiRelativeAltitude = qQNaN();
return;
}

Expand All @@ -123,13 +125,19 @@ void TerrainQueryCoordinator::_roiTerrainReceived(bool success, QList<double> he
roiAltitude = static_cast<float>(_vehicle->homePosition().altitude());
}

if (!qIsNaN(_roiRelativeAltitude)) {
roiAltitude += static_cast<float>(_roiRelativeAltitude);
}

qCDebug(TerrainQueryCoordinatorLog) << "roiWithTerrain: lat" << _roiCoordinate.latitude()
<< "lon" << _roiCoordinate.longitude()
<< "terrainAltAMSL" << roiAltitude << "success" << success;
<< "altAMSL" << roiAltitude << "success" << success
<< "relativeAlt" << _roiRelativeAltitude;

sendROICommand(_roiCoordinate, MAV_FRAME_GLOBAL, roiAltitude);

_roiCoordinate = QGeoCoordinate();
_roiRelativeAltitude = qQNaN();
}

void TerrainQueryCoordinator::sendROICommand(const QGeoCoordinate& coord, MAV_FRAME frame, float altitude)
Expand Down
5 changes: 3 additions & 2 deletions src/Vehicle/TerrainQueryCoordinator.h
Original file line number Diff line number Diff line change
Expand Up @@ -37,8 +37,8 @@ class TerrainQueryCoordinator : public QObject

/// PX4 ROI flow. Starts a terrain query; when it resolves, sends
/// MAV_CMD_DO_SET_ROI_LOCATION in MAV_FRAME_GLOBAL at the resolved altitude
/// (falling back to home altitude on query failure).
void roiWithTerrain(const QGeoCoordinate& coord);
/// or at resolved altitude plus requested relative altitude.
void roiWithTerrain(const QGeoCoordinate& coord, double relativeAltitude = qQNaN());

/// Build + send MAV_CMD_DO_SET_ROI_LOCATION directly (no terrain query).
/// Used by the ArduPilot MAV_FRAME_GLOBAL_RELATIVE_ALT direct path.
Expand All @@ -62,6 +62,7 @@ private slots:

QPointer<TerrainAtCoordinateQuery> _roiQuery;
QGeoCoordinate _roiCoordinate;
double _roiRelativeAltitude = qQNaN();

QElapsedTimer _altQueryTimer;
QPointer<TerrainAtCoordinateQuery> _altQuery;
Expand Down
2 changes: 1 addition & 1 deletion src/Vehicle/Vehicle.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1985,7 +1985,7 @@ void Vehicle::guidedModeROI(const QGeoCoordinate& centerCoord)
if (px4Firmware()) {
// PX4 ignores the coordinate frame in COMMAND_INT and treats the altitude as AMSL,
// so a terrain query is required before we can send the ROI command.
_terrainQueryCoordinator->roiWithTerrain(centerCoord);
_terrainQueryCoordinator->roiWithTerrain(centerCoord, centerCoord.altitude());
} else {
// ArduPilot handles MAV_FRAME_GLOBAL_RELATIVE_ALT correctly, so altitude 0 relative to
// home is a reasonable default for a map click with no altitude info.
Expand Down
Loading