Commit 46f961b2 authored by Don Gagne's avatar Don Gagne

parents ac05923f c5396510
...@@ -14,6 +14,13 @@ Note: This file only contains high level features or important fixes. ...@@ -14,6 +14,13 @@ Note: This file only contains high level features or important fixes.
## 3.4 ## 3.4
### 3.4.5 - Not yet released
* Plan GeoFence: Fix loading of fence from intermediate 3.4 code
* Orbit: Turn off for PX4 since still not supported
* Structure Scan: Fix loading of structure scan height
* ArduPilot: Fix location of planned home position when not connected to vehicle. Issue #6840.
* Fix loading of parameters from multiple components. Would report download complete too early, thus missing all default component params.
### 3.4.4 - Stable ### 3.4.4 - Stable
* Stable desktop versions now inform user at boot if newer version is available. * Stable desktop versions now inform user at boot if newer version is available.
* Multi-Vehicle Start Mission and Pause now work correctly. Issue #6864. * Multi-Vehicle Start Mission and Pause now work correctly. Issue #6864.
......
...@@ -347,12 +347,12 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString ...@@ -347,12 +347,12 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString
// Add meta data to default component. We need to do this before we setup the group map since group // Add meta data to default component. We need to do this before we setup the group map since group
// map requires meta data. // map requires meta data.
_addMetaDataToDefaultComponent(); _addMetaDataToDefaultComponent();
}
// When we are getting the very last component param index, reset the group maps to update for the // When we are getting the very last component param index, reset the group maps to update for the
// new params. By handling this here, we can pick up components which finish up later than the default // new params. By handling this here, we can pick up components which finish up later than the default
// component param set. // component param set.
_setupCategoryMap(); _setupCategoryMap();
}
} }
// Update param cache. The param cache is only used on PX4 Firmware since ArduPilot and Solo have volatile params // Update param cache. The param cache is only used on PX4 Firmware since ArduPilot and Solo have volatile params
......
...@@ -233,7 +233,7 @@ bool PX4FirmwarePlugin::isCapable(const Vehicle *vehicle, FirmwareCapabilities c ...@@ -233,7 +233,7 @@ bool PX4FirmwarePlugin::isCapable(const Vehicle *vehicle, FirmwareCapabilities c
{ {
int available = SetFlightModeCapability | PauseVehicleCapability | GuidedModeCapability; int available = SetFlightModeCapability | PauseVehicleCapability | GuidedModeCapability;
if (vehicle->multiRotor() || vehicle->vtol()) { if (vehicle->multiRotor() || vehicle->vtol()) {
available |= TakeoffVehicleCapability | OrbitModeCapability; available |= TakeoffVehicleCapability;
} }
return (capabilities & available) == capabilities; return (capabilities & available) == capabilities;
......
...@@ -123,8 +123,9 @@ bool GeoFenceController::load(const QJsonObject& json, QString& errorString) ...@@ -123,8 +123,9 @@ bool GeoFenceController::load(const QJsonObject& json, QString& errorString)
errorString.clear(); errorString.clear();
if (json.contains(JsonHelper::jsonVersionKey) && json[JsonHelper::jsonVersionKey].toInt() == 1) { if (!json.contains(JsonHelper::jsonVersionKey) ||
// We just ignore old version 1 data (json.contains(JsonHelper::jsonVersionKey) && json[JsonHelper::jsonVersionKey].toInt() == 1)) {
// We just ignore old version 1 or prior data
return true; return true;
} }
......
...@@ -375,7 +375,9 @@ int MissionController::insertSimpleMissionItem(QGeoCoordinate coordinate, int i) ...@@ -375,7 +375,9 @@ int MissionController::insertSimpleMissionItem(QGeoCoordinate coordinate, int i)
newItem->setMissionFlightStatus(_missionFlightStatus); newItem->setMissionFlightStatus(_missionFlightStatus);
_visualItems->insert(i, newItem); _visualItems->insert(i, newItem);
_recalcAll(); // We send the click coordinate through here to be able to set the planned home position from the user click location if needed
_recalcAllWithClickCoordinate(coordinate);
return newItem->sequenceNumber(); return newItem->sequenceNumber();
} }
...@@ -1526,8 +1528,10 @@ void MissionController::_recalcChildItems(void) ...@@ -1526,8 +1528,10 @@ void MissionController::_recalcChildItems(void)
} }
} }
void MissionController::_setPlannedHomePositionFromFirstCoordinate(void) void MissionController::_setPlannedHomePositionFromFirstCoordinate(const QGeoCoordinate& clickCoordinate)
{ {
QGeoCoordinate firstCoordinate;
if (_settingsItem->coordinate().isValid()) { if (_settingsItem->coordinate().isValid()) {
return; return;
} }
...@@ -1537,18 +1541,28 @@ void MissionController::_setPlannedHomePositionFromFirstCoordinate(void) ...@@ -1537,18 +1541,28 @@ void MissionController::_setPlannedHomePositionFromFirstCoordinate(void)
VisualMissionItem* item = _visualItems->value<VisualMissionItem*>(i); VisualMissionItem* item = _visualItems->value<VisualMissionItem*>(i);
if (item->specifiesCoordinate()) { if (item->specifiesCoordinate()) {
QGeoCoordinate plannedHomeCoord = item->coordinate().atDistanceAndAzimuth(30, 0); firstCoordinate = item->coordinate();
plannedHomeCoord.setAltitude(0); break;
_settingsItem->setCoordinate(plannedHomeCoord);
} }
} }
}
// No item specifying a coordinate was found, in this case it we have a clickCoordinate use that
if (!firstCoordinate.isValid()) {
firstCoordinate = clickCoordinate;
}
void MissionController::_recalcAll(void) if (firstCoordinate.isValid()) {
QGeoCoordinate plannedHomeCoord = firstCoordinate.atDistanceAndAzimuth(30, 0);
plannedHomeCoord.setAltitude(0);
_settingsItem->setCoordinate(plannedHomeCoord);
}
}
/// @param clickCoordinate The location of the user click when inserting a new item
void MissionController::_recalcAllWithClickCoordinate(QGeoCoordinate& clickCoordinate)
{ {
if (!_flyView) { if (!_flyView) {
_setPlannedHomePositionFromFirstCoordinate(); _setPlannedHomePositionFromFirstCoordinate(clickCoordinate);
} }
_recalcSequence(); _recalcSequence();
_recalcChildItems(); _recalcChildItems();
...@@ -1556,6 +1570,12 @@ void MissionController::_recalcAll(void) ...@@ -1556,6 +1570,12 @@ void MissionController::_recalcAll(void)
_updateTimer.start(UPDATE_TIMEOUT); _updateTimer.start(UPDATE_TIMEOUT);
} }
void MissionController::_recalcAll(void)
{
QGeoCoordinate emptyCoord;
_recalcAllWithClickCoordinate(emptyCoord);
}
/// Initializes a new set of mission items /// Initializes a new set of mission items
void MissionController::_initAllVisualItems(void) void MissionController::_initAllVisualItems(void)
{ {
......
...@@ -234,12 +234,13 @@ private slots: ...@@ -234,12 +234,13 @@ private slots:
void _managerRemoveAllComplete(bool error); void _managerRemoveAllComplete(bool error);
void _updateTimeout(); void _updateTimeout();
void _complexBoundingBoxChanged(); void _complexBoundingBoxChanged();
void _recalcAll(void);
private: private:
void _init(void); void _init(void);
void _recalcSequence(void); void _recalcSequence(void);
void _recalcChildItems(void); void _recalcChildItems(void);
void _recalcAll(void); void _recalcAllWithClickCoordinate(QGeoCoordinate& clickCoordinate);
void _initAllVisualItems(void); void _initAllVisualItems(void);
void _deinitAllVisualItems(void); void _deinitAllVisualItems(void);
void _initVisualItem(VisualMissionItem* item); void _initVisualItem(VisualMissionItem* item);
...@@ -258,7 +259,7 @@ private: ...@@ -258,7 +259,7 @@ private:
int _nextSequenceNumber(void); int _nextSequenceNumber(void);
void _scanForAdditionalSettings(QmlObjectListModel* visualItems, Vehicle* vehicle); void _scanForAdditionalSettings(QmlObjectListModel* visualItems, Vehicle* vehicle);
static bool _convertToMissionItems(QmlObjectListModel* visualMissionItems, QList<MissionItem*>& rgMissionItems, QObject* missionItemParent); static bool _convertToMissionItems(QmlObjectListModel* visualMissionItems, QList<MissionItem*>& rgMissionItems, QObject* missionItemParent);
void _setPlannedHomePositionFromFirstCoordinate(void); void _setPlannedHomePositionFromFirstCoordinate(const QGeoCoordinate& clickCoordinate);
void _resetMissionFlightStatus(void); void _resetMissionFlightStatus(void);
void _addHoverTime(double hoverTime, double hoverDistance, int waypointIndex); void _addHoverTime(double hoverTime, double hoverDistance, int waypointIndex);
void _addCruiseTime(double cruiseTime, double cruiseDistance, int wayPointIndex); void _addCruiseTime(double cruiseTime, double cruiseDistance, int wayPointIndex);
......
...@@ -135,9 +135,8 @@ void MissionControllerTest::_testAddWaypointWorker(MAV_AUTOPILOT firmwareType) ...@@ -135,9 +135,8 @@ void MissionControllerTest::_testAddWaypointWorker(MAV_AUTOPILOT firmwareType)
QCOMPARE((MAV_CMD)simpleItem->command(), MAV_CMD_NAV_TAKEOFF); QCOMPARE((MAV_CMD)simpleItem->command(), MAV_CMD_NAV_TAKEOFF);
QCOMPARE(simpleItem->childItems()->count(), 0); QCOMPARE(simpleItem->childItems()->count(), 0);
// If the first item added specifies a coordinate, then planned home position will be set // Planned home position should always be set after first item
bool plannedHomePositionValue = firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA ? false : true; QVERIFY(settingsItem->coordinate().isValid());
QCOMPARE(settingsItem->coordinate().isValid(), plannedHomePositionValue);
// ArduPilot takeoff command has no coordinate, so should be child item // ArduPilot takeoff command has no coordinate, so should be child item
QCOMPARE(settingsItem->childItems()->count(), firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA ? 1 : 0); QCOMPARE(settingsItem->childItems()->count(), firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA ? 1 : 0);
......
...@@ -28,6 +28,7 @@ ...@@ -28,6 +28,7 @@
"name": "StructureHeight", "name": "StructureHeight",
"shortDescription": "Height of structure being scanned.", "shortDescription": "Height of structure being scanned.",
"type": "double", "type": "double",
"decimalPlaces": 2,
"units": "m", "units": "m",
"min": 1, "min": 1,
"defaultValue": 100 "defaultValue": 100
......
...@@ -215,9 +215,11 @@ bool StructureScanComplexItem::load(const QJsonObject& complexObject, int sequen ...@@ -215,9 +215,11 @@ bool StructureScanComplexItem::load(const QJsonObject& complexObject, int sequen
return false; return false;
} }
_altitudeFact.setRawValue (complexObject[altitudeName].toDouble()); _altitudeFact.setRawValue (complexObject[altitudeName].toDouble());
_layersFact.setRawValue (complexObject[layersName].toDouble()); _layersFact.setRawValue (complexObject[layersName].toDouble());
_altitudeRelative = complexObject[_jsonAltitudeRelativeKey].toBool(true); _structureHeightFact.setRawValue(complexObject[structureHeightName].toDouble());
_altitudeRelative = complexObject[_jsonAltitudeRelativeKey].toBool(true);
double gimbalPitchValue = 0; double gimbalPitchValue = 0;
if (complexObject.contains(gimbalPitchName)) { if (complexObject.contains(gimbalPitchName)) {
......
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