Commit ce415f6d authored by Don Gagne's avatar Don Gagne

Add support for VTOL Transition

parent b6d12211
...@@ -9,6 +9,7 @@ ...@@ -9,6 +9,7 @@
<file alias="GPSRTKIndicator.qml">src/ui/toolbar/GPSRTKIndicator.qml</file> <file alias="GPSRTKIndicator.qml">src/ui/toolbar/GPSRTKIndicator.qml</file>
<file alias="MessageIndicator.qml">src/ui/toolbar/MessageIndicator.qml</file> <file alias="MessageIndicator.qml">src/ui/toolbar/MessageIndicator.qml</file>
<file alias="ModeIndicator.qml">src/ui/toolbar/ModeIndicator.qml</file> <file alias="ModeIndicator.qml">src/ui/toolbar/ModeIndicator.qml</file>
<file alias="VTOLModeIndicator.qml">src/ui/toolbar/VTOLModeIndicator.qml</file>
<file alias="RCRSSIIndicator.qml">src/ui/toolbar/RCRSSIIndicator.qml</file> <file alias="RCRSSIIndicator.qml">src/ui/toolbar/RCRSSIIndicator.qml</file>
<file alias="TelemetryRSSIIndicator.qml">src/ui/toolbar/TelemetryRSSIIndicator.qml</file> <file alias="TelemetryRSSIIndicator.qml">src/ui/toolbar/TelemetryRSSIIndicator.qml</file>
<file alias="JoystickIndicator.qml">src/ui/toolbar/JoystickIndicator.qml</file> <file alias="JoystickIndicator.qml">src/ui/toolbar/JoystickIndicator.qml</file>
......
...@@ -335,6 +335,7 @@ const QVariantList &FirmwarePlugin::toolBarIndicators(const Vehicle* vehicle) ...@@ -335,6 +335,7 @@ const QVariantList &FirmwarePlugin::toolBarIndicators(const Vehicle* vehicle)
_toolBarIndicatorList.append(QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/RCRSSIIndicator.qml"))); _toolBarIndicatorList.append(QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/RCRSSIIndicator.qml")));
_toolBarIndicatorList.append(QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/BatteryIndicator.qml"))); _toolBarIndicatorList.append(QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/BatteryIndicator.qml")));
_toolBarIndicatorList.append(QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/ModeIndicator.qml"))); _toolBarIndicatorList.append(QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/ModeIndicator.qml")));
_toolBarIndicatorList.append(QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/VTOLModeIndicator.qml")));
_toolBarIndicatorList.append(QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/ArmedIndicator.qml"))); _toolBarIndicatorList.append(QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/ArmedIndicator.qml")));
_toolBarIndicatorList.append(QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/GPSRTKIndicator.qml"))); _toolBarIndicatorList.append(QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/GPSRTKIndicator.qml")));
} }
......
...@@ -48,6 +48,7 @@ Item { ...@@ -48,6 +48,7 @@ Item {
readonly property string landAbortTitle: qsTr("Land Abort") readonly property string landAbortTitle: qsTr("Land Abort")
readonly property string setWaypointTitle: qsTr("Set Waypoint") readonly property string setWaypointTitle: qsTr("Set Waypoint")
readonly property string gotoTitle: qsTr("Goto Location") readonly property string gotoTitle: qsTr("Goto Location")
readonly property string vtolTransitionTitle: qsTr("VTOL Transition")
readonly property string armMessage: qsTr("Arm the vehicle.") readonly property string armMessage: qsTr("Arm the vehicle.")
readonly property string disarmMessage: qsTr("Disarm the vehicle") readonly property string disarmMessage: qsTr("Disarm the vehicle")
...@@ -67,6 +68,8 @@ Item { ...@@ -67,6 +68,8 @@ Item {
readonly property string landAbortMessage: qsTr("Abort the landing sequence.") 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 pauseMessage: qsTr("Pause the vehicle at it's current position.")
readonly property string mvPauseMessage: qsTr("Pause all vehicles at their current position.") readonly property string mvPauseMessage: qsTr("Pause all vehicles at their current position.")
readonly property string vtolTransitionFwdMessage: qsTr("Transition VTOL to fixed wing flight.")
readonly property string vtolTransitionMRMessage: qsTr("Transition VTOL to multi-rotor flight.")
readonly property int actionRTL: 1 readonly property int actionRTL: 1
readonly property int actionLand: 2 readonly property int actionLand: 2
...@@ -87,6 +90,8 @@ Item { ...@@ -87,6 +90,8 @@ Item {
readonly property int actionPause: 17 readonly property int actionPause: 17
readonly property int actionMVPause: 18 readonly property int actionMVPause: 18
readonly property int actionMVStartMission: 19 readonly property int actionMVStartMission: 19
readonly property int actionVtolTransitionToFwdFlight: 20
readonly property int actionVtolTransitionToMRFlight: 21
property bool showEmergenyStop: !_hideEmergenyStop && _activeVehicle && _vehicleArmed && _vehicleFlying property bool showEmergenyStop: !_hideEmergenyStop && _activeVehicle && _vehicleArmed && _vehicleFlying
property bool showArm: _activeVehicle && !_vehicleArmed property bool showArm: _activeVehicle && !_vehicleArmed
...@@ -287,6 +292,16 @@ Item { ...@@ -287,6 +292,16 @@ Item {
confirmDialog.message = mvPauseMessage confirmDialog.message = mvPauseMessage
confirmDialog.hideTrigger = true confirmDialog.hideTrigger = true
break; break;
case actionVtolTransitionToFwdFlight:
confirmDialog.title = vtolTransitionTitle
confirmDialog.message = vtolTransitionFwdMessage
confirmDialog.hideTrigger = true
break
case actionVtolTransitionToMRFlight:
confirmDialog.title = vtolTransitionTitle
confirmDialog.message = vtolTransitionMRMessage
confirmDialog.hideTrigger = true
break
default: default:
console.warn("Unknown actionCode", actionCode) console.warn("Unknown actionCode", actionCode)
return return
...@@ -359,6 +374,12 @@ Item { ...@@ -359,6 +374,12 @@ Item {
vehicle.pauseVehicle() vehicle.pauseVehicle()
} }
break break
case actionVtolTransitionToFwdFlight:
_activeVehicle.vtolInFwdFlight = true
break
case actionVtolTransitionToMRFlight:
_activeVehicle.vtolInFwdFlight = false
break
default: default:
console.warn(qsTr("Internal error: unknown actionCode"), actionCode) console.warn(qsTr("Internal error: unknown actionCode"), actionCode)
break break
......
...@@ -108,6 +108,7 @@ Vehicle::Vehicle(LinkInterface* link, ...@@ -108,6 +108,7 @@ Vehicle::Vehicle(LinkInterface* link,
, _autoDisconnect(false) , _autoDisconnect(false)
, _flying(false) , _flying(false)
, _landing(false) , _landing(false)
, _vtolInFwdFlight(false)
, _onboardControlSensorsPresent(0) , _onboardControlSensorsPresent(0)
, _onboardControlSensorsEnabled(0) , _onboardControlSensorsEnabled(0)
, _onboardControlSensorsHealth(0) , _onboardControlSensorsHealth(0)
...@@ -292,6 +293,7 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType, ...@@ -292,6 +293,7 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType,
, _autoDisconnect(false) , _autoDisconnect(false)
, _flying(false) , _flying(false)
, _landing(false) , _landing(false)
, _vtolInFwdFlight(false)
, _onboardControlSensorsPresent(0) , _onboardControlSensorsPresent(0)
, _onboardControlSensorsEnabled(0) , _onboardControlSensorsEnabled(0)
, _onboardControlSensorsHealth(0) , _onboardControlSensorsHealth(0)
...@@ -990,6 +992,10 @@ void Vehicle::_handleExtendedSysState(mavlink_message_t& message) ...@@ -990,6 +992,10 @@ void Vehicle::_handleExtendedSysState(mavlink_message_t& message)
default: default:
break; break;
} }
if (vtol()) {
setVtolInFwdFlight(extendedState.vtol_state == MAV_VTOL_STATE_FW);
}
} }
void Vehicle::_handleVibration(mavlink_message_t& message) void Vehicle::_handleVibration(mavlink_message_t& message)
...@@ -2679,6 +2685,14 @@ void Vehicle::triggerCamera(void) ...@@ -2679,6 +2685,14 @@ void Vehicle::triggerCamera(void)
1.0); // test shot flag 1.0); // test shot flag
} }
void Vehicle::setVtolInFwdFlight(bool vtolInFwdFlight)
{
if (_vtolInFwdFlight != vtolInFwdFlight) {
_vtolInFwdFlight = vtolInFwdFlight;
emit vtolInFwdFlightChanged(vtolInFwdFlight);
}
}
const char* VehicleGPSFactGroup::_latFactName = "lat"; const char* VehicleGPSFactGroup::_latFactName = "lat";
const char* VehicleGPSFactGroup::_lonFactName = "lon"; const char* VehicleGPSFactGroup::_lonFactName = "lon";
const char* VehicleGPSFactGroup::_hdopFactName = "hdop"; const char* VehicleGPSFactGroup::_hdopFactName = "hdop";
......
...@@ -351,6 +351,7 @@ public: ...@@ -351,6 +351,7 @@ public:
Q_PROPERTY(QVariantList staticCameraList READ staticCameraList CONSTANT) Q_PROPERTY(QVariantList staticCameraList READ staticCameraList CONSTANT)
Q_PROPERTY(QGCCameraManager* dynamicCameras READ dynamicCameras NOTIFY dynamicCamerasChanged) Q_PROPERTY(QGCCameraManager* dynamicCameras READ dynamicCameras NOTIFY dynamicCamerasChanged)
Q_PROPERTY(QString hobbsMeter READ hobbsMeter NOTIFY hobbsMeterChanged) Q_PROPERTY(QString hobbsMeter READ hobbsMeter NOTIFY hobbsMeterChanged)
Q_PROPERTY(bool vtolInFwdFlight READ vtolInFwdFlight WRITE setVtolInFwdFlight NOTIFY vtolInFwdFlightChanged)
// Vehicle state used for guided control // Vehicle state used for guided control
Q_PROPERTY(bool flying READ flying NOTIFY flyingChanged) ///< Vehicle is flying Q_PROPERTY(bool flying READ flying NOTIFY flyingChanged) ///< Vehicle is flying
...@@ -359,7 +360,7 @@ public: ...@@ -359,7 +360,7 @@ public:
Q_PROPERTY(bool guidedModeSupported READ guidedModeSupported CONSTANT) ///< Guided mode commands are supported by this vehicle Q_PROPERTY(bool guidedModeSupported READ guidedModeSupported CONSTANT) ///< Guided mode commands are supported by this vehicle
Q_PROPERTY(bool pauseVehicleSupported READ pauseVehicleSupported CONSTANT) ///< Pause vehicle command is supported Q_PROPERTY(bool pauseVehicleSupported READ pauseVehicleSupported CONSTANT) ///< Pause vehicle command is supported
Q_PROPERTY(bool orbitModeSupported READ orbitModeSupported CONSTANT) ///< Orbit mode is supported by this vehicle Q_PROPERTY(bool orbitModeSupported READ orbitModeSupported CONSTANT) ///< Orbit mode is supported by this vehicle
Q_PROPERTY(bool takeoffVehicleSupported READ takeoffVehicleSupported CONSTANT) ///< Guided takeoff supported Q_PROPERTY(bool takeoffVehicleSupported READ takeoffVehicleSupported CONSTANT) ///< Guided takeoff supported
Q_PROPERTY(ParameterManager* parameterManager READ parameterManager CONSTANT) Q_PROPERTY(ParameterManager* parameterManager READ parameterManager CONSTANT)
...@@ -610,6 +611,7 @@ public: ...@@ -610,6 +611,7 @@ public:
bool flying () const { return _flying; } bool flying () const { return _flying; }
bool landing () const { return _landing; } bool landing () const { return _landing; }
bool guidedMode () const; bool guidedMode () const;
bool vtolInFwdFlight () const { return _vtolInFwdFlight; }
uint8_t baseMode () const { return _base_mode; } uint8_t baseMode () const { return _base_mode; }
uint32_t customMode () const { return _custom_mode; } uint32_t customMode () const { return _custom_mode; }
bool isOfflineEditingVehicle () const { return _offlineEditingVehicle; } bool isOfflineEditingVehicle () const { return _offlineEditingVehicle; }
...@@ -741,6 +743,7 @@ public: ...@@ -741,6 +743,7 @@ public:
void _setFlying(bool flying); void _setFlying(bool flying);
void _setLanding(bool landing); void _setLanding(bool landing);
void setVtolInFwdFlight(bool vtolInFwdFlight);
void _setHomePosition(QGeoCoordinate& homeCoord); void _setHomePosition(QGeoCoordinate& homeCoord);
void _setMaxProtoVersion (unsigned version); void _setMaxProtoVersion (unsigned version);
...@@ -766,6 +769,7 @@ signals: ...@@ -766,6 +769,7 @@ signals:
void flyingChanged(bool flying); void flyingChanged(bool flying);
void landingChanged(bool landing); void landingChanged(bool landing);
void guidedModeChanged(bool guidedMode); void guidedModeChanged(bool guidedMode);
void vtolInFwdFlightChanged(bool vtolInFwdFlight);
void prearmErrorChanged(const QString& prearmError); void prearmErrorChanged(const QString& prearmError);
void soloFirmwareChanged(bool soloFirmware); void soloFirmwareChanged(bool soloFirmware);
void unhealthySensorsChanged(void); void unhealthySensorsChanged(void);
...@@ -969,6 +973,7 @@ private: ...@@ -969,6 +973,7 @@ private:
bool _autoDisconnect; ///< true: Automatically disconnect vehicle when last connection goes away or lost heartbeat bool _autoDisconnect; ///< true: Automatically disconnect vehicle when last connection goes away or lost heartbeat
bool _flying; bool _flying;
bool _landing; bool _landing;
bool _vtolInFwdFlight;
uint32_t _onboardControlSensorsPresent; uint32_t _onboardControlSensorsPresent;
uint32_t _onboardControlSensorsEnabled; uint32_t _onboardControlSensorsEnabled;
uint32_t _onboardControlSensorsHealth; uint32_t _onboardControlSensorsHealth;
......
...@@ -292,6 +292,8 @@ Item { ...@@ -292,6 +292,8 @@ Item {
flightView.guidedController.confirmAction(flightView.guidedController.actionDisarm) flightView.guidedController.confirmAction(flightView.guidedController.actionDisarm)
} }
} }
onVtolTransitionToFwdFlight: flightView.guidedController.confirmAction(flightView.guidedController.actionVtolTransitionToFwdFlight)
onVtolTransitionToMRFlight: flightView.guidedController.confirmAction(flightView.guidedController.actionVtolTransitionToMRFlight)
//-- Entire tool bar area disable on cammand //-- Entire tool bar area disable on cammand
MouseArea { MouseArea {
......
...@@ -34,6 +34,8 @@ Rectangle { ...@@ -34,6 +34,8 @@ Rectangle {
signal showAnalyzeView signal showAnalyzeView
signal armVehicle signal armVehicle
signal disarmVehicle signal disarmVehicle
signal vtolTransitionToFwdFlight
signal vtolTransitionToMRFlight
function checkSettingsButton() { function checkSettingsButton() {
settingsButton.checked = true settingsButton.checked = true
......
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
import QtQuick 2.3
import QtQuick.Controls 1.2
import QtQuick.Layouts 1.2
import QGroundControl 1.0
import QGroundControl.Controls 1.0
import QGroundControl.MultiVehicleManager 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.Palette 1.0
//-------------------------------------------------------------------------
//-- VTOL Mode Indicator
QGCLabel {
anchors.top: parent.top
anchors.bottom: parent.bottom
verticalAlignment: Text.AlignVCenter
text: _fwdFlight ? qsTr("VTOL: Fixed Wing") : qsTr("VTOL: Multi-Rotor")
font.pointSize: ScreenTools.mediumFontPointSize
color: qgcPal.buttonText
visible: _activeVehicle ? _activeVehicle.vtol && _activeVehicle.px4Firmware : false
width: visible ? implicitWidth : 0
property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
property bool _fwdFlight: _activeVehicle ? _activeVehicle.vtolInFwdFlight : false
QGCPalette { id: qgcPal }
QGCMouseArea {
fillItem: parent
onClicked: _activeVehicle.vtolInFwdFlight ? toolBar.vtolTransitionToMRFlight() : toolBar.vtolTransitionToFwdFlight()
}
}
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