Commit 0a821d49 authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #5471 from DonLakeFlyer/MultiVehicle

More support in multi-vehicle view
parents c64f0626 260b4bc1
......@@ -73,7 +73,7 @@ public:
QString missionFlightMode (void) const override { return QString("Auto"); }
QString rtlFlightMode (void) const override { return QString("RTL"); }
QString landFlightMode (void) const override { return QString("Land"); }
QString takeControlFlightMode (void) const override { return QString("Stablize"); }
QString takeControlFlightMode (void) const override { return QString("Loiter"); }
bool vehicleYawsToNextWaypointInMission (const Vehicle* vehicle) const final;
QString autoDisarmParameter (Vehicle* vehicle) final { Q_UNUSED(vehicle); return QStringLiteral("DISARM_DELAY"); }
void startMission (Vehicle* vehicle) override;
......
......@@ -331,7 +331,7 @@ QGCView {
QGCRadioButton {
exclusiveGroup: multiVehicleSelectorGroup
text: qsTr("Multi-Vehicle (WIP)")
text: qsTr("Multi-Vehicle")
color: mapPal.text
}
}
......@@ -339,7 +339,7 @@ QGCView {
FlightDisplayViewWidgets {
id: flightDisplayViewWidgets
z: _panel.z + 4
height: ScreenTools.availableHeight
height: ScreenTools.availableHeight - (singleMultiSelector.visible ? singleMultiSelector.height + _margins : 0)
anchors.left: parent.left
anchors.right: altitudeSlider.visible ? altitudeSlider.left : parent.right
anchors.bottom: parent.bottom
......@@ -399,16 +399,16 @@ QGCView {
}
MultiVehicleList {
anchors.margins: _margins
anchors.top: singleMultiSelector.bottom
anchors.right: parent.right
anchors.bottom: parent.bottom
width: ScreenTools.defaultFontPixelWidth * 30
visible: !singleVehicleView.checked
z: _panel.z + 4
anchors.margins: _margins
anchors.top: singleMultiSelector.bottom
anchors.right: parent.right
anchors.bottom: parent.bottom
width: ScreenTools.defaultFontPixelWidth * 30
visible: !singleVehicleView.checked
z: _panel.z + 4
guidedActionsController: _guidedController
}
//-- Virtual Joystick
Loader {
id: virtualJoystickMultiTouch
......
......@@ -64,6 +64,7 @@ Item {
readonly property string orbitMessage: qsTr("Orbit the vehicle around the current location.")
readonly property string landAbortMessage: qsTr("Abort the landing sequence.")
readonly property string pauseMessage: qsTr("Pause the vehicle at it's current position.")
readonly property string mvPauseMessage: qsTr("Pause all vehicles at their current position.")
readonly property int actionRTL: 1
readonly property int actionLand: 2
......@@ -81,6 +82,8 @@ Item {
readonly property int actionResumeMission: 14
readonly property int actionResumeMissionReady: 15
readonly property int actionPause: 16
readonly property int actionMVPause: 17
readonly property int actionMVStartMission: 18
property bool showEmergenyStop: !_hideEmergenyStop && _activeVehicle && _vehicleArmed && _vehicleFlying
property bool showArm: _activeVehicle && !_vehicleArmed
......@@ -195,6 +198,11 @@ Item {
confirmDialog.message = startMissionMessage
confirmDialog.hideTrigger = Qt.binding(function() { return !showStartMission })
break;
case actionMVStartMission:
confirmDialog.title = startMissionTitle
confirmDialog.message = startMissionMessage
confirmDialog.hideTrigger = true
break;
case actionContinueMission:
confirmDialog.title = continueMissionTitle
confirmDialog.message = continueMissionMessage
......@@ -251,6 +259,11 @@ Item {
confirmDialog.message = pauseMessage
confirmDialog.hideTrigger = Qt.binding(function() { return !showPause })
break;
case actionMVPause:
confirmDialog.title = pauseTitle
confirmDialog.message = mvPauseMessage
confirmDialog.hideTrigger = true
break;
default:
console.warn("Unknown actionCode", actionCode)
return
......@@ -281,6 +294,13 @@ Item {
case actionContinueMission:
_activeVehicle.startMission()
break
case actionMVStartMission:
var rgVehicle = QGroundControl.multiVehicleManager.vehicles
for (var i=0; i<rgVehicle.count; i++) {
var vehicle = rgVehicle.get(i)
vehicle.startMission()
}
break
case actionArm:
_activeVehicle.armed = true
break
......@@ -308,6 +328,13 @@ Item {
case actionPause:
_activeVehicle.pauseVehicle()
break
case actionMVPause:
var rgVehicle = QGroundControl.multiVehicleManager.vehicles
for (var i=0; i<rgVehicle.count; i++) {
var vehicle = rgVehicle.get(i)
vehicle.pauseVehicle()
}
break
default:
console.warn(qsTr("Internal error: unknown actionCode"), actionCode)
break
......
......@@ -18,118 +18,163 @@ import QGroundControl.Palette 1.0
import QGroundControl.Vehicle 1.0
import QGroundControl.FlightMap 1.0
QGCListView {
id: missionItemEditorListView
spacing: ScreenTools.defaultFontPixelHeight / 2
orientation: ListView.Vertical
model: QGroundControl.multiVehicleManager.vehicles
cacheBuffer: _cacheBuffer < 0 ? 0 : _cacheBuffer
clip: true
property real _margin: ScreenTools.defaultFontPixelWidth / 2
property real _cacheBuffer: height * 2
property real _widgetHeight: ScreenTools.defaultFontPixelHeight * 3
delegate: Rectangle {
width: parent.width
height: innerColumn.y + innerColumn.height + _margin
color: qgcPal.missionItemEditor
opacity: 0.8
radius: _margin
property var _vehicle: object
property color _textColor: "black"
QGCPalette { id: qgcPal }
Row {
id: widgetLayout
anchors.margins: _margin
anchors.top: parent.top
anchors.right: parent.right
spacing: ScreenTools.defaultFontPixelWidth / 2
layoutDirection: Qt.RightToLeft
QGCCompassWidget {
size: _widgetHeight
vehicle: _vehicle
}
QGCAttitudeWidget {
size: _widgetHeight
vehicle: _vehicle
}
}
Item {
property var guidedActionsController
RowLayout {
anchors.top: widgetLayout.top
anchors.bottom: widgetLayout.bottom
anchors.left: parent.left
anchors.right: widgetLayout.left
spacing: ScreenTools.defaultFontPixelWidth / 2
property real _margin: ScreenTools.defaultFontPixelWidth / 2
property real _widgetHeight: ScreenTools.defaultFontPixelHeight * 3
property color _textColor: "black"
property real _rectOpacity: 0.8
QGCLabel {
Layout.alignment: Qt.AlignTop
text: _vehicle.id
color: _textColor
}
QGCPalette { id: qgcPal }
FlightModeMenu {
font.pointSize: ScreenTools.largeFontPointSize
color: _textColor
activeVehicle: _vehicle
}
}
NoMouseThroughRectangle {
id: mvCommands
anchors.left: parent.left
anchors.right: parent.right
height: mvCommandsColumn.height + (_margin *2)
color: qgcPal.missionItemEditor
opacity: _rectOpacity
radius: _margin
Column {
id: innerColumn
id: mvCommandsColumn
anchors.margins: _margin
anchors.top: parent.top
anchors.left: parent.left
anchors.right: parent.right
anchors.top: widgetLayout.bottom
spacing: _margin
Rectangle {
QGCLabel {
anchors.left: parent.left
anchors.right: parent.right
height: 5
color: "green"
text: qsTr("The following commands will be applied to all vehicles")
color: _textColor
wrapMode: Text.WordWrap
font.pointSize: ScreenTools.smallFontPointSize
}
Row {
spacing: ScreenTools.defaultFontPixelWidth
spacing: _margin
QGCButton {
text: "Arm"
visible: !_vehicle.armed
onClicked: _vehicle.armed = true
text: "Pause"
onClicked: guidedActionsController.confirmAction(guidedActionsController.actionMVPause)
}
QGCButton {
text: "Start"
visible: _vehicle.armed && _vehicle.flightMode != _vehicle.missionFlightMode
onClicked: _vehicle.flightMode = _vehicle.missionFlightMode
text: "Start Mision"
onClicked: guidedActionsController.confirmAction(guidedActionsController.actionMVStartMission)
}
QGCButton {
text: "Stop"
visible: _vehicle.armed && _vehicle.pauseVehicleSupported
onClicked: _vehicle.pauseVehicle()
}
QGCButton {
text: "RTL"
visible: _vehicle.armed && _vehicle.flightMode != _vehicle.rtlFlightMode
onClicked: _vehicle.flightMode = _vehicle.rtlFlightMode
}
QGCButton {
text: "Take control"
visible: _vehicle.armed && _vehicle.flightMode != _vehicle.takeControlFlightMode
onClicked: _vehicle.flightMode = _vehicle.takeControlFlightMode
}
}
}
}
} // QGCListView
QGCListView {
id: missionItemEditorListView
anchors.left: parent.left
anchors.right: parent.right
anchors.topMargin: _margin
anchors.top: mvCommands.bottom
anchors.bottom: parent.bottom
spacing: ScreenTools.defaultFontPixelHeight / 2
orientation: ListView.Vertical
model: QGroundControl.multiVehicleManager.vehicles
cacheBuffer: _cacheBuffer < 0 ? 0 : _cacheBuffer
clip: true
property real _cacheBuffer: height * 2
delegate: Rectangle {
width: parent.width
height: innerColumn.y + innerColumn.height + _margin
color: qgcPal.missionItemEditor
opacity: _rectOpacity
radius: _margin
property var _vehicle: object
ColumnLayout {
id: innerColumn
anchors.margins: _margin
anchors.top: parent.top
anchors.left: parent.left
anchors.right: parent.left
spacing: _margin
RowLayout {
anchors.left: parent.left
anchors.right: parent.left
QGCLabel {
Layout.alignment: Qt.AlignTop
text: _vehicle.id
color: _textColor
}
ColumnLayout {
Layout.alignment: Qt.AlignCenter
spacing: _margin
FlightModeMenu {
anchors.horizontalCenter: parent.horizontalCenter
font.pointSize: ScreenTools.largeFontPointSize
color: _textColor
activeVehicle: _vehicle
}
QGCLabel {
anchors.horizontalCenter: parent.horizontalCenter
text: _vehicle.armed ? qsTr("Armed") : qsTr("Disarmed")
color: _textColor
}
}
QGCCompassWidget {
size: _widgetHeight
vehicle: _vehicle
}
QGCAttitudeWidget {
size: _widgetHeight
vehicle: _vehicle
}
} // RowLayout
Row {
spacing: ScreenTools.defaultFontPixelWidth
QGCButton {
text: "Arm"
visible: !_vehicle.armed
onClicked: _vehicle.armed = true
}
QGCButton {
text: "Start Mission"
visible: _vehicle.armed && _vehicle.flightMode != _vehicle.missionFlightMode
onClicked: _vehicle.startMission()
}
QGCButton {
text: "Pause"
visible: _vehicle.armed && _vehicle.pauseVehicleSupported
onClicked: _vehicle.pauseVehicle()
}
QGCButton {
text: "RTL"
visible: _vehicle.armed && _vehicle.flightMode != _vehicle.rtlFlightMode
onClicked: _vehicle.flightMode = _vehicle.rtlFlightMode
}
QGCButton {
text: "Take control"
visible: _vehicle.armed && _vehicle.flightMode != _vehicle.takeControlFlightMode
onClicked: _vehicle.flightMode = _vehicle.takeControlFlightMode
}
} // Row
} // ColumnLayout
} // delegate - Rectangle
} // QGCListView
} // Item
......@@ -33,11 +33,13 @@ QGC_LOGGING_CATEGORY(MockLinkVerboseLog, "MockLinkVerboseLog")
///
/// @author Don Gagne <don@thegagnes.com>
float MockLink::_vehicleLatitude = 47.633033f;
float MockLink::_vehicleLongitude = -122.08794f;
float MockLink::_vehicleAltitude = 3.5f;
int MockLink::_nextVehicleSystemId = 128;
const char* MockLink::_failParam = "COM_FLTMODE6";
// Vehicle position is set close to default Gazebo vehicle location. This allows for multi-vehicle
// testing of a gazebo vehicle and a mocklink vehicle
double MockLink::_defaultVehicleLatitude = 47.397f;
double MockLink::_defaultVehicleLongitude = 8.5455f;
double MockLink::_defaultVehicleAltitude = 488.056f;
int MockLink::_nextVehicleSystemId = 128;
const char* MockLink::_failParam = "COM_FLTMODE6";
const char* MockConfiguration::_firmwareTypeKey = "FirmwareType";
const char* MockConfiguration::_vehicleTypeKey = "VehicleType";
......@@ -45,29 +47,32 @@ const char* MockConfiguration::_sendStatusTextKey = "SendStatusText";
const char* MockConfiguration::_failureModeKey = "FailureMode";
MockLink::MockLink(SharedLinkConfigurationPointer& config)
: LinkInterface(config)
, _missionItemHandler(this, qgcApp()->toolbox()->mavlinkProtocol())
, _name("MockLink")
, _connected(false)
, _mavlinkChannel(0)
, _vehicleSystemId(_nextVehicleSystemId++)
, _vehicleComponentId(MAV_COMP_ID_AUTOPILOT1)
, _inNSH(false)
, _mavlinkStarted(true)
, _mavBaseMode(MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_CUSTOM_MODE_ENABLED)
, _mavState(MAV_STATE_STANDBY)
, _firmwareType(MAV_AUTOPILOT_PX4)
, _vehicleType(MAV_TYPE_QUADROTOR)
, _fileServer(NULL)
, _sendStatusText(false)
, _apmSendHomePositionOnEmptyList(false)
, _failureMode(MockConfiguration::FailNone)
, _sendHomePositionDelayCount(10) // No home position for 4 seconds
, _sendGPSPositionDelayCount(100) // No gps lock for 5 seconds
: LinkInterface (config)
, _missionItemHandler (this, qgcApp()->toolbox()->mavlinkProtocol())
, _name ("MockLink")
, _connected (false)
, _mavlinkChannel (0)
, _vehicleSystemId (_nextVehicleSystemId++)
, _vehicleComponentId (MAV_COMP_ID_AUTOPILOT1)
, _inNSH (false)
, _mavlinkStarted (true)
, _mavBaseMode (MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_CUSTOM_MODE_ENABLED)
, _mavState (MAV_STATE_STANDBY)
, _firmwareType (MAV_AUTOPILOT_PX4)
, _vehicleType (MAV_TYPE_QUADROTOR)
, _vehicleLatitude (_defaultVehicleLatitude + ((_vehicleSystemId - 128) * 0.0001)) // Slight offset for each vehicle
, _vehicleLongitude (_defaultVehicleLongitude + ((_vehicleSystemId - 128) * 0.0001))
, _vehicleAltitude (_defaultVehicleAltitude)
, _fileServer (NULL)
, _sendStatusText (false)
, _apmSendHomePositionOnEmptyList (false)
, _failureMode (MockConfiguration::FailNone)
, _sendHomePositionDelayCount (10) // No home position for 4 seconds
, _sendGPSPositionDelayCount (100) // No gps lock for 5 seconds
, _currentParamRequestListComponentIndex(-1)
, _currentParamRequestListParamIndex(-1)
, _logDownloadCurrentOffset(0)
, _logDownloadBytesRemaining(0)
, _currentParamRequestListParamIndex (-1)
, _logDownloadCurrentOffset (0)
, _logDownloadBytesRemaining (0)
{
MockConfiguration* mockConfig = qobject_cast<MockConfiguration*>(_config.data());
_firmwareType = mockConfig->firmwareType();
......
......@@ -216,6 +216,9 @@ private:
MAV_AUTOPILOT _firmwareType;
MAV_TYPE _vehicleType;
double _vehicleLatitude;
double _vehicleLongitude;
double _vehicleAltitude;
MockLinkFileServer* _fileServer;
......@@ -236,9 +239,9 @@ private:
uint32_t _logDownloadCurrentOffset; ///< Current offset we are sending from
uint32_t _logDownloadBytesRemaining; ///< Number of bytes still to send, 0 = send inactive
static float _vehicleLatitude;
static float _vehicleLongitude;
static float _vehicleAltitude;
static double _defaultVehicleLatitude;
static double _defaultVehicleLongitude;
static double _defaultVehicleAltitude;
static int _nextVehicleSystemId;
static const char* _failParam;
};
......
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