Commit 1b94369c authored by Don Gagne's avatar Don Gagne

New vehicle health display using SYS_STATUS info

parent 750072dc
......@@ -128,6 +128,7 @@
<file alias="QGroundControl/FlightMap/QGCPitchIndicator.qml">src/FlightMap/Widgets/QGCPitchIndicator.qml</file>
<file alias="QGroundControl/FlightMap/QGCVideoBackground.qml">src/FlightMap/QGCVideoBackground.qml</file>
<file alias="QGroundControl/FlightMap/ValuesWidget.qml">src/FlightMap/Widgets/ValuesWidget.qml</file>
<file alias="QGroundControl/FlightMap/VehicleHealthWidget.qml">src/FlightMap/Widgets/VehicleHealthWidget.qml</file>
<file alias="QGroundControl/FlightMap/VibrationWidget.qml">src/FlightMap/Widgets/VibrationWidget.qml</file>
<file alias="QGroundControl/FlightMap/VehicleMapItem.qml">src/FlightMap/MapItems/VehicleMapItem.qml</file>
<file alias="QGroundControl/FlightMap/InstrumentSwipeView.qml">src/FlightMap/Widgets/InstrumentSwipeView.qml</file>
......
......@@ -15,24 +15,41 @@ Item {
property color backgroundColor
property var maxHeight ///< Maximum height that should be taken, smaller than this is ok
property real _margins: ScreenTools.defaultFontPixelWidth / 2
property real _margins: ScreenTools.defaultFontPixelWidth / 2
property real _pageWidth: _root.width
property int _currentPage: 0
property int _maxPage: 2
function showPicker() {
valuesPage.showPicker()
}
function showPage(pageIndex) {
_root.height = Qt.binding(function() { return _root.children[pageIndex].height + pageIndicatorRow.anchors.topMargin + pageIndicatorRow.height } )
_root.children[0].x = -(pageIndex * _pageWidth)
}
ValuesWidget {
id: valuesPage
width: _root.width
width: _pageWidth
qgcView: _root.qgcView
textColor: _root.textColor
maxHeight: _root.maxHeight
}
VehicleHealthWidget {
id: healthPage
anchors.left: valuesPage.right
width: _pageWidth
qgcView: _root.qgcView
textColor: _root.textColor
maxHeight: _root.maxHeight
}
VibrationWidget {
id: vibrationPage
anchors.left: valuesPage.right
width: _root.width
anchors.left: healthPage.right
width: _pageWidth
textColor: _root.textColor
backgroundColor: _root.backgroundColor
maxHeight: _root.maxHeight
......@@ -44,24 +61,17 @@ Item {
anchors.horizontalCenter: parent.horizontalCenter
spacing: _margins
Rectangle {
id: valuesPageIndicator
height: radius * 2
width: radius * 2
radius: 2.5
border.color: textColor
border.width: 1
color: textColor
}
Repeater {
model: _maxPage + 1
Rectangle {
id: vibrationPageIndicator
height: radius * 2
width: radius * 2
radius: 2.5
border.color: textColor
border.width: 1
color: "transparent"
Rectangle {
height: radius * 2
width: radius * 2
radius: 2.5
border.color: textColor
border.width: 1
color: _currentPage == index ? textColor : "transparent"
}
}
}
......@@ -69,40 +79,29 @@ Item {
anchors.fill: parent
property real xDragStart
property real xValuesPageSave
property real xFirstPageSave
onPressed: {
if (mouse.button == Qt.LeftButton) {
mouse.accepted = true
xDragStart = mouse.x
xValuesPageSave = valuesPage.x
xFirstPageSave = _root.children[0].x
}
}
onPositionChanged: {
valuesPage.x = xValuesPageSave + mouse.x - xDragStart
_root.children[0].x = xFirstPageSave + mouse.x - xDragStart
}
onReleased: {
if (mouse.x < xDragStart) {
if (xValuesPageSave == 0) {
valuesPage.x = -valuesPage.width
_root.height = Qt.binding(function() { return vibrationPage.height + pageIndicatorRow.anchors.topMargin + pageIndicatorRow.height } )
valuesPageIndicator.color = "transparent"
vibrationPageIndicator.color = textColor
} else {
valuesPage.x = xValuesPageSave
}
// Swipe left
_currentPage = Math.min(_currentPage + 1, _maxPage)
} else {
if (xValuesPageSave != 0) {
valuesPage.x = 0
_root.height = Qt.binding(function() { return valuesPage.height + pageIndicatorRow.anchors.topMargin + pageIndicatorRow.height } )
valuesPageIndicator.color = textColor
vibrationPageIndicator.color = "transparent"
} else {
valuesPage.x = xValuesPageSave
}
// Swipe right
_currentPage = Math.max(_currentPage - 1, 0)
}
showPage(_currentPage)
}
}
}
......@@ -128,7 +128,9 @@ Item {
InstrumentSwipeView {
id: _valuesWidget
width: parent.width
anchors.margins: 1
anchors.left: parent.left
anchors.right: parent.right
qgcView: instrumentPanel.qgcView
textColor: qgcPal.text
backgroundColor: _backgroundColor
......
/****************************************************************************
*
* (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.4
import QtQuick.Layouts 1.2
import QGroundControl 1.0
import QGroundControl.Controls 1.0
import QGroundControl.ScreenTools 1.0
QGCFlickable {
id: _root
height: Math.min(maxHeight, healthColumn.y + healthColumn.height)
contentHeight: healthColumn.y + healthColumn.height
flickableDirection: Flickable.VerticalFlick
clip: true
property var qgcView
property color textColor
property var maxHeight
property var unhealthySensors: QGroundControl.multiVehicleManager.activeVehicle ? QGroundControl.multiVehicleManager.activeVehicle.unhealthySensors : [ ]
// Any time the unhealthy sensors list changes, switch to the health page
onUnhealthySensorsChanged: {
if (unhealthySensors.length != 0) {
showPage(1)
}
}
Column {
id: healthColumn
width: parent.width
QGCLabel {
width: parent.width
horizontalAlignment: Text.AlignHCenter
color: textColor
text: qsTr("Vehicle Health")
}
QGCLabel {
width: parent.width
horizontalAlignment: Text.AlignHCenter
color: textColor
text: qsTr("All systems healthy")
visible: healthRepeater.count == 0
}
Repeater {
id: healthRepeater
model: unhealthySensors
Row {
Image {
source: "/qmlimages/Yield.svg"
height: ScreenTools.defaultFontPixelHeight
sourceSize.height: height
fillMode: Image.PreserveAspectFit
}
QGCLabel {
color: textColor
text: modelData
}
}
}
}
}
......@@ -16,6 +16,7 @@ QGCInstrumentWidgetAlternate 1.0 QGCInstrumentWidgetAlternate.qml
QGCPitchIndicator 1.0 QGCPitchIndicator.qml
QGCSlider 1.0 QGCSlider.qml
ValuesWidget 1.0 ValuesWidget.qml
VehicleHealthWidget 1.0 VehicleHealthWidget.qml
VibrationWidget 1.0 VibrationWidget.qml
# Map items
......
......@@ -96,6 +96,10 @@ Vehicle::Vehicle(LinkInterface* link,
, _rcRSSIstore(255)
, _autoDisconnect(false)
, _flying(false)
, _onboardControlSensorsPresent(0)
, _onboardControlSensorsEnabled(0)
, _onboardControlSensorsHealth(0)
, _onboardControlSensorsUnhealthy(0)
, _connectionLost(false)
, _connectionLostEnabled(true)
, _missionManager(NULL)
......@@ -296,6 +300,11 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType,
, _rcRSSI(255)
, _rcRSSIstore(255)
, _autoDisconnect(false)
, _flying(false)
, _onboardControlSensorsPresent(0)
, _onboardControlSensorsEnabled(0)
, _onboardControlSensorsHealth(0)
, _onboardControlSensorsUnhealthy(0)
, _connectionLost(false)
, _connectionLostEnabled(true)
, _missionManager(NULL)
......@@ -669,6 +678,16 @@ void Vehicle::_handleSysStatus(mavlink_message_t& message)
_say(QString("%1 low battery: %2 percent remaining").arg(_vehicleIdSpeech()).arg(sysStatus.battery_remaining));
}
}
_onboardControlSensorsPresent = sysStatus.onboard_control_sensors_present;
_onboardControlSensorsEnabled = sysStatus.onboard_control_sensors_enabled;
_onboardControlSensorsHealth = sysStatus.onboard_control_sensors_health;
uint32_t newSensorsUnhealthy = _onboardControlSensorsEnabled & ~_onboardControlSensorsHealth;
if (newSensorsUnhealthy != _onboardControlSensorsUnhealthy) {
_onboardControlSensorsUnhealthy = newSensorsUnhealthy;
emit unhealthySensorsChanged();
}
}
void Vehicle::_handleBatteryStatus(mavlink_message_t& message)
......@@ -1951,6 +1970,54 @@ QString Vehicle::brandImage(void) const
return _firmwarePlugin->brandImage(this);
}
QStringList Vehicle::unhealthySensors(void) const
{
QStringList sensorList;
struct sensorInfo_s {
uint32_t bit;
const char* sensorName;
};
static const sensorInfo_s rgSensorInfo[] = {
{ MAV_SYS_STATUS_SENSOR_3D_GYRO, "Gyro" },
{ MAV_SYS_STATUS_SENSOR_3D_ACCEL, "Accelerometer" },
{ MAV_SYS_STATUS_SENSOR_3D_MAG, "Magnetometer" },
{ MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE, "Absolute pressure" },
{ MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE, "Differential pressure" },
{ MAV_SYS_STATUS_SENSOR_GPS, "GPS" },
{ MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW, "Optical flow" },
{ MAV_SYS_STATUS_SENSOR_VISION_POSITION, "Computer vision position" },
{ MAV_SYS_STATUS_SENSOR_LASER_POSITION, "Laser based position" },
{ MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH, "External ground truth" },
{ MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL, "Angular rate control" },
{ MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION, "Attitude stabilization" },
{ MAV_SYS_STATUS_SENSOR_YAW_POSITION, "Yaw position" },
{ MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL, "Z/altitude control" },
{ MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL, "X/Y position control" },
{ MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS, "Motor outputs / control" },
{ MAV_SYS_STATUS_SENSOR_RC_RECEIVER, "RC receiver" },
{ MAV_SYS_STATUS_SENSOR_3D_GYRO2, "Gyro 2" },
{ MAV_SYS_STATUS_SENSOR_3D_ACCEL2, "Accelerometer 2" },
{ MAV_SYS_STATUS_SENSOR_3D_MAG2, "Magnetometer 2" },
{ MAV_SYS_STATUS_GEOFENCE, "GeoFence" },
{ MAV_SYS_STATUS_AHRS, "AHRS" },
{ MAV_SYS_STATUS_TERRAIN, "Terrain" },
{ MAV_SYS_STATUS_REVERSE_MOTOR, "Motors reversed" },
{ MAV_SYS_STATUS_LOGGING, "Logging" },
};
for (size_t i=0; i<sizeof(rgSensorInfo)/sizeof(sensorInfo_s); i++) {
const sensorInfo_s* pSensorInfo = &rgSensorInfo[i];
if ((_onboardControlSensorsEnabled & pSensorInfo->bit) && !(_onboardControlSensorsHealth & pSensorInfo->bit)) {
sensorList << pSensorInfo->sensorName;
}
}
return sensorList;
}
const char* VehicleGPSFactGroup::_hdopFactName = "hdop";
const char* VehicleGPSFactGroup::_vdopFactName = "vdop";
const char* VehicleGPSFactGroup::_courseOverGroundFactName = "courseOverGround";
......
......@@ -280,6 +280,7 @@ public:
Q_PROPERTY(bool xConfigMotors READ xConfigMotors CONSTANT)
Q_PROPERTY(bool isOfflineEditingVehicle READ isOfflineEditingVehicle CONSTANT)
Q_PROPERTY(QString brandImage READ brandImage CONSTANT)
Q_PROPERTY(QStringList unhealthySensors READ unhealthySensors NOTIFY unhealthySensorsChanged)
/// true: Vehicle is flying, false: Vehicle is on ground
Q_PROPERTY(bool flying READ flying WRITE setFlying NOTIFY flyingChanged)
......@@ -530,6 +531,7 @@ public:
uint32_t customMode () const { return _custom_mode; }
bool isOfflineEditingVehicle () const { return _offlineEditingVehicle; }
QString brandImage () const;
QStringList unhealthySensors () const;
Fact* roll (void) { return &_rollFact; }
Fact* heading (void) { return &_headingFact; }
......@@ -604,6 +606,7 @@ signals:
void prearmErrorChanged(const QString& prearmError);
void commandLongAck(uint8_t compID, uint16_t command, uint8_t result);
void soloFirmwareChanged(bool soloFirmware);
void unhealthySensorsChanged(void);
void messagesReceivedChanged ();
void messagesSentChanged ();
......@@ -751,6 +754,10 @@ private:
double _rcRSSIstore;
bool _autoDisconnect; ///< true: Automatically disconnect vehicle when last connection goes away or lost heartbeat
bool _flying;
uint32_t _onboardControlSensorsPresent;
uint32_t _onboardControlSensorsEnabled;
uint32_t _onboardControlSensorsHealth;
uint32_t _onboardControlSensorsUnhealthy;
QString _prearmError;
QTimer _prearmErrorTimer;
......
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