Unverified Commit 4c872ca4 authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #8954 from DonLakeFlyer/VTOLCommandEditors

Plan: Show correct item editor based on current VTOL state in mission
parents 54859956 630f9e56
......@@ -134,19 +134,6 @@ bool ArduCopterFirmwarePlugin::multiRotorXConfig(Vehicle* vehicle)
return vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, "FRAME")->rawValue().toInt() != 0;
}
bool ArduCopterFirmwarePlugin::vehicleYawsToNextWaypointInMission(const Vehicle* vehicle) const
{
if (vehicle->isOfflineEditingVehicle()) {
return FirmwarePlugin::vehicleYawsToNextWaypointInMission(vehicle);
} else {
if (vehicle->multiRotor() && vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, QStringLiteral("WP_YAW_BEHAVIOR"))) {
Fact* yawMode = vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, QStringLiteral("WP_YAW_BEHAVIOR"));
return yawMode && yawMode->rawValue().toInt() != 0;
}
}
return true;
}
#if 0
// Follow me not ready for Stable
void ArduCopterFirmwarePlugin::sendGCSMotionReport(Vehicle* vehicle, FollowMe::GCSMotionReport& motionReport, uint8_t estimatationCapabilities)
......
......@@ -71,7 +71,6 @@ public:
QString landFlightMode (void) const override { return QStringLiteral("Land"); }
QString takeControlFlightMode (void) const override { return QStringLiteral("Loiter"); }
QString followFlightMode (void) const override { return QStringLiteral("Follow"); }
bool vehicleYawsToNextWaypointInMission (const Vehicle* vehicle) const override;
QString autoDisarmParameter (Vehicle* vehicle) override { Q_UNUSED(vehicle); return QStringLiteral("DISARM_DELAY"); }
bool supportsSmartRTL (void) const override { return true; }
#if 0
......
......@@ -698,11 +698,6 @@ QMap<QString, FactGroup*>* FirmwarePlugin::factGroups(void) {
return nullptr;
}
bool FirmwarePlugin::vehicleYawsToNextWaypointInMission(const Vehicle* vehicle) const
{
return vehicle->multiRotor() ? false : true;
}
bool FirmwarePlugin::_armVehicleAndValidate(Vehicle* vehicle)
{
if (vehicle->armed()) {
......
......@@ -297,9 +297,6 @@ public:
/// Returns a pointer to a dictionary of firmware-specific FactGroups
virtual QMap<QString, FactGroup*>* factGroups(void);
/// @true: When flying a mission the vehicle is always facing towards the next waypoint
virtual bool vehicleYawsToNextWaypointInMission(const Vehicle* vehicle) const;
/// Returns the data needed to do battery consumption calculations
/// @param[out] mAhBattery Battery milliamp-hours rating (0 for no battery data available)
/// @param[out] hoverAmps Current draw in amps during hover
......
......@@ -1057,7 +1057,7 @@ void CameraSectionTest::_testScanForMultipleItems(void)
item2->missionItem() = cameraItem->missionItem();
visualItems.append(item1);
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;
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), true);
......@@ -1078,7 +1078,7 @@ void CameraSectionTest::_testScanForMultipleItems(void)
item2->missionItem() = cameraItem->missionItem();
visualItems.append(item1);
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;
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), true);
......
......@@ -51,7 +51,7 @@ void KMLPlanDomDocument::_addFlightPath(Vehicle* vehicle, QList<MissionItem*> rg
QList<QGeoCoordinate> rgFlightCoords;
QGeoCoordinate homeCoord = rgMissionItems[0]->coordinate();
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) {
double altAdjustment = item->frame() == MAV_FRAME_GLOBAL ? 0 : homeCoord.altitude(); // Used to convert to amsl
if (uiInfo->isTakeoffCommand() && !vehicle->fixedWing()) {
......
......@@ -7,7 +7,7 @@
{
"id": 16,
"comment": "MAV_CMD_NAV_WAYPOINT",
"paramRemove": "4"
"paramRemove": "1,4"
},
{
"id": 17,
......
......@@ -9,6 +9,11 @@
"comment": "MAV_CMD_NAV_LOITER_UNLIM",
"paramRemove": "3"
},
{
"id": 18,
"comment": "MAV_CMD_NAV_LOITER_TURNS",
"paramRemove": "1,2,3,4"
},
{
"id": 19,
"comment": "MAV_CMD_NAV_LOITER_TIME",
......
......@@ -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::VehicleClass_t vehicleClass;
_firmwareAndVehicleClassInfo(vehicle, firmwareClass, vehicleClass);
_firmwareAndVehicleClassInfo(vehicle, vtolMode, firmwareClass, vehicleClass);
if (_allCommands.contains(firmwareClass) && _allCommands[firmwareClass].contains(vehicleClass)) {
// Already built
......@@ -131,8 +131,8 @@ QStringList MissionCommandTree::_availableCategoriesForVehicle(Vehicle* vehicle)
QGCMAVLink::FirmwareClass_t firmwareClass;
QGCMAVLink::VehicleClass_t vehicleClass;
_firmwareAndVehicleClassInfo(vehicle, firmwareClass, vehicleClass);
_buildAllCommands(vehicle);
_firmwareAndVehicleClassInfo(vehicle, QGCMAVLink::VehicleClassGeneric, firmwareClass, vehicleClass);
_buildAllCommands(vehicle, QGCMAVLink::VehicleClassGeneric);
return _supportedCategories[firmwareClass][vehicleClass];
}
......@@ -166,13 +166,13 @@ const QList<MAV_CMD>& MissionCommandTree::allCommandIds(void) const
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::VehicleClass_t vehicleClass;
_firmwareAndVehicleClassInfo(vehicle, firmwareClass, vehicleClass);
_buildAllCommands(vehicle);
_firmwareAndVehicleClassInfo(vehicle, vtolMode, firmwareClass, vehicleClass);
_buildAllCommands(vehicle, vtolMode);
const QMap<MAV_CMD, MissionCommandUIInfo*>& infoMap = _allCommands[firmwareClass][vehicleClass];
if (infoMap.contains(command)) {
......@@ -187,8 +187,8 @@ QVariantList MissionCommandTree::getCommandsForCategory(Vehicle* vehicle, const
QGCMAVLink::FirmwareClass_t firmwareClass;
QGCMAVLink::VehicleClass_t vehicleClass;
_firmwareAndVehicleClassInfo(vehicle, firmwareClass, vehicleClass);
_buildAllCommands(vehicle);
_firmwareAndVehicleClassInfo(vehicle, QGCMAVLink::VehicleClassGeneric, firmwareClass, vehicleClass);
_buildAllCommands(vehicle, QGCMAVLink::VehicleClassGeneric);
// 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.
......@@ -210,8 +210,11 @@ QVariantList MissionCommandTree::getCommandsForCategory(Vehicle* vehicle, const
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());
vehicleClass = QGCMAVLink::vehicleClass(vehicle->vehicleType());
if (vehicleClass == QGCMAVLink::VehicleClassVTOL && vtolMode != QGCMAVLink::VehicleClassGeneric) {
vehicleClass = vtolMode;
}
}
......@@ -59,7 +59,7 @@ public:
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)
Q_INVOKABLE QVariantList getCommandsForCategory(Vehicle* vehicle, const QString& category, bool showFlyThroughCommands);
......@@ -69,9 +69,9 @@ public:
private:
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);
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:
QString _allCommandsCategory; ///< Category which contains all available commands
......
......@@ -188,12 +188,12 @@ void MissionCommandTreeTest::testOverride(void)
{
// Generic/Generic should not have any overrides
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;
// Generic/FixedWing should have overrides
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;
}
......@@ -214,7 +214,7 @@ void MissionCommandTreeTest::testAllTrees(void)
}
qDebug() << firmwareType << vehicleType;
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;
}
}
......
......@@ -318,7 +318,7 @@ VisualMissionItem* MissionController::_insertSimpleMissionItemWorker(QGeoCoordin
_initVisualItem(newItem);
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()) {
double prevAltitude;
int prevAltitudeMode;
......@@ -1672,9 +1672,9 @@ void MissionController::_recalcMissionFlightStatus()
case MAV_CMD_DO_VTOL_TRANSITION:
{
int transitionState = simpleItem->missionItem().param1();
if (transitionState == MAV_VTOL_STATE_TRANSITION_TO_MC) {
if (transitionState == MAV_VTOL_STATE_MC) {
_missionFlightStatus.vtolMode = QGCMAVLink::VehicleClassMultiRotor;
} else if (transitionState == MAV_VTOL_STATE_TRANSITION_TO_FW) {
} else if (transitionState == MAV_VTOL_STATE_FW) {
_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::terrainAltitudeChanged, 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);
if (visualItem->isSimpleItem()) {
......
......@@ -97,11 +97,11 @@ void MissionManager::generateResumeMission(int resumeIndex)
resumeIndex = qMax(0, qMin(resumeIndex, _missionItems.count() - 1));
// 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()) {
// We have to back up to the last command which the vehicle flies through
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())) {
// Found it
break;
......
......@@ -191,6 +191,11 @@ void SimpleMissionItem::_connectSignals(void)
// Whenever these properties change the ui model changes as well
connect(this, &SimpleMissionItem::commandChanged, 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
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
{
const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, (MAV_CMD)command());
const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, _previousVTOLMode, (MAV_CMD)command());
if (uiInfo) {
return uiInfo->isStandaloneCoordinate();
} else {
......@@ -343,7 +348,7 @@ bool SimpleMissionItem::isStandaloneCoordinate(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) {
return uiInfo->specifiesCoordinate();
} else {
......@@ -353,7 +358,7 @@ bool SimpleMissionItem::specifiesCoordinate(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) {
return uiInfo->specifiesAltitudeOnly();
} else {
......@@ -363,7 +368,7 @@ bool SimpleMissionItem::specifiesAltitudeOnly(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) {
return uiInfo->description();
} else {
......@@ -374,7 +379,7 @@ QString SimpleMissionItem::commandDescription(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) {
return uiInfo->friendlyName();
} 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 };
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++) {
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 };
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++) {
bool showUI;
......@@ -496,10 +501,6 @@ void SimpleMissionItem::_rebuildNaNFacts(void)
if (!firmwareVehicle) {
firmwareVehicle = _controllerVehicle;
}
bool hideWaypointHeading = (command == MAV_CMD_NAV_WAYPOINT || command == MAV_CMD_NAV_TAKEOFF) && (i == 4) && firmwareVehicle->firmwarePlugin()->vehicleYawsToNextWaypointInMission(firmwareVehicle);
if (hideWaypointHeading) {
continue;
}
Fact* paramFact = rgParamFacts[i-1];
FactMetaData* paramMetaData = rgParamMetaData[i-1];
......@@ -541,7 +542,7 @@ void SimpleMissionItem::_rebuildComboBoxFacts(void)
for (int i=1; i<=7; i++) {
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) {
Fact* paramFact = rgParamFacts[i-1];
......@@ -567,7 +568,7 @@ void SimpleMissionItem::_rebuildFacts(void)
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 (!_missionItem.autoContinue()) {
return false;
......@@ -740,7 +741,7 @@ void SimpleMissionItem::_setDefaultsForCommand(void)
}
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) {
for (int i=1; i<=7; i++) {
bool showUI;
......@@ -777,7 +778,7 @@ void SimpleMissionItem::_sendFriendlyEditAllowedChanged(void)
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)
......@@ -920,7 +921,7 @@ void SimpleMissionItem::appendMissionItems(QList<MissionItem*>& items, QObject*
void SimpleMissionItem::applyNewAltitude(double newAltitude)
{
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()) {
switch (static_cast<MAV_CMD>(this->command())) {
......@@ -937,8 +938,9 @@ void SimpleMissionItem::applyNewAltitude(double newAltitude)
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);
// 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)) {
_speedSection->flightSpeed()->setRawValue(missionFlightStatus.vehicleSpeed);
}
......@@ -988,7 +990,7 @@ void SimpleMissionItem::_possibleAdditionalTimeDelayChanged(void)
bool SimpleMissionItem::isLandCommand(void) const
{
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();
}
......@@ -1019,3 +1021,11 @@ double SimpleMissionItem::amslEntryAlt(void) const
qWarning() << "Internal Error SimpleMissionItem::amslEntryAlt: Invalid altitudeMode:" << _altitudeMode;
return qQNaN();
}
void SimpleMissionItem::_signalIfVTOLTransitionCommand(void)
{
if (mavCommand() == MAV_CMD_DO_VTOL_TRANSITION) {
// This will cause a MissionController recalc
emit currentVTOLModeChanged();
}
}
......@@ -150,9 +150,10 @@ private slots:
void _updateLastSequenceNumber (void);
void _rebuildFacts (void);
void _rebuildTextFieldFacts (void);
void _possibleAdditionalTimeDelayChanged(void);
void _possibleAdditionalTimeDelayChanged (void);
void _setDefaultsForCommand (void);
void _possibleVehicleYawChanged (void);
void _signalIfVTOLTransitionCommand (void);
private:
void _connectSignals (void);
......
This diff is collapsed.
......@@ -13,6 +13,26 @@
#include "SimpleMissionItem.h"
/// Unit test for SimpleMissionItem
typedef struct {
MAV_CMD command;
MAV_FRAME frame;
} ItemInfo_t;
typedef struct {
const char* name;
QGCMAVLink::VehicleClass_t vehicleClass;
bool nanValue;
int paramIndex;
} FactValue_t;
typedef struct {
size_t cFactValues;
const FactValue_t* rgFactValues;
double altValue;
QGroundControlQmlGlobal::AltitudeMode altMode;
} ItemExpected_t;
class SimpleMissionItemTest : public VisualMissionItemTest
{
Q_OBJECT
......@@ -20,18 +40,18 @@ class SimpleMissionItemTest : public VisualMissionItemTest
public:
SimpleMissionItemTest(void);
void init(void) override;
void init (void) override;
void cleanup(void) override;
private slots:
void _testSignals(void);
void _testEditorFacts(void);
void _testDefaultValues(void);
void _testCameraSectionDirty(void);
void _testSpeedSectionDirty(void);
void _testCameraSection(void);
void _testSpeedSection(void);
void _testAltitudePropogation(void);
void _testSignals (void);
void _testEditorFacts (void);
void _testDefaultValues (void);
void _testCameraSectionDirty (void);
void _testSpeedSectionDirty (void);
void _testCameraSection (void);
void _testSpeedSection (void);
void _testAltitudePropogation (void);
private:
enum {
......@@ -58,35 +78,10 @@ private:
static const size_t cSimpleItemSignals = maxSignalIndex;
const char* rgSimpleItemSignals[cSimpleItemSignals];
typedef struct {
MAV_CMD command;
MAV_FRAME frame;
} ItemInfo_t;
typedef struct {
const char* name;
double value;
} FactValue_t;
typedef struct {
size_t cFactValues;
const FactValue_t* rgFactValues;
double altValue;
QGroundControlQmlGlobal::AltitudeMode altMode;
} ItemExpected_t;
void _testEditorFactsWorker (QGCMAVLink::VehicleClass_t vehicleClass, QGCMAVLink::VehicleClass_t vtolMode, const ItemExpected_t* rgExpected);
bool _classMatch (QGCMAVLink::VehicleClass_t vehicleClass, QGCMAVLink::VehicleClass_t testClass);
SimpleMissionItem* _simpleItem;
MultiSignalSpy* _spySimpleItem;
MultiSignalSpy* _spyVisualItem;
static const ItemInfo_t _rgItemInfo[];
static const ItemExpected_t _rgItemExpected[];
static const FactValue_t _rgFactValuesWaypoint[];
static const FactValue_t _rgFactValuesLoiterUnlim[];
static const FactValue_t _rgFactValuesLoiterTurns[];
static const FactValue_t _rgFactValuesLoiterTime[];
static const FactValue_t _rgFactValuesLand[];
static const FactValue_t _rgFactValuesTakeoff[];
static const FactValue_t _rgFactValuesConditionDelay[];
static const FactValue_t _rgFactValuesDoJump[];
};
......@@ -116,7 +116,7 @@ void TakeoffMissionItem::setCoordinate(const QGeoCoordinate& coordinate)
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;
}
......
......@@ -7,7 +7,6 @@
*
****************************************************************************/
#include <QStringList>
#include <QDebug>
......@@ -18,6 +17,7 @@
#include "TerrainQuery.h"
#include "TakeoffMissionItem.h"
#include "PlanMasterController.h"
#include "QGC.h"
const char* VisualMissionItem::jsonTypeKey = "type";
const char* VisualMissionItem::jsonTypeSimpleItemValue = "SimpleItem";
......@@ -152,13 +152,14 @@ void VisualMissionItem::setAzimuth(double azimuth)
void VisualMissionItem::setMissionFlightStatus(MissionController::MissionFlightStatus_t& missionFlightStatus)
{
if (qIsNaN(missionFlightStatus.gimbalYaw) && qIsNaN(_missionGimbalYaw)) {
return;
}
if (!qFuzzyCompare(missionFlightStatus.gimbalYaw, _missionGimbalYaw)) {
if (!QGC::fuzzyCompare(missionFlightStatus.gimbalYaw, _missionGimbalYaw)) {
_missionGimbalYaw = missionFlightStatus.gimbalYaw;
emit missionGimbalYawChanged(_missionGimbalYaw);
}
if (missionFlightStatus.vtolMode != _previousVTOLMode) {
_previousVTOLMode = missionFlightStatus.vtolMode;
emit previousVTOLModeChanged();
}
}
void VisualMissionItem::setMissionVehicleYaw(double vehicleYaw)
......
......@@ -81,6 +81,7 @@ public:
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 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(ReadyForSaveState readyForSaveState READ readyForSaveState NOTIFY readyForSaveStateChanged)
......@@ -238,6 +239,8 @@ signals:
void parentItemChanged (VisualMissionItem* parentItem);
void amslEntryAltChanged (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);
......@@ -263,6 +266,7 @@ protected:
QString _editorQml; ///< Qml resource for editing item
double _missionGimbalYaw = qQNaN();
double _missionVehicleYaw = qQNaN();
QGCMAVLink::VehicleClass_t _previousVTOLMode = QGCMAVLink::VehicleClassGeneric; ///< Generic == unknown
PlanMasterController* _masterController = nullptr;
MissionController* _missionController = nullptr;
......
......@@ -9,9 +9,12 @@
#include "QGC.h"
#include <qmath.h>
#include <float.h>
#include <QtGlobal>
namespace QGC
{
......@@ -137,4 +140,17 @@ quint32 crc32(const quint8 *src, unsigned len, unsigned state)
return state;
}
bool fuzzyCompare(double value1, double value2)
{
if (qIsNaN(value1) && qIsNaN(value2)) {
return true;
} else if (qIsNaN(value1) || qIsNaN(value2)) {
return false;
} else if (value1 == value2) {
return true;
} else {
return qFuzzyCompare(value1, value2);
}
}
}
......@@ -7,9 +7,7 @@
*
****************************************************************************/
#ifndef QGC_H
#define QGC_H
#pragma once
#include <QDateTime>
#include <QColor>
......@@ -42,7 +40,8 @@ void initTimer();
/** @brief Get the ground time since boot in milliseconds */
quint64 bootTimeMilliseconds();
const static int MAX_FLIGHT_TIME = 60 * 60 * 24 * 21;
/// Returns true if the two values are equal or close. Correctly handles 0 and NaN values.
bool fuzzyCompare(double value1, double value2);
class SLEEP : public QThread
{
......@@ -56,7 +55,3 @@ public:
quint32 crc32(const quint8 *src, unsigned len, unsigned state);
}
#define QGC_EVENTLOOP_DEBUG 0
#endif // QGC_H
......@@ -3835,11 +3835,6 @@ const QVariantList& Vehicle::staticCameraList() const
return emptyList;
}
bool Vehicle::vehicleYawsToNextWaypointInMission() const
{
return _firmwarePlugin->vehicleYawsToNextWaypointInMission(this);
}
void Vehicle::_setupAutoDisarmSignalling()
{
QString param = _firmwarePlugin->autoDisarmParameter(this);
......
......@@ -1125,9 +1125,6 @@ public:
QGCCameraManager* dynamicCameras () { return _cameras; }
QString hobbsMeter ();
/// @true: When flying a mission the vehicle is always facing towards the next waypoint
bool vehicleYawsToNextWaypointInMission() const;
/// The vehicle is responsible for making the initial request for the Plan.
/// @return: true: initial request is complete, false: initial request is still in progress;
bool initialPlanRequestComplete() const { return _initialPlanRequestComplete; }
......
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