Browse Source

Show correct item editor based on current VTOL state

QGC4.4
DonLakeFlyer 5 years ago
parent
commit
c2bfd944ad
  1. 4
      src/MissionManager/CameraSectionTest.cc
  2. 2
      src/MissionManager/KMLPlanDomDocument.cc
  3. 2
      src/MissionManager/MavCmdInfoFixedWing.json
  4. 23
      src/MissionManager/MissionCommandTree.cc
  5. 6
      src/MissionManager/MissionCommandTree.h
  6. 6
      src/MissionManager/MissionCommandTreeTest.cc
  7. 8
      src/MissionManager/MissionController.cc
  8. 4
      src/MissionManager/MissionManager.cc
  9. 42
      src/MissionManager/SimpleMissionItem.cc
  10. 1
      src/MissionManager/SimpleMissionItem.h
  11. 2
      src/MissionManager/TakeoffMissionItem.cc
  12. 11
      src/MissionManager/VisualMissionItem.cc
  13. 4
      src/MissionManager/VisualMissionItem.h

4
src/MissionManager/CameraSectionTest.cc

@ -1057,7 +1057,7 @@ void CameraSectionTest::_testScanForMultipleItems(void)
item2->missionItem() = cameraItem->missionItem(); item2->missionItem() = cameraItem->missionItem();
visualItems.append(item1); visualItems.append(item1);
visualItems.append(item2); visualItems.append(item2);
qDebug() << commandTree->getUIInfo(_controllerVehicle, (MAV_CMD)item1->command())->rawName() << commandTree->getUIInfo(_controllerVehicle, (MAV_CMD)item2->command())->rawName();; qDebug() << commandTree->getUIInfo(_controllerVehicle, QGCMAVLink::VehicleClassGeneric, (MAV_CMD)item1->command())->rawName() << commandTree->getUIInfo(_controllerVehicle, QGCMAVLink::VehicleClassGeneric, (MAV_CMD)item2->command())->rawName();;
scanIndex = 0; scanIndex = 0;
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), true); QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), true);
@ -1078,7 +1078,7 @@ void CameraSectionTest::_testScanForMultipleItems(void)
item2->missionItem() = cameraItem->missionItem(); item2->missionItem() = cameraItem->missionItem();
visualItems.append(item1); visualItems.append(item1);
visualItems.append(item2); visualItems.append(item2);
qDebug() << commandTree->getUIInfo(_controllerVehicle, (MAV_CMD)item1->command())->rawName() << commandTree->getUIInfo(_controllerVehicle, (MAV_CMD)item2->command())->rawName();; qDebug() << commandTree->getUIInfo(_controllerVehicle, QGCMAVLink::VehicleClassGeneric, (MAV_CMD)item1->command())->rawName() << commandTree->getUIInfo(_controllerVehicle, QGCMAVLink::VehicleClassGeneric, (MAV_CMD)item2->command())->rawName();;
scanIndex = 0; scanIndex = 0;
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), true); QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), true);

2
src/MissionManager/KMLPlanDomDocument.cc

@ -51,7 +51,7 @@ void KMLPlanDomDocument::_addFlightPath(Vehicle* vehicle, QList<MissionItem*> rg
QList<QGeoCoordinate> rgFlightCoords; QList<QGeoCoordinate> rgFlightCoords;
QGeoCoordinate homeCoord = rgMissionItems[0]->coordinate(); QGeoCoordinate homeCoord = rgMissionItems[0]->coordinate();
for (const MissionItem* item : rgMissionItems) { for (const MissionItem* item : rgMissionItems) {
const MissionCommandUIInfo* uiInfo = qgcApp()->toolbox()->missionCommandTree()->getUIInfo(vehicle, item->command()); const MissionCommandUIInfo* uiInfo = qgcApp()->toolbox()->missionCommandTree()->getUIInfo(vehicle, QGCMAVLink::VehicleClassGeneric, item->command());
if (uiInfo) { if (uiInfo) {
double altAdjustment = item->frame() == MAV_FRAME_GLOBAL ? 0 : homeCoord.altitude(); // Used to convert to amsl double altAdjustment = item->frame() == MAV_FRAME_GLOBAL ? 0 : homeCoord.altitude(); // Used to convert to amsl
if (uiInfo->isTakeoffCommand() && !vehicle->fixedWing()) { if (uiInfo->isTakeoffCommand() && !vehicle->fixedWing()) {

2
src/MissionManager/MavCmdInfoFixedWing.json

@ -7,7 +7,7 @@
{ {
"id": 16, "id": 16,
"comment": "MAV_CMD_NAV_WAYPOINT", "comment": "MAV_CMD_NAV_WAYPOINT",
"paramRemove": "4" "paramRemove": "1,4"
}, },
{ {
"id": 17, "id": 17,

23
src/MissionManager/MissionCommandTree.cc

@ -81,12 +81,12 @@ void MissionCommandTree::_collapseHierarchy(const MissionCommandList*
} }
} }
void MissionCommandTree::_buildAllCommands(Vehicle* vehicle) void MissionCommandTree::_buildAllCommands(Vehicle* vehicle, QGCMAVLink::VehicleClass_t vtolMode)
{ {
QGCMAVLink::FirmwareClass_t firmwareClass; QGCMAVLink::FirmwareClass_t firmwareClass;
QGCMAVLink::VehicleClass_t vehicleClass; QGCMAVLink::VehicleClass_t vehicleClass;
_firmwareAndVehicleClassInfo(vehicle, firmwareClass, vehicleClass); _firmwareAndVehicleClassInfo(vehicle, vtolMode, firmwareClass, vehicleClass);
if (_allCommands.contains(firmwareClass) && _allCommands[firmwareClass].contains(vehicleClass)) { if (_allCommands.contains(firmwareClass) && _allCommands[firmwareClass].contains(vehicleClass)) {
// Already built // Already built
@ -131,8 +131,8 @@ QStringList MissionCommandTree::_availableCategoriesForVehicle(Vehicle* vehicle)
QGCMAVLink::FirmwareClass_t firmwareClass; QGCMAVLink::FirmwareClass_t firmwareClass;
QGCMAVLink::VehicleClass_t vehicleClass; QGCMAVLink::VehicleClass_t vehicleClass;
_firmwareAndVehicleClassInfo(vehicle, firmwareClass, vehicleClass); _firmwareAndVehicleClassInfo(vehicle, QGCMAVLink::VehicleClassGeneric, firmwareClass, vehicleClass);
_buildAllCommands(vehicle); _buildAllCommands(vehicle, QGCMAVLink::VehicleClassGeneric);
return _supportedCategories[firmwareClass][vehicleClass]; return _supportedCategories[firmwareClass][vehicleClass];
} }
@ -166,13 +166,13 @@ const QList<MAV_CMD>& MissionCommandTree::allCommandIds(void) const
return _staticCommandTree[QGCMAVLink::FirmwareClassGeneric][QGCMAVLink::VehicleClassGeneric]->commandIds(); return _staticCommandTree[QGCMAVLink::FirmwareClassGeneric][QGCMAVLink::VehicleClassGeneric]->commandIds();
} }
const MissionCommandUIInfo* MissionCommandTree::getUIInfo(Vehicle* vehicle, MAV_CMD command) const MissionCommandUIInfo* MissionCommandTree::getUIInfo(Vehicle* vehicle, QGCMAVLink::VehicleClass_t vtolMode, MAV_CMD command)
{ {
QGCMAVLink::FirmwareClass_t firmwareClass; QGCMAVLink::FirmwareClass_t firmwareClass;
QGCMAVLink::VehicleClass_t vehicleClass; QGCMAVLink::VehicleClass_t vehicleClass;
_firmwareAndVehicleClassInfo(vehicle, firmwareClass, vehicleClass); _firmwareAndVehicleClassInfo(vehicle, vtolMode, firmwareClass, vehicleClass);
_buildAllCommands(vehicle); _buildAllCommands(vehicle, vtolMode);
const QMap<MAV_CMD, MissionCommandUIInfo*>& infoMap = _allCommands[firmwareClass][vehicleClass]; const QMap<MAV_CMD, MissionCommandUIInfo*>& infoMap = _allCommands[firmwareClass][vehicleClass];
if (infoMap.contains(command)) { if (infoMap.contains(command)) {
@ -187,8 +187,8 @@ QVariantList MissionCommandTree::getCommandsForCategory(Vehicle* vehicle, const
QGCMAVLink::FirmwareClass_t firmwareClass; QGCMAVLink::FirmwareClass_t firmwareClass;
QGCMAVLink::VehicleClass_t vehicleClass; QGCMAVLink::VehicleClass_t vehicleClass;
_firmwareAndVehicleClassInfo(vehicle, firmwareClass, vehicleClass); _firmwareAndVehicleClassInfo(vehicle, QGCMAVLink::VehicleClassGeneric, firmwareClass, vehicleClass);
_buildAllCommands(vehicle); _buildAllCommands(vehicle, QGCMAVLink::VehicleClassGeneric);
// vehicle can be null in which case _firmwareAndVehicleClassInfo will tell of the firmware/vehicle type for the offline editing vehicle. // vehicle can be null in which case _firmwareAndVehicleClassInfo will tell of the firmware/vehicle type for the offline editing vehicle.
// We then use that to get a firmware plugin so we can get the list of supported commands. // We then use that to get a firmware plugin so we can get the list of supported commands.
@ -210,8 +210,11 @@ QVariantList MissionCommandTree::getCommandsForCategory(Vehicle* vehicle, const
return list; return list;
} }
void MissionCommandTree::_firmwareAndVehicleClassInfo(Vehicle* vehicle, QGCMAVLink::FirmwareClass_t& firmwareClass, QGCMAVLink::VehicleClass_t& vehicleClass) const void MissionCommandTree::_firmwareAndVehicleClassInfo(Vehicle* vehicle, QGCMAVLink::VehicleClass_t vtolMode, QGCMAVLink::FirmwareClass_t& firmwareClass, QGCMAVLink::VehicleClass_t& vehicleClass) const
{ {
firmwareClass = QGCMAVLink::firmwareClass(vehicle->firmwareType()); firmwareClass = QGCMAVLink::firmwareClass(vehicle->firmwareType());
vehicleClass = QGCMAVLink::vehicleClass(vehicle->vehicleType()); vehicleClass = QGCMAVLink::vehicleClass(vehicle->vehicleType());
if (vehicleClass == QGCMAVLink::VehicleClassVTOL && vtolMode != QGCMAVLink::VehicleClassGeneric) {
vehicleClass = vtolMode;
}
} }

6
src/MissionManager/MissionCommandTree.h

@ -59,7 +59,7 @@ public:
Q_INVOKABLE QStringList categoriesForVehicle(Vehicle* vehicle) { return _availableCategoriesForVehicle(vehicle); } Q_INVOKABLE QStringList categoriesForVehicle(Vehicle* vehicle) { return _availableCategoriesForVehicle(vehicle); }
const MissionCommandUIInfo* getUIInfo(Vehicle* vehicle, MAV_CMD command); const MissionCommandUIInfo* getUIInfo(Vehicle* vehicle, QGCMAVLink::VehicleClass_t vtolMode, MAV_CMD command);
/// @param showFlyThroughCommands - true: all commands shows, false: filter out commands which the vehicle flies through (specifiedCoordinate=true, standaloneCoordinate=false) /// @param showFlyThroughCommands - true: all commands shows, false: filter out commands which the vehicle flies through (specifiedCoordinate=true, standaloneCoordinate=false)
Q_INVOKABLE QVariantList getCommandsForCategory(Vehicle* vehicle, const QString& category, bool showFlyThroughCommands); Q_INVOKABLE QVariantList getCommandsForCategory(Vehicle* vehicle, const QString& category, bool showFlyThroughCommands);
@ -69,9 +69,9 @@ public:
private: private:
void _collapseHierarchy (const MissionCommandList* cmdList, QMap<MAV_CMD, MissionCommandUIInfo*>& collapsedTree); void _collapseHierarchy (const MissionCommandList* cmdList, QMap<MAV_CMD, MissionCommandUIInfo*>& collapsedTree);
void _buildAllCommands (Vehicle* vehicle); void _buildAllCommands (Vehicle* vehicle, QGCMAVLink::VehicleClass_t vtolMode);
QStringList _availableCategoriesForVehicle (Vehicle* vehicle); QStringList _availableCategoriesForVehicle (Vehicle* vehicle);
void _firmwareAndVehicleClassInfo (Vehicle* vehicle, QGCMAVLink::FirmwareClass_t& firmwareClass, QGCMAVLink::VehicleClass_t& vehicleClass) const; void _firmwareAndVehicleClassInfo (Vehicle* vehicle, QGCMAVLink::VehicleClass_t vtolMode, QGCMAVLink::FirmwareClass_t& firmwareClass, QGCMAVLink::VehicleClass_t& vehicleClass) const;
private: private:
QString _allCommandsCategory; ///< Category which contains all available commands QString _allCommandsCategory; ///< Category which contains all available commands

6
src/MissionManager/MissionCommandTreeTest.cc

@ -188,12 +188,12 @@ void MissionCommandTreeTest::testOverride(void)
{ {
// Generic/Generic should not have any overrides // Generic/Generic should not have any overrides
Vehicle* vehicle = new Vehicle(MAV_AUTOPILOT_GENERIC, MAV_TYPE_GENERIC, qgcApp()->toolbox()->firmwarePluginManager()); Vehicle* vehicle = new Vehicle(MAV_AUTOPILOT_GENERIC, MAV_TYPE_GENERIC, qgcApp()->toolbox()->firmwarePluginManager());
_checkBaseValues(_commandTree->getUIInfo(vehicle, (MAV_CMD)4), 4); _checkBaseValues(_commandTree->getUIInfo(vehicle, QGCMAVLink::VehicleClassGeneric, (MAV_CMD)4), 4);
delete vehicle; delete vehicle;
// Generic/FixedWing should have overrides // Generic/FixedWing should have overrides
vehicle = new Vehicle(MAV_AUTOPILOT_GENERIC, MAV_TYPE_FIXED_WING, qgcApp()->toolbox()->firmwarePluginManager()); vehicle = new Vehicle(MAV_AUTOPILOT_GENERIC, MAV_TYPE_FIXED_WING, qgcApp()->toolbox()->firmwarePluginManager());
_checkOverrideValues(_commandTree->getUIInfo(vehicle, (MAV_CMD)4), 4); _checkOverrideValues(_commandTree->getUIInfo(vehicle, QGCMAVLink::VehicleClassGeneric, (MAV_CMD)4), 4);
delete vehicle; delete vehicle;
} }
@ -214,7 +214,7 @@ void MissionCommandTreeTest::testAllTrees(void)
} }
qDebug() << firmwareType << vehicleType; qDebug() << firmwareType << vehicleType;
Vehicle* vehicle = new Vehicle(firmwareType, vehicleType, qgcApp()->toolbox()->firmwarePluginManager()); Vehicle* vehicle = new Vehicle(firmwareType, vehicleType, qgcApp()->toolbox()->firmwarePluginManager());
QVERIFY(qgcApp()->toolbox()->missionCommandTree()->getUIInfo(vehicle, MAV_CMD_NAV_WAYPOINT) != nullptr); QVERIFY(qgcApp()->toolbox()->missionCommandTree()->getUIInfo(vehicle, QGCMAVLink::VehicleClassMultiRotor, MAV_CMD_NAV_WAYPOINT) != nullptr);
delete vehicle; delete vehicle;
} }
} }

8
src/MissionManager/MissionController.cc

@ -318,7 +318,7 @@ VisualMissionItem* MissionController::_insertSimpleMissionItemWorker(QGeoCoordin
_initVisualItem(newItem); _initVisualItem(newItem);
if (newItem->specifiesAltitude()) { if (newItem->specifiesAltitude()) {
const MissionCommandUIInfo* uiInfo = qgcApp()->toolbox()->missionCommandTree()->getUIInfo(_controllerVehicle, command); const MissionCommandUIInfo* uiInfo = qgcApp()->toolbox()->missionCommandTree()->getUIInfo(_controllerVehicle, QGCMAVLink::VehicleClassGeneric, command);
if (!uiInfo->isLandCommand()) { if (!uiInfo->isLandCommand()) {
double prevAltitude; double prevAltitude;
int prevAltitudeMode; int prevAltitudeMode;
@ -1672,9 +1672,9 @@ void MissionController::_recalcMissionFlightStatus()
case MAV_CMD_DO_VTOL_TRANSITION: case MAV_CMD_DO_VTOL_TRANSITION:
{ {
int transitionState = simpleItem->missionItem().param1(); int transitionState = simpleItem->missionItem().param1();
if (transitionState == MAV_VTOL_STATE_TRANSITION_TO_MC) { if (transitionState == MAV_VTOL_STATE_MC) {
_missionFlightStatus.vtolMode = QGCMAVLink::VehicleClassMultiRotor; _missionFlightStatus.vtolMode = QGCMAVLink::VehicleClassMultiRotor;
} else if (transitionState == MAV_VTOL_STATE_TRANSITION_TO_FW) { } else if (transitionState == MAV_VTOL_STATE_FW) {
_missionFlightStatus.vtolMode = QGCMAVLink::VehicleClassFixedWing; _missionFlightStatus.vtolMode = QGCMAVLink::VehicleClassFixedWing;
} }
} }
@ -1901,7 +1901,7 @@ void MissionController::_initVisualItem(VisualMissionItem* visualItem)
connect(visualItem, &VisualMissionItem::specifiedVehicleYawChanged, this, &MissionController::_recalcMissionFlightStatusSignal, Qt::QueuedConnection); connect(visualItem, &VisualMissionItem::specifiedVehicleYawChanged, this, &MissionController::_recalcMissionFlightStatusSignal, Qt::QueuedConnection);
connect(visualItem, &VisualMissionItem::terrainAltitudeChanged, this, &MissionController::_recalcMissionFlightStatusSignal, Qt::QueuedConnection); connect(visualItem, &VisualMissionItem::terrainAltitudeChanged, this, &MissionController::_recalcMissionFlightStatusSignal, Qt::QueuedConnection);
connect(visualItem, &VisualMissionItem::additionalTimeDelayChanged, this, &MissionController::_recalcMissionFlightStatusSignal, Qt::QueuedConnection); connect(visualItem, &VisualMissionItem::additionalTimeDelayChanged, this, &MissionController::_recalcMissionFlightStatusSignal, Qt::QueuedConnection);
connect(visualItem, &VisualMissionItem::currentVTOLModeChanged, this, &MissionController::_recalcMissionFlightStatusSignal, Qt::QueuedConnection);
connect(visualItem, &VisualMissionItem::lastSequenceNumberChanged, this, &MissionController::_recalcSequence); connect(visualItem, &VisualMissionItem::lastSequenceNumberChanged, this, &MissionController::_recalcSequence);
if (visualItem->isSimpleItem()) { if (visualItem->isSimpleItem()) {

4
src/MissionManager/MissionManager.cc

@ -97,11 +97,11 @@ void MissionManager::generateResumeMission(int resumeIndex)
resumeIndex = qMax(0, qMin(resumeIndex, _missionItems.count() - 1)); resumeIndex = qMax(0, qMin(resumeIndex, _missionItems.count() - 1));
// Adjust resume index to be a location based command // Adjust resume index to be a location based command
const MissionCommandUIInfo* uiInfo = qgcApp()->toolbox()->missionCommandTree()->getUIInfo(_vehicle, _missionItems[resumeIndex]->command()); const MissionCommandUIInfo* uiInfo = qgcApp()->toolbox()->missionCommandTree()->getUIInfo(_vehicle, QGCMAVLink::VehicleClassGeneric, _missionItems[resumeIndex]->command());
if (!uiInfo || uiInfo->isStandaloneCoordinate() || !uiInfo->specifiesCoordinate()) { if (!uiInfo || uiInfo->isStandaloneCoordinate() || !uiInfo->specifiesCoordinate()) {
// We have to back up to the last command which the vehicle flies through // We have to back up to the last command which the vehicle flies through
while (--resumeIndex > 0) { while (--resumeIndex > 0) {
uiInfo = qgcApp()->toolbox()->missionCommandTree()->getUIInfo(_vehicle, _missionItems[resumeIndex]->command()); uiInfo = qgcApp()->toolbox()->missionCommandTree()->getUIInfo(_vehicle, QGCMAVLink::VehicleClassGeneric, _missionItems[resumeIndex]->command());
if (uiInfo && (uiInfo->specifiesCoordinate() && !uiInfo->isStandaloneCoordinate())) { if (uiInfo && (uiInfo->specifiesCoordinate() && !uiInfo->isStandaloneCoordinate())) {
// Found it // Found it
break; break;

42
src/MissionManager/SimpleMissionItem.cc

@ -191,6 +191,11 @@ void SimpleMissionItem::_connectSignals(void)
// Whenever these properties change the ui model changes as well // Whenever these properties change the ui model changes as well
connect(this, &SimpleMissionItem::commandChanged, this, &SimpleMissionItem::_rebuildFacts); connect(this, &SimpleMissionItem::commandChanged, this, &SimpleMissionItem::_rebuildFacts);
connect(this, &SimpleMissionItem::rawEditChanged, this, &SimpleMissionItem::_rebuildFacts); connect(this, &SimpleMissionItem::rawEditChanged, this, &SimpleMissionItem::_rebuildFacts);
connect(this, &SimpleMissionItem::previousVTOLModeChanged,this, &SimpleMissionItem::_rebuildFacts);
// The following changes must signal currentVTOLModeChanged to cause a MissionController recalc
connect(this, &SimpleMissionItem::commandChanged, this, &SimpleMissionItem::_signalIfVTOLTransitionCommand);
connect(&_missionItem._param1Fact, &Fact::valueChanged, this, &SimpleMissionItem::_signalIfVTOLTransitionCommand);
// These fact signals must alway signal out through SimpleMissionItem signals // These fact signals must alway signal out through SimpleMissionItem signals
connect(&_missionItem._commandFact, &Fact::valueChanged, this, &SimpleMissionItem::_sendCommandChanged); connect(&_missionItem._commandFact, &Fact::valueChanged, this, &SimpleMissionItem::_sendCommandChanged);
@ -333,7 +338,7 @@ bool SimpleMissionItem::load(const QJsonObject& json, int sequenceNumber, QStrin
bool SimpleMissionItem::isStandaloneCoordinate(void) const bool SimpleMissionItem::isStandaloneCoordinate(void) const
{ {
const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, (MAV_CMD)command()); const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, _previousVTOLMode, (MAV_CMD)command());
if (uiInfo) { if (uiInfo) {
return uiInfo->isStandaloneCoordinate(); return uiInfo->isStandaloneCoordinate();
} else { } else {
@ -343,7 +348,7 @@ bool SimpleMissionItem::isStandaloneCoordinate(void) const
bool SimpleMissionItem::specifiesCoordinate(void) const bool SimpleMissionItem::specifiesCoordinate(void) const
{ {
const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, (MAV_CMD)command()); const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, _previousVTOLMode, (MAV_CMD)command());
if (uiInfo) { if (uiInfo) {
return uiInfo->specifiesCoordinate(); return uiInfo->specifiesCoordinate();
} else { } else {
@ -353,7 +358,7 @@ bool SimpleMissionItem::specifiesCoordinate(void) const
bool SimpleMissionItem::specifiesAltitudeOnly(void) const bool SimpleMissionItem::specifiesAltitudeOnly(void) const
{ {
const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, (MAV_CMD)command()); const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, _previousVTOLMode, (MAV_CMD)command());
if (uiInfo) { if (uiInfo) {
return uiInfo->specifiesAltitudeOnly(); return uiInfo->specifiesAltitudeOnly();
} else { } else {
@ -363,7 +368,7 @@ bool SimpleMissionItem::specifiesAltitudeOnly(void) const
QString SimpleMissionItem::commandDescription(void) const QString SimpleMissionItem::commandDescription(void) const
{ {
const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, (MAV_CMD)command()); const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, _previousVTOLMode, (MAV_CMD)command());
if (uiInfo) { if (uiInfo) {
return uiInfo->description(); return uiInfo->description();
} else { } else {
@ -374,7 +379,7 @@ QString SimpleMissionItem::commandDescription(void) const
QString SimpleMissionItem::commandName(void) const QString SimpleMissionItem::commandName(void) const
{ {
const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, (MAV_CMD)command()); const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, _previousVTOLMode, (MAV_CMD)command());
if (uiInfo) { if (uiInfo) {
return uiInfo->friendlyName(); return uiInfo->friendlyName();
} else { } else {
@ -444,7 +449,7 @@ void SimpleMissionItem::_rebuildTextFieldFacts(void)
Fact* rgParamFacts[7] = { &_missionItem._param1Fact, &_missionItem._param2Fact, &_missionItem._param3Fact, &_missionItem._param4Fact, &_missionItem._param5Fact, &_missionItem._param6Fact, &_missionItem._param7Fact }; Fact* rgParamFacts[7] = { &_missionItem._param1Fact, &_missionItem._param2Fact, &_missionItem._param3Fact, &_missionItem._param4Fact, &_missionItem._param5Fact, &_missionItem._param6Fact, &_missionItem._param7Fact };
FactMetaData* rgParamMetaData[7] = { &_param1MetaData, &_param2MetaData, &_param3MetaData, &_param4MetaData, &_param5MetaData, &_param6MetaData, &_param7MetaData }; FactMetaData* rgParamMetaData[7] = { &_param1MetaData, &_param2MetaData, &_param3MetaData, &_param4MetaData, &_param5MetaData, &_param6MetaData, &_param7MetaData };
const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, command); const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, _previousVTOLMode, command);
for (int i=1; i<=7; i++) { for (int i=1; i<=7; i++) {
bool showUI; bool showUI;
@ -483,7 +488,7 @@ void SimpleMissionItem::_rebuildNaNFacts(void)
Fact* rgParamFacts[7] = { &_missionItem._param1Fact, &_missionItem._param2Fact, &_missionItem._param3Fact, &_missionItem._param4Fact, &_missionItem._param5Fact, &_missionItem._param6Fact, &_missionItem._param7Fact }; Fact* rgParamFacts[7] = { &_missionItem._param1Fact, &_missionItem._param2Fact, &_missionItem._param3Fact, &_missionItem._param4Fact, &_missionItem._param5Fact, &_missionItem._param6Fact, &_missionItem._param7Fact };
FactMetaData* rgParamMetaData[7] = { &_param1MetaData, &_param2MetaData, &_param3MetaData, &_param4MetaData, &_param5MetaData, &_param6MetaData, &_param7MetaData }; FactMetaData* rgParamMetaData[7] = { &_param1MetaData, &_param2MetaData, &_param3MetaData, &_param4MetaData, &_param5MetaData, &_param6MetaData, &_param7MetaData };
const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, command); const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, _previousVTOLMode, command);
for (int i=1; i<=7; i++) { for (int i=1; i<=7; i++) {
bool showUI; bool showUI;
@ -541,7 +546,7 @@ void SimpleMissionItem::_rebuildComboBoxFacts(void)
for (int i=1; i<=7; i++) { for (int i=1; i<=7; i++) {
bool showUI; bool showUI;
const MissionCmdParamInfo* paramInfo = _commandTree->getUIInfo(_controllerVehicle, command)->getParamInfo(i, showUI); const MissionCmdParamInfo* paramInfo = _commandTree->getUIInfo(_controllerVehicle, _previousVTOLMode, command)->getParamInfo(i, showUI);
if (showUI && paramInfo && paramInfo->enumStrings().count() != 0) { if (showUI && paramInfo && paramInfo->enumStrings().count() != 0) {
Fact* paramFact = rgParamFacts[i-1]; Fact* paramFact = rgParamFacts[i-1];
@ -567,7 +572,7 @@ void SimpleMissionItem::_rebuildFacts(void)
bool SimpleMissionItem::friendlyEditAllowed(void) const bool SimpleMissionItem::friendlyEditAllowed(void) const
{ {
const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, static_cast<MAV_CMD>(command())); const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, _previousVTOLMode, static_cast<MAV_CMD>(command()));
if (uiInfo && uiInfo->friendlyEdit()) { if (uiInfo && uiInfo->friendlyEdit()) {
if (!_missionItem.autoContinue()) { if (!_missionItem.autoContinue()) {
return false; return false;
@ -740,7 +745,7 @@ void SimpleMissionItem::_setDefaultsForCommand(void)
} }
MAV_CMD command = static_cast<MAV_CMD>(this->command()); MAV_CMD command = static_cast<MAV_CMD>(this->command());
const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, command); const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, _previousVTOLMode, command);
if (uiInfo) { if (uiInfo) {
for (int i=1; i<=7; i++) { for (int i=1; i<=7; i++) {
bool showUI; bool showUI;
@ -777,7 +782,7 @@ void SimpleMissionItem::_sendFriendlyEditAllowedChanged(void)
QString SimpleMissionItem::category(void) const QString SimpleMissionItem::category(void) const
{ {
return _commandTree->getUIInfo(_controllerVehicle, static_cast<MAV_CMD>(command()))->category(); return _commandTree->getUIInfo(_controllerVehicle, _previousVTOLMode, static_cast<MAV_CMD>(command()))->category();
} }
void SimpleMissionItem::setCommand(int command) void SimpleMissionItem::setCommand(int command)
@ -920,7 +925,7 @@ void SimpleMissionItem::appendMissionItems(QList<MissionItem*>& items, QObject*
void SimpleMissionItem::applyNewAltitude(double newAltitude) void SimpleMissionItem::applyNewAltitude(double newAltitude)
{ {
MAV_CMD command = static_cast<MAV_CMD>(this->command()); MAV_CMD command = static_cast<MAV_CMD>(this->command());
const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, command); const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, _previousVTOLMode, command);
if (uiInfo->specifiesCoordinate() || uiInfo->specifiesAltitudeOnly()) { if (uiInfo->specifiesCoordinate() || uiInfo->specifiesAltitudeOnly()) {
switch (static_cast<MAV_CMD>(this->command())) { switch (static_cast<MAV_CMD>(this->command())) {
@ -937,8 +942,9 @@ void SimpleMissionItem::applyNewAltitude(double newAltitude)
void SimpleMissionItem::setMissionFlightStatus(MissionController::MissionFlightStatus_t& missionFlightStatus) void SimpleMissionItem::setMissionFlightStatus(MissionController::MissionFlightStatus_t& missionFlightStatus)
{ {
// If speed and/or gimbal are not specifically set on this item. Then use the flight status values as initial defaults should a user turn them on.
VisualMissionItem::setMissionFlightStatus(missionFlightStatus); VisualMissionItem::setMissionFlightStatus(missionFlightStatus);
// If speed and/or gimbal are not specifically set on this item. Then use the flight status values as initial defaults should a user turn them on.
if (_speedSection->available() && !_speedSection->specifyFlightSpeed() && !qFuzzyCompare(_speedSection->flightSpeed()->rawValue().toDouble(), missionFlightStatus.vehicleSpeed)) { if (_speedSection->available() && !_speedSection->specifyFlightSpeed() && !qFuzzyCompare(_speedSection->flightSpeed()->rawValue().toDouble(), missionFlightStatus.vehicleSpeed)) {
_speedSection->flightSpeed()->setRawValue(missionFlightStatus.vehicleSpeed); _speedSection->flightSpeed()->setRawValue(missionFlightStatus.vehicleSpeed);
} }
@ -988,7 +994,7 @@ void SimpleMissionItem::_possibleAdditionalTimeDelayChanged(void)
bool SimpleMissionItem::isLandCommand(void) const bool SimpleMissionItem::isLandCommand(void) const
{ {
MAV_CMD command = static_cast<MAV_CMD>(this->command()); MAV_CMD command = static_cast<MAV_CMD>(this->command());
const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, command); const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, _previousVTOLMode, command);
return uiInfo->isLandCommand(); return uiInfo->isLandCommand();
} }
@ -1019,3 +1025,11 @@ double SimpleMissionItem::amslEntryAlt(void) const
qWarning() << "Internal Error SimpleMissionItem::amslEntryAlt: Invalid altitudeMode:" << _altitudeMode; qWarning() << "Internal Error SimpleMissionItem::amslEntryAlt: Invalid altitudeMode:" << _altitudeMode;
return qQNaN(); return qQNaN();
} }
void SimpleMissionItem::_signalIfVTOLTransitionCommand(void)
{
if (mavCommand() == MAV_CMD_DO_VTOL_TRANSITION) {
// This will cause a MissionController recalc
emit currentVTOLModeChanged();
}
}

1
src/MissionManager/SimpleMissionItem.h

@ -153,6 +153,7 @@ private slots:
void _possibleAdditionalTimeDelayChanged (void); void _possibleAdditionalTimeDelayChanged (void);
void _setDefaultsForCommand (void); void _setDefaultsForCommand (void);
void _possibleVehicleYawChanged (void); void _possibleVehicleYawChanged (void);
void _signalIfVTOLTransitionCommand (void);
private: private:
void _connectSignals (void); void _connectSignals (void);

2
src/MissionManager/TakeoffMissionItem.cc

@ -116,7 +116,7 @@ void TakeoffMissionItem::setCoordinate(const QGeoCoordinate& coordinate)
bool TakeoffMissionItem::isTakeoffCommand(MAV_CMD command) bool TakeoffMissionItem::isTakeoffCommand(MAV_CMD command)
{ {
const MissionCommandUIInfo* uiInfo = qgcApp()->toolbox()->missionCommandTree()->getUIInfo(qgcApp()->toolbox()->multiVehicleManager()->offlineEditingVehicle(), command); const MissionCommandUIInfo* uiInfo = qgcApp()->toolbox()->missionCommandTree()->getUIInfo(qgcApp()->toolbox()->multiVehicleManager()->offlineEditingVehicle(), QGCMAVLink::VehicleClassGeneric, command);
return uiInfo ? uiInfo->isTakeoffCommand() : false; return uiInfo ? uiInfo->isTakeoffCommand() : false;
} }

11
src/MissionManager/VisualMissionItem.cc

@ -7,7 +7,6 @@
* *
****************************************************************************/ ****************************************************************************/
#include <QStringList> #include <QStringList>
#include <QDebug> #include <QDebug>
@ -18,6 +17,7 @@
#include "TerrainQuery.h" #include "TerrainQuery.h"
#include "TakeoffMissionItem.h" #include "TakeoffMissionItem.h"
#include "PlanMasterController.h" #include "PlanMasterController.h"
#include "QGC.h"
const char* VisualMissionItem::jsonTypeKey = "type"; const char* VisualMissionItem::jsonTypeKey = "type";
const char* VisualMissionItem::jsonTypeSimpleItemValue = "SimpleItem"; const char* VisualMissionItem::jsonTypeSimpleItemValue = "SimpleItem";
@ -152,13 +152,14 @@ void VisualMissionItem::setAzimuth(double azimuth)
void VisualMissionItem::setMissionFlightStatus(MissionController::MissionFlightStatus_t& missionFlightStatus) void VisualMissionItem::setMissionFlightStatus(MissionController::MissionFlightStatus_t& missionFlightStatus)
{ {
if (qIsNaN(missionFlightStatus.gimbalYaw) && qIsNaN(_missionGimbalYaw)) { if (!QGC::fuzzyCompare(missionFlightStatus.gimbalYaw, _missionGimbalYaw)) {
return;
}
if (!qFuzzyCompare(missionFlightStatus.gimbalYaw, _missionGimbalYaw)) {
_missionGimbalYaw = missionFlightStatus.gimbalYaw; _missionGimbalYaw = missionFlightStatus.gimbalYaw;
emit missionGimbalYawChanged(_missionGimbalYaw); emit missionGimbalYawChanged(_missionGimbalYaw);
} }
if (missionFlightStatus.vtolMode != _previousVTOLMode) {
_previousVTOLMode = missionFlightStatus.vtolMode;
emit previousVTOLModeChanged();
}
} }
void VisualMissionItem::setMissionVehicleYaw(double vehicleYaw) void VisualMissionItem::setMissionVehicleYaw(double vehicleYaw)

4
src/MissionManager/VisualMissionItem.h

@ -81,6 +81,7 @@ public:
Q_PROPERTY(double missionVehicleYaw READ missionVehicleYaw NOTIFY missionVehicleYawChanged) ///< Expected vehicle yaw at this point in mission Q_PROPERTY(double missionVehicleYaw READ missionVehicleYaw NOTIFY missionVehicleYawChanged) ///< Expected vehicle yaw at this point in mission
Q_PROPERTY(bool flyView READ flyView CONSTANT) Q_PROPERTY(bool flyView READ flyView CONSTANT)
Q_PROPERTY(bool wizardMode READ wizardMode WRITE setWizardMode NOTIFY wizardModeChanged) Q_PROPERTY(bool wizardMode READ wizardMode WRITE setWizardMode NOTIFY wizardModeChanged)
Q_PROPERTY(int previousVTOLMode MEMBER _previousVTOLMode NOTIFY previousVTOLModeChanged) ///< Current VTOL mode (VehicleClass_t) prior to executing this item
Q_PROPERTY(PlanMasterController* masterController READ masterController CONSTANT) Q_PROPERTY(PlanMasterController* masterController READ masterController CONSTANT)
Q_PROPERTY(ReadyForSaveState readyForSaveState READ readyForSaveState NOTIFY readyForSaveStateChanged) Q_PROPERTY(ReadyForSaveState readyForSaveState READ readyForSaveState NOTIFY readyForSaveStateChanged)
@ -238,6 +239,8 @@ signals:
void parentItemChanged (VisualMissionItem* parentItem); void parentItemChanged (VisualMissionItem* parentItem);
void amslEntryAltChanged (double alt); void amslEntryAltChanged (double alt);
void amslExitAltChanged (double alt); void amslExitAltChanged (double alt);
void previousVTOLModeChanged (void);
void currentVTOLModeChanged (void); ///< Signals that this item has changed the VTOL mode (MAV_CMD_DO_VTOL_TRANSITION)
void exitCoordinateSameAsEntryChanged (bool exitCoordinateSameAsEntry); void exitCoordinateSameAsEntryChanged (bool exitCoordinateSameAsEntry);
@ -263,6 +266,7 @@ protected:
QString _editorQml; ///< Qml resource for editing item QString _editorQml; ///< Qml resource for editing item
double _missionGimbalYaw = qQNaN(); double _missionGimbalYaw = qQNaN();
double _missionVehicleYaw = qQNaN(); double _missionVehicleYaw = qQNaN();
QGCMAVLink::VehicleClass_t _previousVTOLMode = QGCMAVLink::VehicleClassGeneric; ///< Generic == unknown
PlanMasterController* _masterController = nullptr; PlanMasterController* _masterController = nullptr;
MissionController* _missionController = nullptr; MissionController* _missionController = nullptr;

Loading…
Cancel
Save