Commit 18c16023 authored by Gus Grubba's avatar Gus Grubba

Merge branch 'master' of https://github.com/mavlink/qgroundcontrol into qgc4

parents 9f33e4b2 c0ea93e9
......@@ -80,6 +80,7 @@
<file alias="Frames/Vectored6DOF.png">src/AutoPilotPlugins/APM/Images/vectored6dof-frame.png</file>
<file alias="Frames/SimpleROV-3.png">src/AutoPilotPlugins/APM/Images/simple3-frame.png</file>
<file alias="Frames/SimpleROV-4.png">src/AutoPilotPlugins/APM/Images/simple4-frame.png</file>
<file alias="Frames/SimpleROV-5.png">src/AutoPilotPlugins/APM/Images/simple5-frame.png</file>
<file alias="LogDownloadIcon">src/AnalyzeView/LogDownloadIcon.svg</file>
<file alias="LowBattery.svg">src/AutoPilotPlugins/PX4/Images/LowBattery.svg</file>
<file alias="LowBatteryLight.svg">src/AutoPilotPlugins/PX4/Images/LowBatteryLight.svg</file>
......
......@@ -103,6 +103,12 @@ SetupPage {
resource: "qrc:///qmlimages/Frames/SimpleROV-4.png"
paramValue: 5
}
ListElement {
name: "SimpleROV-5"
resource: "qrc:///qmlimages/Frames/SimpleROV-5.png"
paramValue: 6
}
}
Item {
......
......@@ -22,6 +22,7 @@ APMRoverMode::APMRoverMode(uint32_t mode, bool settable)
enumToString.insert(STEERING, "Steering");
enumToString.insert(HOLD, "Hold");
enumToString.insert(LOITER, "Loiter");
enumToString.insert(FOLLOW, "Follow");
enumToString.insert(SIMPLE, "Simple");
enumToString.insert(AUTO, "Auto");
enumToString.insert(RTL, "RTL");
......@@ -40,6 +41,7 @@ ArduRoverFirmwarePlugin::ArduRoverFirmwarePlugin(void)
supportedFlightModes << APMRoverMode(APMRoverMode::STEERING ,true);
supportedFlightModes << APMRoverMode(APMRoverMode::HOLD ,true);
supportedFlightModes << APMRoverMode(APMRoverMode::LOITER ,true);
supportedFlightModes << APMRoverMode(APMRoverMode::FOLLOW ,true);
supportedFlightModes << APMRoverMode(APMRoverMode::SIMPLE ,true);
supportedFlightModes << APMRoverMode(APMRoverMode::AUTO ,true);
supportedFlightModes << APMRoverMode(APMRoverMode::RTL ,true);
......
......@@ -25,6 +25,7 @@ public:
STEERING = 3,
HOLD = 4,
LOITER = 5,
FOLLOW = 6,
SIMPLE = 7,
AUTO = 10,
RTL = 11,
......
......@@ -9,6 +9,36 @@
"comment": "MAV_CMD_NAV_WAYPOINT",
"paramRemove": "2"
},
{
"id": 17,
"comment": "MAV_CMD_NAV_LOITER_UNLIM",
"param4": {
"label": "Heading",
"units": "radians",
"default": 0,
"decimalPlaces": 2
}
},
{
"id": 18,
"comment": "MAV_CMD_NAV_LOITER_TURNS",
"param4": {
"label": "Heading",
"units": "radians",
"default": 0,
"decimalPlaces": 2
}
},
{
"id": 19,
"comment": "MAV_CMD_NAV_LOITER_TIME",
"param4": {
"label": "Heading",
"units": "radians",
"default": 0,
"decimalPlaces": 2
}
},
{
"id": 22,
"comment": "MAV_CMD_NAV_TAKEOFF",
......
......@@ -9,6 +9,28 @@
"comment": "MAV_CMD_NAV_WAYPOINT",
"paramRemove": "1,3,4"
},
{
"id": 18,
"comment": "MAV_CMD_NAV_LOITER_TURNS",
"param4": {
"label": "Exit loiter from",
"enumStrings": "Center,Tangent",
"enumValues": "0,1",
"default": 1,
"decimalPlaces": 0
}
},
{
"id": 19,
"comment": "MAV_CMD_NAV_LOITER_TIME",
"param4": {
"label": "Exit loiter from",
"enumStrings": "Center,Tangent",
"enumValues": "0,1",
"default": 1,
"decimalPlaces": 0
}
},
{
"id": 21,
"comment": "MAV_CMD_NAV_LAND",
......
......@@ -9,39 +9,6 @@
"comment": "MAV_CMD_NAV_WAYPOINT",
"paramRemove": "2,3"
},
{
"id": 17,
"comment": "MAV_CMD_NAV_LOITER_UNLIM",
"param4": {
"label": "Heading",
"units": "radians",
"nanUnchanged": true,
"default": null,
"decimalPlaces": 2
}
},
{
"id": 18,
"comment": "MAV_CMD_NAV_LOITER_TURNS",
"param4": {
"label": "Heading",
"units": "radians",
"nanUnchanged": true,
"default": null,
"decimalPlaces": 2
}
},
{
"id": 19,
"comment": "MAV_CMD_NAV_LOITER_TIME",
"param4": {
"label": "Heading",
"units": "radians",
"nanUnchanged": true,
"default": null,
"decimalPlaces": 2
}
},
{
"id": 21,
"comment": "MAV_CMD_NAV_LAND",
......
......@@ -100,6 +100,12 @@ FixedWingLandingComplexItem::FixedWingLandingComplexItem(Vehicle* vehicle, bool
connect(this, &FixedWingLandingComplexItem::altitudesAreRelativeChanged, this, &FixedWingLandingComplexItem::coordinateHasRelativeAltitudeChanged);
connect(this, &FixedWingLandingComplexItem::altitudesAreRelativeChanged, this, &FixedWingLandingComplexItem::exitCoordinateHasRelativeAltitudeChanged);
if (vehicle->apmFirmware()) {
// ArduPilot does not support camera commands
_stopTakingVideoFact.setRawValue(false);
_stopTakingPhotosFact.setRawValue(false);
}
if (_valueSetIsDistanceFact.rawValue().toBool()) {
_recalcFromHeadingAndDistanceChange();
} else {
......
......@@ -101,7 +101,8 @@
"param4": {
"label": "Heading",
"units": "radians",
"default": 0,
"nanUnchanged": true,
"default": null,
"decimalPlaces": 2
}
},
......@@ -128,7 +129,8 @@
"param4": {
"label": "Heading",
"units": "radians",
"default": 0,
"nanUnchanged": true,
"default": null,
"decimalPlaces": 2
}
},
......
......@@ -32,10 +32,14 @@ Rectangle {
//property real availableWidth ///< Width for control
//property var missionItem ///< Mission Item for editor
property var _masterControler: masterController
property var _missionController: _masterControler.missionController
property var _missionVehicle: _masterControler.controllerVehicle
property real _margin: ScreenTools.defaultFontPixelWidth / 2
property real _spacer: ScreenTools.defaultFontPixelWidth / 2
property string _setToVehicleHeadingStr: qsTr("Set to vehicle heading")
property string _setToVehicleLocationStr: qsTr("Set to vehicle location")
property bool _showCameraSection: !_missionVehicle.apmFirmware
ExclusiveGroup { id: distanceGlideGroup }
......@@ -165,15 +169,16 @@ Rectangle {
}
SectionHeader {
id: cameraSection
text: qsTr("Camera")
id: cameraSection
text: qsTr("Camera")
visible: _showCameraSection
}
Column {
anchors.left: parent.left
anchors.right: parent.right
spacing: _margin
visible: cameraSection.checked
visible: _showCameraSection && cameraSection.checked
Item { width: 1; height: _spacer }
......
......@@ -147,6 +147,15 @@ void QGroundControlQmlGlobal::startAPMArduSubMockLink(bool sendStatusText)
#endif
}
void QGroundControlQmlGlobal::startAPMArduRoverMockLink(bool sendStatusText)
{
#ifdef QT_DEBUG
MockLink::startAPMArduRoverMockLink(sendStatusText);
#else
Q_UNUSED(sendStatusText);
#endif
}
void QGroundControlQmlGlobal::stopOneMockLink(void)
{
#ifdef QT_DEBUG
......
......@@ -121,6 +121,7 @@ public:
Q_INVOKABLE void startAPMArduCopterMockLink (bool sendStatusText);
Q_INVOKABLE void startAPMArduPlaneMockLink (bool sendStatusText);
Q_INVOKABLE void startAPMArduSubMockLink (bool sendStatusText);
Q_INVOKABLE void startAPMArduRoverMockLink (bool sendStatusText);
Q_INVOKABLE void stopOneMockLink (void);
/// Converts from meters to the user specified distance unit
......
......@@ -1159,64 +1159,46 @@ MockLink* MockLink::_startMockLink(MockConfiguration* mockConfig)
return qobject_cast<MockLink*>(linkMgr->createConnectedLink(config));
}
MockLink* MockLink::startPX4MockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
MockLink* MockLink::_startMockLinkWorker(QString configName, MAV_AUTOPILOT firmwareType, MAV_TYPE vehicleType, bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
{
MockConfiguration* mockConfig = new MockConfiguration("PX4 MockLink");
MockConfiguration* mockConfig = new MockConfiguration(configName);
mockConfig->setFirmwareType(MAV_AUTOPILOT_PX4);
mockConfig->setVehicleType(MAV_TYPE_QUADROTOR);
mockConfig->setFirmwareType(firmwareType);
mockConfig->setVehicleType(vehicleType);
mockConfig->setSendStatusText(sendStatusText);
mockConfig->setFailureMode(failureMode);
return _startMockLink(mockConfig);
}
MockLink* MockLink::startGenericMockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
MockLink* MockLink::startPX4MockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
{
MockConfiguration* mockConfig = new MockConfiguration("Generic MockLink");
mockConfig->setFirmwareType(MAV_AUTOPILOT_GENERIC);
mockConfig->setVehicleType(MAV_TYPE_QUADROTOR);
mockConfig->setSendStatusText(sendStatusText);
mockConfig->setFailureMode(failureMode);
return _startMockLinkWorker("PX4 MultiRotor MockLink", MAV_AUTOPILOT_PX4, MAV_TYPE_QUADROTOR, sendStatusText, failureMode);
}
return _startMockLink(mockConfig);
MockLink* MockLink::startGenericMockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
{
return _startMockLinkWorker("Generic MockLink", MAV_AUTOPILOT_GENERIC, MAV_TYPE_QUADROTOR, sendStatusText, failureMode);
}
MockLink* MockLink::startAPMArduCopterMockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
{
MockConfiguration* mockConfig = new MockConfiguration("APM ArduCopter MockLink");
mockConfig->setFirmwareType(MAV_AUTOPILOT_ARDUPILOTMEGA);
mockConfig->setVehicleType(MAV_TYPE_QUADROTOR);
mockConfig->setSendStatusText(sendStatusText);
mockConfig->setFailureMode(failureMode);
return _startMockLink(mockConfig);
return _startMockLinkWorker("ArduCopter MockLink",MAV_AUTOPILOT_ARDUPILOTMEGA, MAV_TYPE_QUADROTOR, sendStatusText, failureMode);
}
MockLink* MockLink::startAPMArduPlaneMockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
{
MockConfiguration* mockConfig = new MockConfiguration("APM ArduPlane MockLink");
mockConfig->setFirmwareType(MAV_AUTOPILOT_ARDUPILOTMEGA);
mockConfig->setVehicleType(MAV_TYPE_FIXED_WING);
mockConfig->setSendStatusText(sendStatusText);
mockConfig->setFailureMode(failureMode);
return _startMockLink(mockConfig);
return _startMockLinkWorker("ArduPlane MockLink", MAV_AUTOPILOT_ARDUPILOTMEGA, MAV_TYPE_FIXED_WING, sendStatusText, failureMode);
}
MockLink* MockLink::startAPMArduSubMockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
{
MockConfiguration* mockConfig = new MockConfiguration("APM ArduSub MockLink");
mockConfig->setFirmwareType(MAV_AUTOPILOT_ARDUPILOTMEGA);
mockConfig->setVehicleType(MAV_TYPE_SUBMARINE);
mockConfig->setSendStatusText(sendStatusText);
mockConfig->setFailureMode(failureMode);
return _startMockLinkWorker("ArduSub MockLink", MAV_AUTOPILOT_ARDUPILOTMEGA, MAV_TYPE_SUBMARINE, sendStatusText, failureMode);
}
return _startMockLink(mockConfig);
MockLink* MockLink::startAPMArduRoverMockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
{
return _startMockLinkWorker("ArduRover MockLink", MAV_AUTOPILOT_ARDUPILOTMEGA, MAV_TYPE_GROUND_ROVER, sendStatusText, failureMode);
}
void MockLink::_sendRCChannels(void)
......
......@@ -156,6 +156,7 @@ public:
static MockLink* startAPMArduCopterMockLink (bool sendStatusText, MockConfiguration::FailureMode_t failureMode = MockConfiguration::FailNone);
static MockLink* startAPMArduPlaneMockLink (bool sendStatusText, MockConfiguration::FailureMode_t failureMode = MockConfiguration::FailNone);
static MockLink* startAPMArduSubMockLink (bool sendStatusText, MockConfiguration::FailureMode_t failureMode = MockConfiguration::FailNone);
static MockLink* startAPMArduRoverMockLink (bool sendStatusText, MockConfiguration::FailureMode_t failureMode = MockConfiguration::FailNone);
private slots:
virtual void _writeBytes(const QByteArray bytes);
......@@ -203,6 +204,7 @@ private:
void _sendADSBVehicles(void);
void _moveADSBVehicle(void);
static MockLink* _startMockLinkWorker(QString configName, MAV_AUTOPILOT firmwareType, MAV_TYPE vehicleType, bool sendStatusText, MockConfiguration::FailureMode_t failureMode);
static MockLink* _startMockLink(MockConfiguration* mockConfig);
MockLinkMissionItemHandler _missionItemHandler;
......
......@@ -52,6 +52,10 @@ Rectangle {
text: qsTr("APM ArduSub Vehicle")
onClicked: QGroundControl.startAPMArduSubMockLink(sendStatusText.checked)
}
QGCButton {
text: qsTr("APM ArduRover Vehicle")
onClicked: QGroundControl.startAPMArduRoverMockLink(sendStatusText.checked)
}
QGCButton {
text: qsTr("Generic Vehicle")
onClicked: QGroundControl.startGenericMockLink(sendStatusText.checked)
......
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