diff --git a/src/MissionManager/MissionController.cc b/src/MissionManager/MissionController.cc index 9eedc40ec987a68e6d14c6ee1159da596a843c63..1b3e803f8ed1997284e4c50efcd9c645e1c04270 100644 --- a/src/MissionManager/MissionController.cc +++ b/src/MissionManager/MissionController.cc @@ -349,7 +349,7 @@ int MissionController::insertSimpleMissionItem(QGeoCoordinate coordinate, int i) newItem->setCoordinate(coordinate); newItem->setCommand(MAV_CMD_NAV_WAYPOINT); _initVisualItem(newItem); - if (_visualItems->count() == 1) { + if (_visualItems->count() == 1 && (_controllerVehicle->fixedWing() || _controllerVehicle->vtol() || _controllerVehicle->multiRotor())) { MAV_CMD takeoffCmd = _controllerVehicle->vtol() ? MAV_CMD_NAV_VTOL_TAKEOFF : MAV_CMD_NAV_TAKEOFF; if (_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains((MAV_CMD)takeoffCmd)) { newItem->setCommand(takeoffCmd);