Unverified Commit 403f864b authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #8956 from DonLakeFlyer/SupportedCommands

Plan: supportedMissionCommands is vehicle class sensitive
parents daa11a93 0a3eb89a
......@@ -715,12 +715,19 @@ FactMetaData* APMFirmwarePlugin::_getMetaDataForFact(QObject* parameterMetaData,
return nullptr;
}
QList<MAV_CMD> APMFirmwarePlugin::supportedMissionCommands(void)
QList<MAV_CMD> APMFirmwarePlugin::supportedMissionCommands(QGCMAVLink::VehicleClass_t vehicleClass)
{
return {
#if 0
// Waiting for module update
MAV_CMD_DO_SET_REVERSE,
#endif
};
QList<MAV_CMD> supportedCommands = {
MAV_CMD_NAV_WAYPOINT,
MAV_CMD_NAV_LOITER_UNLIM, MAV_CMD_NAV_LOITER_TURNS, MAV_CMD_NAV_LOITER_TIME,
MAV_CMD_NAV_RETURN_TO_LAUNCH, MAV_CMD_NAV_LAND, MAV_CMD_NAV_TAKEOFF,
MAV_CMD_NAV_RETURN_TO_LAUNCH,
MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT,
MAV_CMD_NAV_LOITER_TO_ALT,
MAV_CMD_NAV_SPLINE_WAYPOINT,
......@@ -744,12 +751,32 @@ QList<MAV_CMD> APMFirmwarePlugin::supportedMissionCommands(void)
MAV_CMD_DO_GRIPPER,
MAV_CMD_DO_GUIDED_LIMITS,
MAV_CMD_DO_AUTOTUNE_ENABLE,
};
QList<MAV_CMD> vtolCommands = {
MAV_CMD_NAV_VTOL_TAKEOFF, MAV_CMD_NAV_VTOL_LAND, MAV_CMD_DO_VTOL_TRANSITION,
#if 0
// Waiting for module update
MAV_CMD_DO_SET_REVERSE,
#endif
};
QList<MAV_CMD> flightCommands = {
MAV_CMD_NAV_LAND, MAV_CMD_NAV_TAKEOFF,
};
if (vehicleClass == QGCMAVLink::VehicleClassGeneric) {
supportedCommands += vtolCommands;
supportedCommands += flightCommands;
}
if (vehicleClass == QGCMAVLink::VehicleClassVTOL) {
supportedCommands += vtolCommands;
supportedCommands += flightCommands;
} else if (vehicleClass == QGCMAVLink::VehicleClassFixedWing || vehicleClass == QGCMAVLink::VehicleClassMultiRotor) {
supportedCommands += flightCommands;
}
if (qgcApp()->toolbox()->settingsManager()->planViewSettings()->useConditionGate()->rawValue().toBool()) {
supportedCommands.append(MAV_CMD_CONDITION_GATE);
}
return supportedCommands;
}
QString APMFirmwarePlugin::missionCommandOverrides(QGCMAVLink::VehicleClass_t vehicleClass) const
......
......@@ -72,7 +72,7 @@ public:
// Overrides from FirmwarePlugin
QList<VehicleComponent*> componentsForVehicle(AutoPilotPlugin* vehicle) override;
QList<MAV_CMD> supportedMissionCommands(void) override;
QList<MAV_CMD> supportedMissionCommands(QGCMAVLink::VehicleClass_t vehicleClass) override;
AutoPilotPlugin* autopilotPlugin (Vehicle* vehicle) override;
bool isCapable (const Vehicle *vehicle, FirmwareCapabilities capabilities) override;
......
......@@ -144,36 +144,6 @@ ArduSubFirmwarePlugin::ArduSubFirmwarePlugin(void):
_factRenameMap[QStringLiteral("airSpeed")] = QStringLiteral("");
}
QList<MAV_CMD> ArduSubFirmwarePlugin::supportedMissionCommands(void)
{
return {
MAV_CMD_NAV_WAYPOINT,
MAV_CMD_NAV_RETURN_TO_LAUNCH,
MAV_CMD_NAV_LAND,
MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT,
MAV_CMD_NAV_SPLINE_WAYPOINT,
MAV_CMD_NAV_GUIDED_ENABLE,
MAV_CMD_NAV_DELAY,
MAV_CMD_CONDITION_DELAY, MAV_CMD_CONDITION_DISTANCE, MAV_CMD_CONDITION_YAW,
MAV_CMD_DO_SET_MODE,
MAV_CMD_DO_JUMP,
MAV_CMD_DO_CHANGE_SPEED,
MAV_CMD_DO_SET_HOME,
MAV_CMD_DO_SET_RELAY, MAV_CMD_DO_REPEAT_RELAY,
MAV_CMD_DO_SET_SERVO, MAV_CMD_DO_REPEAT_SERVO,
MAV_CMD_DO_LAND_START,
MAV_CMD_DO_SET_ROI,
MAV_CMD_DO_DIGICAM_CONFIGURE, MAV_CMD_DO_DIGICAM_CONTROL,
MAV_CMD_DO_MOUNT_CONTROL,
MAV_CMD_DO_SET_CAM_TRIGG_DIST,
MAV_CMD_DO_FENCE_ENABLE,
MAV_CMD_DO_INVERTED_FLIGHT,
MAV_CMD_DO_GRIPPER,
MAV_CMD_DO_GUIDED_LIMITS,
MAV_CMD_DO_AUTOTUNE_ENABLE,
};
}
int ArduSubFirmwarePlugin::remapParamNameHigestMinorVersionNumber(int majorVersionNumber) const
{
// Remapping supports up to 3.6
......
......@@ -110,8 +110,6 @@ class ArduSubFirmwarePlugin : public APMFirmwarePlugin
public:
ArduSubFirmwarePlugin(void);
QList<MAV_CMD> supportedMissionCommands(void) final;
int defaultJoystickTXMode(void) final { return 3; }
void initializeStreamRates(Vehicle* vehicle) override final;
......
......@@ -174,7 +174,7 @@ bool FirmwarePlugin::sendHomePositionToVehicle(void)
return false;
}
QList<MAV_CMD> FirmwarePlugin::supportedMissionCommands(void)
QList<MAV_CMD> FirmwarePlugin::supportedMissionCommands(QGCMAVLink::VehicleClass_t vehicleClass)
{
// Generic supports all commands
return QList<MAV_CMD>();
......
......@@ -238,7 +238,7 @@ public:
virtual bool _isParameterVolatile(QObject* /*parameterMetaData*/, const QString& /*name*/, MAV_TYPE /*vehicleType*/) { return false; }
/// List of supported mission commands. Empty list for all commands supported.
virtual QList<MAV_CMD> supportedMissionCommands(void);
virtual QList<MAV_CMD> supportedMissionCommands(QGCMAVLink::VehicleClass_t vehicleClass);
/// Returns the name of the mission command json override file for the specified vehicle type.
/// @param vehicleClass Vehicle class to return file for, VehicleClassGeneric is a request for overrides for all vehicle types
......
......@@ -268,14 +268,13 @@ void PX4FirmwarePlugin::_getParameterMetaDataVersionInfo(const QString& metaData
return PX4ParameterMetaData::getParameterMetaDataVersionInfo(metaDataFile, majorVersion, minorVersion);
}
QList<MAV_CMD> PX4FirmwarePlugin::supportedMissionCommands(void)
QList<MAV_CMD> PX4FirmwarePlugin::supportedMissionCommands(QGCMAVLink::VehicleClass_t vehicleClass)
{
QList<MAV_CMD> cmds = {
QList<MAV_CMD> supportedCommands = {
MAV_CMD_NAV_WAYPOINT,
MAV_CMD_NAV_LOITER_UNLIM, MAV_CMD_NAV_LOITER_TIME, MAV_CMD_NAV_LOITER_TO_ALT,
MAV_CMD_NAV_LAND, MAV_CMD_NAV_TAKEOFF, MAV_CMD_NAV_RETURN_TO_LAUNCH,
MAV_CMD_NAV_LOITER_UNLIM, MAV_CMD_NAV_LOITER_TIME,
MAV_CMD_NAV_RETURN_TO_LAUNCH,
MAV_CMD_DO_JUMP,
MAV_CMD_DO_VTOL_TRANSITION, MAV_CMD_NAV_VTOL_TAKEOFF, MAV_CMD_NAV_VTOL_LAND,
MAV_CMD_DO_DIGICAM_CONTROL,
MAV_CMD_DO_SET_CAM_TRIGG_DIST,
MAV_CMD_DO_SET_SERVO,
......@@ -288,13 +287,33 @@ QList<MAV_CMD> PX4FirmwarePlugin::supportedMissionCommands(void)
MAV_CMD_IMAGE_START_CAPTURE, MAV_CMD_IMAGE_STOP_CAPTURE, MAV_CMD_VIDEO_START_CAPTURE, MAV_CMD_VIDEO_STOP_CAPTURE,
MAV_CMD_NAV_DELAY,
MAV_CMD_CONDITION_YAW,
MAV_CMD_NAV_LOITER_TO_ALT,
};
QList<MAV_CMD> vtolCommands = {
MAV_CMD_DO_VTOL_TRANSITION, MAV_CMD_NAV_VTOL_TAKEOFF, MAV_CMD_NAV_VTOL_LAND,
};
QList<MAV_CMD> flightCommands = {
MAV_CMD_NAV_LAND, MAV_CMD_NAV_TAKEOFF,
};
if (vehicleClass == QGCMAVLink::VehicleClassGeneric) {
supportedCommands += vtolCommands;
supportedCommands += flightCommands;
}
if (vehicleClass == QGCMAVLink::VehicleClassVTOL) {
supportedCommands += vtolCommands;
supportedCommands += flightCommands;
} else if (vehicleClass == QGCMAVLink::VehicleClassFixedWing || vehicleClass == QGCMAVLink::VehicleClassMultiRotor) {
supportedCommands += flightCommands;
}
if (qgcApp()->toolbox()->settingsManager()->planViewSettings()->useConditionGate()->rawValue().toBool()) {
cmds.append(MAV_CMD_CONDITION_GATE);
supportedCommands.append(MAV_CMD_CONDITION_GATE);
}
return cmds;
return supportedCommands;
}
QString PX4FirmwarePlugin::missionCommandOverrides(QGCMAVLink::VehicleClass_t vehicleClass) const
......
......@@ -29,7 +29,7 @@ public:
// Overrides from FirmwarePlugin
QList<VehicleComponent*> componentsForVehicle(AutoPilotPlugin* vehicle) override;
QList<MAV_CMD> supportedMissionCommands(void) override;
QList<MAV_CMD> supportedMissionCommands(QGCMAVLink::VehicleClass_t vehicleClass) override;
AutoPilotPlugin* autopilotPlugin (Vehicle* vehicle) override;
bool isCapable (const Vehicle *vehicle, FirmwareCapabilities capabilities) override;
......
......@@ -580,7 +580,7 @@ void CameraSection::_cameraActionChanged(void)
bool CameraSection::cameraModeSupported(void) const
{
return _specifyCameraMode || _masterController->controllerVehicle()->firmwarePlugin()->supportedMissionCommands().contains(MAV_CMD_SET_CAMERA_MODE);
return _specifyCameraMode || _masterController->controllerVehicle()->firmwarePlugin()->supportedMissionCommands(QGCMAVLink::VehicleClassGeneric).contains(MAV_CMD_SET_CAMERA_MODE);
}
void CameraSection::_dirtyIfSpecified(void)
......
......@@ -114,7 +114,7 @@ void MissionCommandTree::_buildAllCommands(Vehicle* vehicle, QGCMAVLink::Vehicle
}
// Build category list from supported commands
QList<MAV_CMD> supportedCommands = vehicle->firmwarePlugin()->supportedMissionCommands();
QList<MAV_CMD> supportedCommands = vehicle->firmwarePlugin()->supportedMissionCommands(vehicleClass);
for (MAV_CMD cmd: collapsedTree.keys()) {
if (supportedCommands.contains(cmd)) {
QString newCategory = collapsedTree[cmd]->category();
......@@ -193,15 +193,14 @@ QVariantList MissionCommandTree::getCommandsForCategory(Vehicle* vehicle, const
// 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.
FirmwarePlugin* firmwarePlugin = qgcApp()->toolbox()->firmwarePluginManager()->firmwarePluginForAutopilot(QGCMAVLink::firmwareClassToAutopilot(firmwareClass), QGCMAVLink::vehicleClassToMavType(vehicleClass));
QList<MAV_CMD> supportedCommands = firmwarePlugin->supportedMissionCommands();
QList<MAV_CMD> supportedCommands = firmwarePlugin->supportedMissionCommands(vehicleClass);
QVariantList list;
QMap<MAV_CMD, MissionCommandUIInfo*> commandMap = _allCommands[firmwareClass][vehicleClass];
for (MAV_CMD command: commandMap.keys()) {
if (supportedCommands.contains(command)) {
if (supportedCommands.isEmpty() || supportedCommands.contains(command)) {
MissionCommandUIInfo* uiInfo = commandMap[command];
if ((uiInfo->category() == category || category == _allCommandsCategory) &&
(showFlyThroughCommands || !uiInfo->specifiesCoordinate() || uiInfo->isStandaloneCoordinate())) {
if ((uiInfo->category() == category || category == _allCommandsCategory) && (showFlyThroughCommands || !uiInfo->specifiesCoordinate() || uiInfo->isStandaloneCoordinate())) {
list.append(QVariant::fromValue(uiInfo));
}
}
......
......@@ -29,13 +29,13 @@ void MissionCommandTreeEditorTest::_testEditorsWorker(QGCMAVLink::FirmwareClass_
PlanMasterController* masterController = new PlanMasterController();
FirmwarePlugin* firmwarePlugin = qgcApp()->toolbox()->firmwarePluginManager()->firmwarePluginForAutopilot(QGCMAVLink::firmwareClassToAutopilot(firmwareClass), QGCMAVLink::vehicleClassToMavType(vehicleClass));
if (firmwarePlugin->supportedMissionCommands().count() == 0) {
if (firmwarePlugin->supportedMissionCommands(vehicleClass).count() == 0) {
firmwarePlugin = qgcApp()->toolbox()->firmwarePluginManager()->firmwarePluginForAutopilot(QGCMAVLink::firmwareClassToAutopilot(QGCMAVLink::FirmwareClassPX4), QGCMAVLink::vehicleClassToMavType(vehicleClass));
}
int cColumns = firmwarePlugin->supportedMissionCommands().count();
int cColumns = firmwarePlugin->supportedMissionCommands(vehicleClass).count();
QVariantList varSimpleItems;
for (MAV_CMD command: firmwarePlugin->supportedMissionCommands()) {
for (MAV_CMD command: firmwarePlugin->supportedMissionCommands(vehicleClass)) {
SimpleMissionItem* simpleItem = new SimpleMissionItem(masterController, false /* flyView */, false /* forLoad */, this);
simpleItem->setCommand(command);
varSimpleItems.append(QVariant::fromValue(simpleItem));
......
......@@ -406,7 +406,7 @@ VisualMissionItem* MissionController::insertROIMissionItem(QGeoCoordinate coordi
{
SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(_insertSimpleMissionItemWorker(coordinate, MAV_CMD_DO_SET_ROI_LOCATION, visualItemIndex, makeCurrentItem));
if (!_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains(MAV_CMD_DO_SET_ROI_LOCATION)) {
if (!_controllerVehicle->firmwarePlugin()->supportedMissionCommands(QGCMAVLink::VehicleClassGeneric).contains(MAV_CMD_DO_SET_ROI_LOCATION)) {
simpleItem->setCommand(MAV_CMD_DO_SET_ROI) ;
simpleItem->missionItem().setParam1(MAV_ROI_LOCATION);
}
......@@ -418,7 +418,7 @@ VisualMissionItem* MissionController::insertCancelROIMissionItem(int visualItemI
{
SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(_insertSimpleMissionItemWorker(QGeoCoordinate(), MAV_CMD_DO_SET_ROI_NONE, visualItemIndex, makeCurrentItem));
if (!_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains(MAV_CMD_DO_SET_ROI_NONE)) {
if (!_controllerVehicle->firmwarePlugin()->supportedMissionCommands(QGCMAVLink::VehicleClassGeneric).contains(MAV_CMD_DO_SET_ROI_NONE)) {
simpleItem->setCommand(MAV_CMD_DO_SET_ROI) ;
simpleItem->missionItem().setParam1(MAV_ROI_NONE);
}
......
......@@ -1018,7 +1018,7 @@ void TransectStyleComplexItem::_buildAndAppendMissionItems(QList<MissionItem*>&
bool imagesInTurnaround = _cameraTriggerInTurnAroundFact.rawValue().toBool();
bool hasTurnarounds = _turnAroundDistance() != 0;
bool addTriggerAtBeginningEnd = !hoverAndCaptureEnabled() && imagesInTurnaround && triggerCamera();
bool useConditionGate = _controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains(MAV_CMD_CONDITION_GATE) &&
bool useConditionGate = _controllerVehicle->firmwarePlugin()->supportedMissionCommands(QGCMAVLink::VehicleClassGeneric).contains(MAV_CMD_CONDITION_GATE) &&
triggerCamera() &&
!hoverAndCaptureEnabled();
......
......@@ -652,7 +652,7 @@ Item {
text: qsTr("Takeoff")
iconSource: "/res/takeoff.svg"
enabled: _missionController.isInsertTakeoffValid
visible: toolStrip._isMissionLayer
visible: toolStrip._isMissionLayer && !_planMasterController.controllerVehicle.rover
onTriggered: {
toolStrip.allAddClickBoolsOff()
insertTakeItemAfterCurrent()
......
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