Commit c2f9b562 authored by Don Gagne's avatar Don Gagne

Vehicle.battery FactGroup

Removed incorrect Vehicle.altitudeWGS84
parent 58181a8a
...@@ -55,7 +55,7 @@ QGCView { ...@@ -55,7 +55,7 @@ QGCView {
readonly property real _defaultRoll: 0 readonly property real _defaultRoll: 0
readonly property real _defaultPitch: 0 readonly property real _defaultPitch: 0
readonly property real _defaultHeading: 0 readonly property real _defaultHeading: 0
readonly property real _defaultAltitudeWGS84: 0 readonly property real _defaultAltitudeAMSL: 0
readonly property real _defaultGroundSpeed: 0 readonly property real _defaultGroundSpeed: 0
readonly property real _defaultAirSpeed: 0 readonly property real _defaultAirSpeed: 0
...@@ -75,7 +75,7 @@ QGCView { ...@@ -75,7 +75,7 @@ QGCView {
property Fact _emptyFact: Fact { } property Fact _emptyFact: Fact { }
property Fact _groundSpeedFact: _activeVehicle ? _activeVehicle.groundSpeed : _emptyFact property Fact _groundSpeedFact: _activeVehicle ? _activeVehicle.groundSpeed : _emptyFact
property Fact _airSpeedFact: _activeVehicle ? _activeVehicle.airSpeed : _emptyFact property Fact _airSpeedFact: _activeVehicle ? _activeVehicle.airSpeed : _emptyFact
property Fact _altitudeWGS84Fact: _activeVehicle ? _activeVehicle.altitudeWGS84 : _emptyFact property Fact _altitudeAMSLFact: _activeVehicle ? _activeVehicle.altitudeAMSL : _emptyFact
property bool activeVehicleJoystickEnabled: _activeVehicle ? _activeVehicle.joystickEnabled : false property bool activeVehicleJoystickEnabled: _activeVehicle ? _activeVehicle.joystickEnabled : false
......
...@@ -100,7 +100,7 @@ Item { ...@@ -100,7 +100,7 @@ Item {
heading: _heading heading: _heading
rollAngle: _roll rollAngle: _roll
pitchAngle: _pitch pitchAngle: _pitch
altitudeFact: _altitudeWGS84Fact altitudeFact: _altitudeAMSLFact
groundSpeedFact: _groundSpeedFact groundSpeedFact: _groundSpeedFact
airSpeedFact: _airSpeedFact airSpeedFact: _airSpeedFact
isSatellite: _mainIsMap ? _flightMap ? _flightMap.isSatelliteMap : true : true isSatellite: _mainIsMap ? _flightMap ? _flightMap.isSatelliteMap : true : true
...@@ -124,7 +124,7 @@ Item { ...@@ -124,7 +124,7 @@ Item {
spacing: ScreenTools.defaultFontPixelSize * 0.33 spacing: ScreenTools.defaultFontPixelSize * 0.33
anchors.verticalCenter: parent.verticalCenter anchors.verticalCenter: parent.verticalCenter
QGCLabel { QGCLabel {
text: _altitudeWGS84Fact.shortDescription + "(" + _altitudeWGS84Fact.units + ")" text: _altitudeAMSLFact.shortDescription + "(" + _altitudeAMSLFact.units + ")"
font.pixelSize: ScreenTools.defaultFontPixelSize * 0.75 font.pixelSize: ScreenTools.defaultFontPixelSize * 0.75
width: parent.width width: parent.width
height: ScreenTools.defaultFontPixelSize * 0.75 height: ScreenTools.defaultFontPixelSize * 0.75
...@@ -132,7 +132,7 @@ Item { ...@@ -132,7 +132,7 @@ Item {
horizontalAlignment: TextEdit.AlignHCenter horizontalAlignment: TextEdit.AlignHCenter
} }
QGCLabel { QGCLabel {
text: _altitudeWGS84Fact.valueString text: _altitudeAMSLFact.valueString
font.pixelSize: ScreenTools.defaultFontPixelSize * 1.5 font.pixelSize: ScreenTools.defaultFontPixelSize * 1.5
font.weight: Font.DemiBold font.weight: Font.DemiBold
width: parent.width width: parent.width
......
...@@ -36,9 +36,17 @@ ValuesWidgetController::ValuesWidgetController(void) ...@@ -36,9 +36,17 @@ ValuesWidgetController::ValuesWidgetController(void)
settings.beginGroup(_groupKey); settings.beginGroup(_groupKey);
largeDefaults << "Vehicle.altitudeWGS84" << "Vehicle.groundSpeed"; largeDefaults << "Vehicle.altitudeRelative" << "Vehicle.groundSpeed";
_largeValues = settings.value(_largeValuesKey, largeDefaults).toStringList(); _largeValues = settings.value(_largeValuesKey, largeDefaults).toStringList();
_smallValues = settings.value(_smallValuesKey, QStringList()).toStringList(); _smallValues = settings.value(_smallValuesKey, QStringList()).toStringList();
// Keep back compat for removed WGS84 value
if (_largeValues.contains ("Vehicle.altitudeWGS84")) {
setLargeValues(_largeValues.replaceInStrings("Vehicle.altitudeWGS84", "Vehicle.altitudeRelative"));
}
if (_smallValues.contains ("Vehicle.altitudeWGS84")) {
setSmallValues(_largeValues.replaceInStrings("Vehicle.altitudeWGS84", "Vehicle.altitudeRelative"));
}
} }
void ValuesWidgetController::setLargeValues(const QStringList& values) void ValuesWidgetController::setLargeValues(const QStringList& values)
......
...@@ -3,67 +3,45 @@ ...@@ -3,67 +3,45 @@
"properties": [ "properties": [
{ {
"name": "roll", "name": "voltage",
"shortDescription": "Roll", "shortDescription": "Voltage",
"type": "double", "type": "double",
"decimalPlaces": 1, "decimalPlaces": 2,
"units": "degrees" "units": "v"
}, },
{ {
"name": "pitch", "name": "percentRemaining",
"shortDescription": "Pitch", "shortDescription": "Percent",
"type": "double", "type": "int32",
"decimalPlaces": 1,
"units": "degrees"
},
{
"name": "heading",
"shortDescription": "Heading",
"type": "double",
"decimalPlaces": 0, "decimalPlaces": 0,
"units": "degrees" "units": "%"
},
{
"name": "groundSpeed",
"shortDescription": "Ground Speed",
"type": "double",
"decimalPlaces": 1,
"units": "m/s"
},
{
"name": "airSpeed",
"shortDescription": "Air Speed",
"type": "double",
"decimalPlaces": 1,
"units": "m/s"
}, },
{ {
"name": "climbRate", "name": "mahConsumed",
"shortDescription": "Climb Rate", "shortDescription": "Consumed",
"type": "double", "type": "int32",
"decimalPlaces": 1, "decimalPlaces": 0,
"units": "m/s" "units": "mAh"
}, },
{ {
"name": "altitudeRelative", "name": "current",
"shortDescription": "Altitude", "shortDescription": "Current",
"type": "double", "type": "int32",
"decimalPlaces": 1, "decimalPlaces": 0,
"units": "m" "units": "mA"
}, },
{ {
"name": "altitudeQGS84", "name": "temperature",
"shortDescription": "Altitude", "shortDescription": "Temperature",
"type": "double", "type": "int32",
"decimalPlaces": 1, "decimalPlaces": 2,
"units": "m" "units": "C"
}, },
{ {
"name": "altitudeAMSL", "name": "cellCount",
"shortDescription": "Altitude", "shortDescription": "Cell Count",
"type": "double", "type": "int32",
"decimalPlaces": 1, "decimalPlaces": 0
"units": "m"
} }
] ]
} }
...@@ -53,9 +53,10 @@ const char* Vehicle::_airSpeedFactName = "airSpeed"; ...@@ -53,9 +53,10 @@ const char* Vehicle::_airSpeedFactName = "airSpeed";
const char* Vehicle::_groundSpeedFactName = "groundSpeed"; const char* Vehicle::_groundSpeedFactName = "groundSpeed";
const char* Vehicle::_climbRateFactName = "climbRate"; const char* Vehicle::_climbRateFactName = "climbRate";
const char* Vehicle::_altitudeRelativeFactName = "altitudeRelative"; const char* Vehicle::_altitudeRelativeFactName = "altitudeRelative";
const char* Vehicle::_altitudeWGS84FactName = "altitudeWGS84";
const char* Vehicle::_altitudeAMSLFactName = "altitudeAMSL"; const char* Vehicle::_altitudeAMSLFactName = "altitudeAMSL";
const char* Vehicle::_gpsFactGroupName = "gps";
const char* Vehicle::_gpsFactGroupName = "gps";
const char* Vehicle::_batteryFactGroupName = "battery";
const char* VehicleGPSFactGroup::_hdopFactName = "hdop"; const char* VehicleGPSFactGroup::_hdopFactName = "hdop";
const char* VehicleGPSFactGroup::_vdopFactName = "vdop"; const char* VehicleGPSFactGroup::_vdopFactName = "vdop";
...@@ -63,6 +64,20 @@ const char* VehicleGPSFactGroup::_courseOverGroundFactName = "courseOverGroun ...@@ -63,6 +64,20 @@ const char* VehicleGPSFactGroup::_courseOverGroundFactName = "courseOverGroun
const char* VehicleGPSFactGroup::_countFactName = "count"; const char* VehicleGPSFactGroup::_countFactName = "count";
const char* VehicleGPSFactGroup::_lockFactName = "lock"; const char* VehicleGPSFactGroup::_lockFactName = "lock";
const char* VehicleBatteryFactGroup::_voltageFactName = "voltage";
const char* VehicleBatteryFactGroup::_percentRemainingFactName = "percentRemaining";
const char* VehicleBatteryFactGroup::_mahConsumedFactName = "mahConsumed";
const char* VehicleBatteryFactGroup::_currentFactName = "current";
const char* VehicleBatteryFactGroup::_temperatureFactName = "temperature";
const char* VehicleBatteryFactGroup::_cellCountFactName = "cellCount";
const double VehicleBatteryFactGroup::_voltageUnavailable = -1.0;
const int VehicleBatteryFactGroup::_percentRemainingUnavailable = -1;
const int VehicleBatteryFactGroup::_mahConsumedUnavailable = -1;
const int VehicleBatteryFactGroup::_currentUnavailable = -1;
const double VehicleBatteryFactGroup::_temperatureUnavailable = -1.0;
const int VehicleBatteryFactGroup::_cellCountUnavailable = -1.0;
Vehicle::Vehicle(LinkInterface* link, Vehicle::Vehicle(LinkInterface* link,
int vehicleId, int vehicleId,
MAV_AUTOPILOT firmwareType, MAV_AUTOPILOT firmwareType,
...@@ -95,9 +110,6 @@ Vehicle::Vehicle(LinkInterface* link, ...@@ -95,9 +110,6 @@ Vehicle::Vehicle(LinkInterface* link,
, _navigationCrosstrackError(0.0f) , _navigationCrosstrackError(0.0f)
, _navigationTargetBearing(0.0f) , _navigationTargetBearing(0.0f)
, _refreshTimer(new QTimer(this)) , _refreshTimer(new QTimer(this))
, _batteryVoltage(-1.0f)
, _batteryPercent(0.0)
, _batteryConsumed(-1.0)
, _updateCount(0) , _updateCount(0)
, _rcRSSI(0) , _rcRSSI(0)
, _rcRSSIstore(100.0) , _rcRSSIstore(100.0)
...@@ -129,9 +141,9 @@ Vehicle::Vehicle(LinkInterface* link, ...@@ -129,9 +141,9 @@ Vehicle::Vehicle(LinkInterface* link,
, _airSpeedFact (0, _airSpeedFactName, FactMetaData::valueTypeDouble) , _airSpeedFact (0, _airSpeedFactName, FactMetaData::valueTypeDouble)
, _climbRateFact (0, _climbRateFactName, FactMetaData::valueTypeDouble) , _climbRateFact (0, _climbRateFactName, FactMetaData::valueTypeDouble)
, _altitudeRelativeFact (0, _altitudeRelativeFactName, FactMetaData::valueTypeDouble) , _altitudeRelativeFact (0, _altitudeRelativeFactName, FactMetaData::valueTypeDouble)
, _altitudeWGS84Fact (0, _altitudeWGS84FactName, FactMetaData::valueTypeDouble)
, _altitudeAMSLFact (0, _altitudeAMSLFactName, FactMetaData::valueTypeDouble) , _altitudeAMSLFact (0, _altitudeAMSLFactName, FactMetaData::valueTypeDouble)
, _gpsFactGroup(this) , _gpsFactGroup(this)
, _batteryFactGroup(this)
{ {
_addLink(link); _addLink(link);
...@@ -182,8 +194,6 @@ Vehicle::Vehicle(LinkInterface* link, ...@@ -182,8 +194,6 @@ Vehicle::Vehicle(LinkInterface* link,
connect(_mav, &UASInterface::altitudeChanged, this, &Vehicle::_updateAltitude); connect(_mav, &UASInterface::altitudeChanged, this, &Vehicle::_updateAltitude);
connect(_mav, &UASInterface::navigationControllerErrorsChanged,this, &Vehicle::_updateNavigationControllerErrors); connect(_mav, &UASInterface::navigationControllerErrorsChanged,this, &Vehicle::_updateNavigationControllerErrors);
connect(_mav, &UASInterface::NavigationControllerDataChanged, this, &Vehicle::_updateNavigationControllerData); connect(_mav, &UASInterface::NavigationControllerDataChanged, this, &Vehicle::_updateNavigationControllerData);
connect(_mav, &UASInterface::batteryChanged, this, &Vehicle::_updateBatteryRemaining);
connect(_mav, &UASInterface::batteryConsumedChanged, this, &Vehicle::_updateBatteryConsumedChanged);
_loadSettings(); _loadSettings();
...@@ -211,11 +221,12 @@ Vehicle::Vehicle(LinkInterface* link, ...@@ -211,11 +221,12 @@ Vehicle::Vehicle(LinkInterface* link,
_addFact(&_airSpeedFact, _airSpeedFactName); _addFact(&_airSpeedFact, _airSpeedFactName);
_addFact(&_climbRateFact, _climbRateFactName); _addFact(&_climbRateFact, _climbRateFactName);
_addFact(&_altitudeRelativeFact, _altitudeRelativeFactName); _addFact(&_altitudeRelativeFact, _altitudeRelativeFactName);
_addFact(&_altitudeWGS84Fact, _altitudeWGS84FactName);
_addFact(&_altitudeAMSLFact, _altitudeAMSLFactName); _addFact(&_altitudeAMSLFact, _altitudeAMSLFactName);
_addFactGroup(&_gpsFactGroup, _gpsFactGroupName); _addFactGroup(&_gpsFactGroup, _gpsFactGroupName);
_addFactGroup(&_batteryFactGroup, _batteryFactGroupName);
_gpsFactGroup.setVehicle(this); _gpsFactGroup.setVehicle(this);
_batteryFactGroup.setVehicle(this);
} }
Vehicle::~Vehicle() Vehicle::~Vehicle()
...@@ -295,6 +306,12 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes ...@@ -295,6 +306,12 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes
case MAVLINK_MSG_ID_RC_CHANNELS_RAW: case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
_handleRCChannelsRaw(message); _handleRCChannelsRaw(message);
break; break;
case MAVLINK_MSG_ID_BATTERY_STATUS:
_handleBatteryStatus(message);
break;
case MAVLINK_MSG_ID_SYS_STATUS:
_handleSysStatus(message);
break;
case MAVLINK_MSG_ID_RAW_IMU: case MAVLINK_MSG_ID_RAW_IMU:
emit mavlinkRawImu(message); emit mavlinkRawImu(message);
break; break;
...@@ -314,6 +331,53 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes ...@@ -314,6 +331,53 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes
_uas->receiveMessage(message); _uas->receiveMessage(message);
} }
void Vehicle::_handleSysStatus(mavlink_message_t& message)
{
mavlink_sys_status_t sysStatus;
mavlink_msg_sys_status_decode(&message, &sysStatus);
if (sysStatus.current_battery == -1) {
_batteryFactGroup.current()->setRawValue(VehicleBatteryFactGroup::_currentUnavailable);
} else {
_batteryFactGroup.current()->setRawValue((double)sysStatus.current_battery * 10);
}
if (sysStatus.voltage_battery == UINT16_MAX) {
_batteryFactGroup.voltage()->setRawValue(VehicleBatteryFactGroup::_voltageUnavailable);
} else {
_batteryFactGroup.voltage()->setRawValue((double)sysStatus.voltage_battery / 1000.0);
}
_batteryFactGroup.percentRemaining()->setRawValue(sysStatus.battery_remaining);
}
void Vehicle::_handleBatteryStatus(mavlink_message_t& message)
{
mavlink_battery_status_t bat_status;
mavlink_msg_battery_status_decode(&message, &bat_status);
if (bat_status.temperature == INT16_MAX) {
_batteryFactGroup.temperature()->setRawValue(VehicleBatteryFactGroup::_temperatureUnavailable);
} else {
_batteryFactGroup.temperature()->setRawValue((double)bat_status.temperature / 100.0);
}
if (bat_status.current_consumed == -1) {
_batteryFactGroup.mahConsumed()->setRawValue(VehicleBatteryFactGroup::_mahConsumedUnavailable);
} else {
_batteryFactGroup.mahConsumed()->setRawValue(bat_status.current_consumed);
}
int cellCount = 0;
for (int i=0; i<10; i++) {
if (bat_status.voltages[i] != UINT16_MAX) {
cellCount++;
}
}
if (cellCount == 0) {
cellCount = -1;
}
_batteryFactGroup.cellCount()->setRawValue(cellCount);
}
void Vehicle::_handleHomePosition(mavlink_message_t& message) void Vehicle::_handleHomePosition(mavlink_message_t& message)
{ {
bool emitHomePositionChanged = false; bool emitHomePositionChanged = false;
...@@ -604,9 +668,9 @@ void Vehicle::_updateSpeed(UASInterface*, double groundSpeed, double airSpeed, q ...@@ -604,9 +668,9 @@ void Vehicle::_updateSpeed(UASInterface*, double groundSpeed, double airSpeed, q
_airSpeedFact.setRawValue(airSpeed); _airSpeedFact.setRawValue(airSpeed);
} }
void Vehicle::_updateAltitude(UASInterface*, double altitudeAMSL, double altitudeWGS84, double altitudeRelative, double climbRate, quint64) { void Vehicle::_updateAltitude(UASInterface*, double altitudeAMSL, double altitudeRelative, double climbRate, quint64)
{
_altitudeAMSLFact.setRawValue(altitudeAMSL); _altitudeAMSLFact.setRawValue(altitudeAMSL);
_altitudeWGS84Fact.setRawValue(altitudeWGS84);
_altitudeRelativeFact.setRawValue(altitudeRelative); _altitudeRelativeFact.setRawValue(altitudeRelative);
_climbRateFact.setRawValue(climbRate); _climbRateFact.setRawValue(climbRate);
} }
...@@ -667,34 +731,6 @@ void Vehicle::_handletextMessageReceived(UASMessage* message) ...@@ -667,34 +731,6 @@ void Vehicle::_handletextMessageReceived(UASMessage* message)
} }
} }
void Vehicle::_updateBatteryRemaining(UASInterface*, double voltage, double, double percent, int)
{
if(percent < 0.0) {
percent = 0.0;
}
if(voltage < 0.0) {
voltage = 0.0;
}
if (_batteryVoltage != voltage) {
_batteryVoltage = voltage;
emit batteryVoltageChanged();
}
if (_batteryPercent != percent) {
_batteryPercent = percent;
emit batteryPercentChanged();
}
}
void Vehicle::_updateBatteryConsumedChanged(UASInterface*, double current_consumed)
{
if(_batteryConsumed != current_consumed) {
_batteryConsumed = current_consumed;
emit batteryConsumedChanged();
}
}
void Vehicle::_updateState(UASInterface*, QString name, QString) void Vehicle::_updateState(UASInterface*, QString name, QString)
{ {
if (_currentState != name) { if (_currentState != name) {
...@@ -1195,8 +1231,6 @@ VehicleGPSFactGroup::VehicleGPSFactGroup(QObject* parent) ...@@ -1195,8 +1231,6 @@ VehicleGPSFactGroup::VehicleGPSFactGroup(QObject* parent)
, _countFact (0, _countFactName, FactMetaData::valueTypeInt32) , _countFact (0, _countFactName, FactMetaData::valueTypeInt32)
, _lockFact (0, _lockFactName, FactMetaData::valueTypeInt32) , _lockFact (0, _lockFactName, FactMetaData::valueTypeInt32)
{ {
// Build FactGroup object model
_addFact(&_hdopFact, _hdopFactName); _addFact(&_hdopFact, _hdopFactName);
_addFact(&_vdopFact, _vdopFactName); _addFact(&_vdopFact, _vdopFactName);
_addFact(&_courseOverGroundFact, _courseOverGroundFactName); _addFact(&_courseOverGroundFact, _courseOverGroundFactName);
...@@ -1208,14 +1242,6 @@ void VehicleGPSFactGroup::setVehicle(Vehicle* vehicle) ...@@ -1208,14 +1242,6 @@ void VehicleGPSFactGroup::setVehicle(Vehicle* vehicle)
{ {
_vehicle = vehicle; _vehicle = vehicle;
#if 0
// Reset satellite data (no GPS)
_satelliteCount = -1;
_satRawHDOP = 1e10f;
_satRawVDOP = 1e10f;
_satRawCOG = 0.0;
#endif
connect(_vehicle->uas(), &UASInterface::localizationChanged, this, &VehicleGPSFactGroup::_setSatLoc); connect(_vehicle->uas(), &UASInterface::localizationChanged, this, &VehicleGPSFactGroup::_setSatLoc);
UAS* pUas = dynamic_cast<UAS*>(_vehicle->uas()); UAS* pUas = dynamic_cast<UAS*>(_vehicle->uas());
...@@ -1259,3 +1285,33 @@ void VehicleGPSFactGroup::_setSatLoc(UASInterface*, int fix) ...@@ -1259,3 +1285,33 @@ void VehicleGPSFactGroup::_setSatLoc(UASInterface*, int fix)
} }
} }
VehicleBatteryFactGroup::VehicleBatteryFactGroup(QObject* parent)
: FactGroup(1000, ":/json/Vehicle/BatteryFact.json", parent)
, _vehicle(NULL)
, _voltageFact (0, _voltageFactName, FactMetaData::valueTypeDouble)
, _percentRemainingFact (0, _percentRemainingFactName, FactMetaData::valueTypeInt32)
, _mahConsumedFact (0, _mahConsumedFactName, FactMetaData::valueTypeInt32)
, _currentFact (0, _currentFactName, FactMetaData::valueTypeInt32)
, _temperatureFact (0, _temperatureFactName, FactMetaData::valueTypeDouble)
, _cellCountFact (0, _cellCountFactName, FactMetaData::valueTypeInt32)
{
_addFact(&_voltageFact, _voltageFactName);
_addFact(&_percentRemainingFact, _percentRemainingFactName);
_addFact(&_mahConsumedFact, _mahConsumedFactName);
_addFact(&_currentFact, _currentFactName);
_addFact(&_temperatureFact, _temperatureFactName);
_addFact(&_cellCountFact, _cellCountFactName);
// Start out as not available
_voltageFact.setRawValue (_voltageUnavailable);
_percentRemainingFact.setRawValue (_percentRemainingUnavailable);
_mahConsumedFact.setRawValue (_mahConsumedUnavailable);
_currentFact.setRawValue (_currentUnavailable);
_temperatureFact.setRawValue (_temperatureUnavailable);
_cellCountFact.setRawValue (_cellCountUnavailable);
}
void VehicleBatteryFactGroup::setVehicle(Vehicle* vehicle)
{
_vehicle = vehicle;
}
...@@ -74,6 +74,12 @@ public: ...@@ -74,6 +74,12 @@ public:
void setVehicle(Vehicle* vehicle); void setVehicle(Vehicle* vehicle);
static const char* _hdopFactName;
static const char* _vdopFactName;
static const char* _courseOverGroundFactName;
static const char* _countFactName;
static const char* _lockFactName;
private slots: private slots:
void _setSatelliteCount(double val, QString); void _setSatelliteCount(double val, QString);
void _setSatRawHDOP(double val); void _setSatRawHDOP(double val);
...@@ -88,12 +94,53 @@ private: ...@@ -88,12 +94,53 @@ private:
Fact _courseOverGroundFact; Fact _courseOverGroundFact;
Fact _countFact; Fact _countFact;
Fact _lockFact; Fact _lockFact;
};
static const char* _hdopFactName; class VehicleBatteryFactGroup : public FactGroup
static const char* _vdopFactName; {
static const char* _courseOverGroundFactName; Q_OBJECT
static const char* _countFactName;
static const char* _lockFactName; public:
VehicleBatteryFactGroup(QObject* parent = NULL);
Q_PROPERTY(Fact* voltage READ voltage CONSTANT)
Q_PROPERTY(Fact* percentRemaining READ percentRemaining CONSTANT)
Q_PROPERTY(Fact* mahConsumed READ mahConsumed CONSTANT)
Q_PROPERTY(Fact* current READ current CONSTANT)
Q_PROPERTY(Fact* temperature READ temperature CONSTANT)
Q_PROPERTY(Fact* cellCount READ cellCount CONSTANT)
Fact* voltage(void) { return &_voltageFact; }
Fact* percentRemaining(void) { return &_percentRemainingFact; }
Fact* mahConsumed(void) { return &_mahConsumedFact; }
Fact* current(void) { return &_currentFact; }
Fact* temperature(void) { return &_temperatureFact; }
Fact* cellCount(void) { return &_cellCountFact; }
void setVehicle(Vehicle* vehicle);
static const char* _voltageFactName;
static const char* _percentRemainingFactName;
static const char* _mahConsumedFactName;
static const char* _currentFactName;
static const char* _temperatureFactName;
static const char* _cellCountFactName;
static const double _voltageUnavailable;
static const int _percentRemainingUnavailable;
static const int _mahConsumedUnavailable;
static const int _currentUnavailable;
static const double _temperatureUnavailable;
static const int _cellCountUnavailable;
private:
Vehicle* _vehicle;
Fact _voltageFact;
Fact _percentRemainingFact;
Fact _mahConsumedFact;
Fact _currentFact;
Fact _temperatureFact;
Fact _cellCountFact;
}; };
class Vehicle : public FactGroup class Vehicle : public FactGroup
...@@ -126,9 +173,6 @@ public: ...@@ -126,9 +173,6 @@ public:
Q_PROPERTY(QmlObjectListModel* trajectoryPoints READ trajectoryPoints CONSTANT) Q_PROPERTY(QmlObjectListModel* trajectoryPoints READ trajectoryPoints CONSTANT)
Q_PROPERTY(float latitude READ latitude NOTIFY coordinateChanged) Q_PROPERTY(float latitude READ latitude NOTIFY coordinateChanged)
Q_PROPERTY(float longitude READ longitude NOTIFY coordinateChanged) Q_PROPERTY(float longitude READ longitude NOTIFY coordinateChanged)
Q_PROPERTY(double batteryVoltage READ batteryVoltage NOTIFY batteryVoltageChanged)
Q_PROPERTY(double batteryPercent READ batteryPercent NOTIFY batteryPercentChanged)
Q_PROPERTY(double batteryConsumed READ batteryConsumed NOTIFY batteryConsumedChanged)
Q_PROPERTY(QString currentState READ currentState NOTIFY currentStateChanged) Q_PROPERTY(QString currentState READ currentState NOTIFY currentStateChanged)
Q_PROPERTY(QmlObjectListModel* missionItems READ missionItemsModel CONSTANT) Q_PROPERTY(QmlObjectListModel* missionItems READ missionItemsModel CONSTANT)
Q_PROPERTY(bool messageTypeNone READ messageTypeNone NOTIFY messageTypeChanged) Q_PROPERTY(bool messageTypeNone READ messageTypeNone NOTIFY messageTypeChanged)
...@@ -167,10 +211,10 @@ public: ...@@ -167,10 +211,10 @@ public:
Q_PROPERTY(Fact* airSpeed READ airSpeed CONSTANT) Q_PROPERTY(Fact* airSpeed READ airSpeed CONSTANT)
Q_PROPERTY(Fact* climbRate READ climbRate CONSTANT) Q_PROPERTY(Fact* climbRate READ climbRate CONSTANT)
Q_PROPERTY(Fact* altitudeRelative READ altitudeRelative CONSTANT) Q_PROPERTY(Fact* altitudeRelative READ altitudeRelative CONSTANT)
Q_PROPERTY(Fact* altitudeWGS84 READ altitudeWGS84 CONSTANT)
Q_PROPERTY(Fact* altitudeAMSL READ altitudeAMSL CONSTANT) Q_PROPERTY(Fact* altitudeAMSL READ altitudeAMSL CONSTANT)
Q_PROPERTY(FactGroup* gps READ gpsFactGroup CONSTANT) Q_PROPERTY(FactGroup* gps READ gpsFactGroup CONSTANT)
Q_PROPERTY(FactGroup* battery READ batteryFactGroup CONSTANT)
/// Resets link status counters /// Resets link status counters
Q_INVOKABLE void resetCounters (); Q_INVOKABLE void resetCounters ();
...@@ -298,9 +342,6 @@ public: ...@@ -298,9 +342,6 @@ public:
float latitude () { return _coordinate.latitude(); } float latitude () { return _coordinate.latitude(); }
float longitude () { return _coordinate.longitude(); } float longitude () { return _coordinate.longitude(); }
bool mavPresent () { return _mav != NULL; } bool mavPresent () { return _mav != NULL; }
double batteryVoltage () { return _batteryVoltage; }
double batteryPercent () { return _batteryPercent; }
double batteryConsumed () { return _batteryConsumed; }
QString currentState () { return _currentState; } QString currentState () { return _currentState; }
int rcRSSI () { return _rcRSSI; } int rcRSSI () { return _rcRSSI; }
bool px4Firmware () { return _firmwareType == MAV_AUTOPILOT_PX4; } bool px4Firmware () { return _firmwareType == MAV_AUTOPILOT_PX4; }
...@@ -319,10 +360,10 @@ public: ...@@ -319,10 +360,10 @@ public:
Fact* groundSpeed (void) { return &_groundSpeedFact; } Fact* groundSpeed (void) { return &_groundSpeedFact; }
Fact* climbRate (void) { return &_climbRateFact; } Fact* climbRate (void) { return &_climbRateFact; }
Fact* altitudeRelative (void) { return &_altitudeRelativeFact; } Fact* altitudeRelative (void) { return &_altitudeRelativeFact; }
Fact* altitudeWGS84 (void) { return &_altitudeWGS84Fact; }
Fact* altitudeAMSL (void) { return &_altitudeAMSLFact; } Fact* altitudeAMSL (void) { return &_altitudeAMSLFact; }
FactGroup* gpsFactGroup(void) { return &_gpsFactGroup; } FactGroup* gpsFactGroup (void) { return &_gpsFactGroup; }
FactGroup* batteryFactGroup (void) { return &_batteryFactGroup; }
void setConnectionLostEnabled(bool connectionLostEnabled); void setConnectionLostEnabled(bool connectionLostEnabled);
...@@ -369,9 +410,6 @@ signals: ...@@ -369,9 +410,6 @@ signals:
void formatedMessageChanged (); void formatedMessageChanged ();
void latestErrorChanged (); void latestErrorChanged ();
void longitudeChanged (); void longitudeChanged ();
void batteryVoltageChanged ();
void batteryPercentChanged ();
void batteryConsumedChanged ();
void currentConfigChanged (); void currentConfigChanged ();
void currentStateChanged (); void currentStateChanged ();
void flowImageIndexChanged (); void flowImageIndexChanged ();
...@@ -407,12 +445,10 @@ private slots: ...@@ -407,12 +445,10 @@ private slots:
/** @brief Attitude from one specific component / redundant autopilot */ /** @brief Attitude from one specific component / redundant autopilot */
void _updateAttitude (UASInterface* uas, int component, double roll, double pitch, double yaw, quint64 timestamp); void _updateAttitude (UASInterface* uas, int component, double roll, double pitch, double yaw, quint64 timestamp);
void _updateSpeed (UASInterface* uas, double _groundSpeed, double _airSpeed, quint64 timestamp); void _updateSpeed (UASInterface* uas, double _groundSpeed, double _airSpeed, quint64 timestamp);
void _updateAltitude (UASInterface* uas, double _altitudeAMSL, double _altitudeWGS84, double _altitudeRelative, double _climbRate, quint64 timestamp); void _updateAltitude (UASInterface* uas, double _altitudeAMSL, double _altitudeRelative, double _climbRate, quint64 timestamp);
void _updateNavigationControllerErrors (UASInterface* uas, double altitudeError, double speedError, double xtrackError); void _updateNavigationControllerErrors (UASInterface* uas, double altitudeError, double speedError, double xtrackError);
void _updateNavigationControllerData (UASInterface *uas, float navRoll, float navPitch, float navBearing, float targetBearing, float targetDistance); void _updateNavigationControllerData (UASInterface *uas, float navRoll, float navPitch, float navBearing, float targetBearing, float targetDistance);
void _checkUpdate (); void _checkUpdate ();
void _updateBatteryRemaining (UASInterface*, double voltage, double, double percent, int);
void _updateBatteryConsumedChanged (UASInterface*, double current_consumed);
void _updateState (UASInterface* system, QString name, QString description); void _updateState (UASInterface* system, QString name, QString description);
/** @brief A new camera image has arrived */ /** @brief A new camera image has arrived */
void _imageReady (UASInterface* uas); void _imageReady (UASInterface* uas);
...@@ -428,6 +464,8 @@ private: ...@@ -428,6 +464,8 @@ private:
void _handleHeartbeat(mavlink_message_t& message); void _handleHeartbeat(mavlink_message_t& message);
void _handleRCChannels(mavlink_message_t& message); void _handleRCChannels(mavlink_message_t& message);
void _handleRCChannelsRaw(mavlink_message_t& message); void _handleRCChannelsRaw(mavlink_message_t& message);
void _handleBatteryStatus(mavlink_message_t& message);
void _handleSysStatus(mavlink_message_t& message);
void _missionManagerError(int errorCode, const QString& errorMsg); void _missionManagerError(int errorCode, const QString& errorMsg);
void _mapTrajectoryStart(void); void _mapTrajectoryStart(void);
void _mapTrajectoryStop(void); void _mapTrajectoryStop(void);
...@@ -470,9 +508,6 @@ private: ...@@ -470,9 +508,6 @@ private:
float _navigationCrosstrackError; float _navigationCrosstrackError;
float _navigationTargetBearing; float _navigationTargetBearing;
QTimer* _refreshTimer; QTimer* _refreshTimer;
double _batteryVoltage;
double _batteryPercent;
double _batteryConsumed;
QString _currentState; QString _currentState;
int _updateCount; int _updateCount;
QString _formatedMessage; QString _formatedMessage;
...@@ -539,10 +574,10 @@ private: ...@@ -539,10 +574,10 @@ private:
Fact _airSpeedFact; Fact _airSpeedFact;
Fact _climbRateFact; Fact _climbRateFact;
Fact _altitudeRelativeFact; Fact _altitudeRelativeFact;
Fact _altitudeWGS84Fact;
Fact _altitudeAMSLFact; Fact _altitudeAMSLFact;
VehicleGPSFactGroup _gpsFactGroup; VehicleGPSFactGroup _gpsFactGroup;
VehicleBatteryFactGroup _batteryFactGroup;
static const char* _rollFactName; static const char* _rollFactName;
static const char* _pitchFactName; static const char* _pitchFactName;
...@@ -551,9 +586,9 @@ private: ...@@ -551,9 +586,9 @@ private:
static const char* _airSpeedFactName; static const char* _airSpeedFactName;
static const char* _climbRateFactName; static const char* _climbRateFactName;
static const char* _altitudeRelativeFactName; static const char* _altitudeRelativeFactName;
static const char* _altitudeWGS84FactName;
static const char* _altitudeAMSLFactName; static const char* _altitudeAMSLFactName;
static const char* _gpsFactGroupName; static const char* _gpsFactGroupName;
static const char* _batteryFactGroupName;
static const int _vehicleUIUpdateRateMSecs = 100; static const int _vehicleUIUpdateRateMSecs = 100;
......
...@@ -46,14 +46,7 @@ ...@@ -46,14 +46,7 @@
}, },
{ {
"name": "altitudeRelative", "name": "altitudeRelative",
"shortDescription": "Altitude", "shortDescription": "Altitude (home)",
"type": "double",
"decimalPlaces": 1,
"units": "m"
},
{
"name": "altitudeWGS84",
"shortDescription": "Altitude",
"type": "double", "type": "double",
"decimalPlaces": 1, "decimalPlaces": 1,
"units": "m" "units": "m"
......
...@@ -92,7 +92,6 @@ UAS::UAS(MAVLinkProtocol* protocol, Vehicle* vehicle, FirmwarePluginManager * fi ...@@ -92,7 +92,6 @@ UAS::UAS(MAVLinkProtocol* protocol, Vehicle* vehicle, FirmwarePluginManager * fi
longitude(0.0), longitude(0.0),
altitudeAMSL(0.0), altitudeAMSL(0.0),
altitudeAMSLFT(0.0), altitudeAMSLFT(0.0),
altitudeWGS84(0.0),
altitudeRelative(0.0), altitudeRelative(0.0),
satRawHDOP(1e10f), satRawHDOP(1e10f),
...@@ -355,18 +354,6 @@ void UAS::receiveMessage(mavlink_message_t message) ...@@ -355,18 +354,6 @@ void UAS::receiveMessage(mavlink_message_t message)
break; break;
case MAVLINK_MSG_ID_BATTERY_STATUS:
{
if (multiComponentSourceDetected && wrongComponent)
{
break;
}
mavlink_battery_status_t bat_status;
mavlink_msg_battery_status_decode(&message, &bat_status);
emit batteryConsumedChanged(this, (double)bat_status.current_consumed);
}
break;
case MAVLINK_MSG_ID_SYS_STATUS: case MAVLINK_MSG_ID_SYS_STATUS:
{ {
if (multiComponentSourceDetected && wrongComponent) if (multiComponentSourceDetected && wrongComponent)
...@@ -391,6 +378,8 @@ void UAS::receiveMessage(mavlink_message_t message) ...@@ -391,6 +378,8 @@ void UAS::receiveMessage(mavlink_message_t message)
emit loadChanged(this,state.load/10.0f); emit loadChanged(this,state.load/10.0f);
emit valueChanged(uasId, name.arg("load"), "%", state.load/10.0f, time); emit valueChanged(uasId, name.arg("load"), "%", state.load/10.0f, time);
currentVoltage = state.voltage_battery/1000.0f;
if (state.voltage_battery > 0.0f && state.voltage_battery != UINT16_MAX) { if (state.voltage_battery > 0.0f && state.voltage_battery != UINT16_MAX) {
// Battery charge/time remaining/voltage calculations // Battery charge/time remaining/voltage calculations
currentVoltage = state.voltage_battery/1000.0f; currentVoltage = state.voltage_battery/1000.0f;
...@@ -572,7 +561,7 @@ void UAS::receiveMessage(mavlink_message_t message) ...@@ -572,7 +561,7 @@ void UAS::receiveMessage(mavlink_message_t message)
if (!isnan(hud.airspeed)) if (!isnan(hud.airspeed))
setAirSpeed(hud.airspeed); setAirSpeed(hud.airspeed);
speedZ = -hud.climb; speedZ = -hud.climb;
emit altitudeChanged(this, altitudeAMSL, altitudeWGS84, altitudeRelative, -speedZ, time); emit altitudeChanged(this, altitudeAMSL, altitudeRelative, -speedZ, time);
emit speedChanged(this, groundSpeed, airSpeed, time); emit speedChanged(this, groundSpeed, airSpeed, time);
} }
break; break;
...@@ -614,7 +603,6 @@ void UAS::receiveMessage(mavlink_message_t message) ...@@ -614,7 +603,6 @@ void UAS::receiveMessage(mavlink_message_t message)
setLatitude(pos.lat/(double)1E7); setLatitude(pos.lat/(double)1E7);
setLongitude(pos.lon/(double)1E7); setLongitude(pos.lon/(double)1E7);
setAltitudeWGS84(pos.alt/1000.0);
setAltitudeRelative(pos.relative_alt/1000.0); setAltitudeRelative(pos.relative_alt/1000.0);
globalEstimatorActive = true; globalEstimatorActive = true;
...@@ -623,8 +611,8 @@ void UAS::receiveMessage(mavlink_message_t message) ...@@ -623,8 +611,8 @@ void UAS::receiveMessage(mavlink_message_t message)
speedY = pos.vy/100.0; speedY = pos.vy/100.0;
speedZ = pos.vz/100.0; speedZ = pos.vz/100.0;
emit globalPositionChanged(this, getLatitude(), getLongitude(), getAltitudeAMSL(), getAltitudeWGS84(), time); emit globalPositionChanged(this, getLatitude(), getLongitude(), getAltitudeAMSL(), time);
emit altitudeChanged(this, altitudeAMSL, altitudeWGS84, altitudeRelative, -speedZ, time); emit altitudeChanged(this, altitudeAMSL, altitudeRelative, -speedZ, time);
// We had some frame mess here, global and local axes were mixed. // We had some frame mess here, global and local axes were mixed.
emit velocityChanged_NED(this, speedX, speedY, speedZ, time); emit velocityChanged_NED(this, speedX, speedY, speedZ, time);
...@@ -661,9 +649,8 @@ void UAS::receiveMessage(mavlink_message_t message) ...@@ -661,9 +649,8 @@ void UAS::receiveMessage(mavlink_message_t message)
if (!globalEstimatorActive) { if (!globalEstimatorActive) {
setLatitude(latitude_gps); setLatitude(latitude_gps);
setLongitude(longitude_gps); setLongitude(longitude_gps);
setAltitudeWGS84(altitude_gps); emit globalPositionChanged(this, getLatitude(), getLongitude(), getAltitudeAMSL(), time);
emit globalPositionChanged(this, getLatitude(), getLongitude(), getAltitudeAMSL(), getAltitudeWGS84(), time); emit altitudeChanged(this, altitudeAMSL, altitudeRelative, -speedZ, time);
emit altitudeChanged(this, altitudeAMSL, altitudeWGS84, altitudeRelative, -speedZ, time);
float vel = pos.vel/100.0f; float vel = pos.vel/100.0f;
// Smaller than threshold and not NaN // Smaller than threshold and not NaN
......
...@@ -93,7 +93,6 @@ public: ...@@ -93,7 +93,6 @@ public:
Q_PROPERTY(double bearingToWaypoint READ getBearingToWaypoint WRITE setBearingToWaypoint NOTIFY bearingToWaypointChanged) Q_PROPERTY(double bearingToWaypoint READ getBearingToWaypoint WRITE setBearingToWaypoint NOTIFY bearingToWaypointChanged)
Q_PROPERTY(double altitudeAMSL READ getAltitudeAMSL WRITE setAltitudeAMSL NOTIFY altitudeAMSLChanged) Q_PROPERTY(double altitudeAMSL READ getAltitudeAMSL WRITE setAltitudeAMSL NOTIFY altitudeAMSLChanged)
Q_PROPERTY(double altitudeAMSLFT READ getAltitudeAMSLFT NOTIFY altitudeAMSLFTChanged) Q_PROPERTY(double altitudeAMSLFT READ getAltitudeAMSLFT NOTIFY altitudeAMSLFTChanged)
Q_PROPERTY(double altitudeWGS84 READ getAltitudeWGS84 WRITE setAltitudeWGS84 NOTIFY altitudeWGS84Changed)
Q_PROPERTY(double altitudeRelative READ getAltitudeRelative WRITE setAltitudeRelative NOTIFY altitudeRelativeChanged) Q_PROPERTY(double altitudeRelative READ getAltitudeRelative WRITE setAltitudeRelative NOTIFY altitudeRelativeChanged)
Q_PROPERTY(double satRawHDOP READ getSatRawHDOP NOTIFY satRawHDOPChanged) Q_PROPERTY(double satRawHDOP READ getSatRawHDOP NOTIFY satRawHDOPChanged)
Q_PROPERTY(double satRawVDOP READ getSatRawVDOP NOTIFY satRawVDOPChanged) Q_PROPERTY(double satRawVDOP READ getSatRawVDOP NOTIFY satRawVDOPChanged)
...@@ -203,19 +202,6 @@ public: ...@@ -203,19 +202,6 @@ public:
return altitudeAMSLFT; return altitudeAMSLFT;
} }
void setAltitudeWGS84(double val)
{
altitudeWGS84 = val;
emit altitudeWGS84Changed(val, "altitudeWGS84");
emit valueChanged(this->uasId,"altitudeWGS84","m",QVariant(val),getUnixTime());
}
double getAltitudeWGS84() const
{
return altitudeWGS84;
}
void setAltitudeRelative(double val) void setAltitudeRelative(double val)
{ {
altitudeRelative = val; altitudeRelative = val;
...@@ -431,7 +417,6 @@ protected: //COMMENTS FOR TEST UNIT ...@@ -431,7 +417,6 @@ protected: //COMMENTS FOR TEST UNIT
double longitude; ///< Global longitude as estimated by position estimator double longitude; ///< Global longitude as estimated by position estimator
double altitudeAMSL; ///< Global altitude as estimated by position estimator, AMSL double altitudeAMSL; ///< Global altitude as estimated by position estimator, AMSL
double altitudeAMSLFT; ///< Global altitude as estimated by position estimator, AMSL double altitudeAMSLFT; ///< Global altitude as estimated by position estimator, AMSL
double altitudeWGS84; ///< Global altitude as estimated by position estimator, WGS84
double altitudeRelative; ///< Altitude above home as estimated by position estimator double altitudeRelative; ///< Altitude above home as estimated by position estimator
double satRawHDOP; double satRawHDOP;
...@@ -614,7 +599,6 @@ signals: ...@@ -614,7 +599,6 @@ signals:
void latitudeChanged(double val,QString name); void latitudeChanged(double val,QString name);
void altitudeAMSLChanged(double val,QString name); void altitudeAMSLChanged(double val,QString name);
void altitudeAMSLFTChanged(double val,QString name); void altitudeAMSLFTChanged(double val,QString name);
void altitudeWGS84Changed(double val,QString name);
void altitudeRelativeChanged(double val,QString name); void altitudeRelativeChanged(double val,QString name);
void satRawHDOPChanged (double value); void satRawHDOPChanged (double value);
......
...@@ -253,7 +253,6 @@ signals: ...@@ -253,7 +253,6 @@ signals:
* @param seconds estimated remaining flight time in seconds * @param seconds estimated remaining flight time in seconds
*/ */
void batteryChanged(UASInterface* uas, double voltage, double current, double percent, int seconds); void batteryChanged(UASInterface* uas, double voltage, double current, double percent, int seconds);
void batteryConsumedChanged(UASInterface* uas, double current_consumed);
void statusChanged(UASInterface* uas, QString status); void statusChanged(UASInterface* uas, QString status);
void thrustChanged(UASInterface*, double thrust); void thrustChanged(UASInterface*, double thrust);
void attitudeChanged(UASInterface*, double roll, double pitch, double yaw, quint64 usec); void attitudeChanged(UASInterface*, double roll, double pitch, double yaw, quint64 usec);
...@@ -264,8 +263,8 @@ signals: ...@@ -264,8 +263,8 @@ signals:
void positionSetPointsChanged(int uasid, float xDesired, float yDesired, float zDesired, float yawDesired, quint64 usec); void positionSetPointsChanged(int uasid, float xDesired, float yDesired, float zDesired, float yawDesired, quint64 usec);
/** @brief A user (or an autonomous mission or obstacle avoidance planner) requested to set a new setpoint */ /** @brief A user (or an autonomous mission or obstacle avoidance planner) requested to set a new setpoint */
void userPositionSetPointsChanged(int uasid, float xDesired, float yDesired, float zDesired, float yawDesired); void userPositionSetPointsChanged(int uasid, float xDesired, float yDesired, float zDesired, float yawDesired);
void globalPositionChanged(UASInterface*, double lat, double lon, double altAMSL, double altWGS84, quint64 usec); void globalPositionChanged(UASInterface*, double lat, double lon, double altAMSL, quint64 usec);
void altitudeChanged(UASInterface*, double altitudeAMSL, double altitudeWGS84, double altitudeRelative, double climbRate, quint64 usec); void altitudeChanged(UASInterface*, double altitudeAMSL, double altitudeRelative, double climbRate, quint64 usec);
/** @brief Update the status of one satellite used for localization */ /** @brief Update the status of one satellite used for localization */
void gpsSatelliteStatusChanged(int uasid, int satid, float azimuth, float direction, float snr, bool used); void gpsSatelliteStatusChanged(int uasid, int satid, float azimuth, float direction, float snr, bool used);
......
...@@ -165,13 +165,13 @@ Rectangle { ...@@ -165,13 +165,13 @@ Rectangle {
function getBatteryColor() { function getBatteryColor() {
if(activeVehicle) { if(activeVehicle) {
if(activeVehicle.batteryPercent > 75) { if(activeVehicle.battery.percentRemaining.value > 75) {
return colorGreen return colorGreen
} }
if(activeVehicle.batteryPercent > 50) { if(activeVehicle.battery.percentRemaining.value > 50) {
return colorOrange return colorOrange
} }
if(activeVehicle.batteryPercent > 0.1) { if(activeVehicle.battery.percentRemaining.value > 0.1) {
return colorRed return colorRed
} }
} }
...@@ -276,27 +276,29 @@ Rectangle { ...@@ -276,27 +276,29 @@ Rectangle {
// Battery Info // Battery Info
Component { Component {
id: batteryInfo id: batteryInfo
Rectangle { Rectangle {
color: Qt.rgba(0,0,0,0.75) color: Qt.rgba(0,0,0,0.75)
width: battCol.width + ScreenTools.defaultFontPixelWidth * 3 width: battCol.width + ScreenTools.defaultFontPixelWidth * 3
height: battCol.height + ScreenTools.defaultFontPixelHeight * 2 height: battCol.height + ScreenTools.defaultFontPixelHeight * 2
radius: ScreenTools.defaultFontPixelHeight * 0.5 radius: ScreenTools.defaultFontPixelHeight * 0.5
Column { Column {
id: battCol id: battCol
spacing: ScreenTools.defaultFontPixelHeight * 0.5 spacing: ScreenTools.defaultFontPixelHeight * 0.5
width: Math.max(battGrid.width, battLabel.width) width: Math.max(battGrid.width, battLabel.width)
anchors.margins: ScreenTools.defaultFontPixelHeight anchors.margins: ScreenTools.defaultFontPixelHeight
anchors.centerIn: parent anchors.centerIn: parent
QGCLabel { QGCLabel {
id: battLabel id: battLabel
text: (activeVehicle && (activeVehicle.batteryVoltage > 0)) ? "Battery Status" : "Battery Data Unavailable" text: "Battery Status"
color: colorWhite color: colorWhite
font.weight:Font.DemiBold font.weight:Font.DemiBold
anchors.horizontalCenter: parent.horizontalCenter anchors.horizontalCenter: parent.horizontalCenter
} }
GridLayout { GridLayout {
id: battGrid id: battGrid
visible: (activeVehicle && (activeVehicle.batteryVoltage > 0))
anchors.margins: ScreenTools.defaultFontPixelHeight anchors.margins: ScreenTools.defaultFontPixelHeight
columnSpacing: ScreenTools.defaultFontPixelWidth columnSpacing: ScreenTools.defaultFontPixelWidth
anchors.horizontalCenter: parent.horizontalCenter anchors.horizontalCenter: parent.horizontalCenter
...@@ -306,29 +308,20 @@ Rectangle { ...@@ -306,29 +308,20 @@ Rectangle {
color: colorWhite color: colorWhite
} }
QGCLabel { QGCLabel {
text: activeVehicle ? (activeVehicle.batteryVoltage.toFixed(1) + " V") : "N/A" text: (activeVehicle && activeVehicle.battery.voltage.value != -1) ? (activeVehicle.battery.voltage.valueString + " " + activeVehicle.battery.voltage.units) : "N/A"
color: getBatteryColor() color: getBatteryColor()
} }
// TODO: What "controller" provides "Facts"?
/*
QGCLabel {
text: "Cell Voltage:"
}
QGCLabel {
text: (activeVehicle.batteryVoltage / controller.getParameterFact(-1, "BAT_N_CELLS").value) + "V"
color: getBatteryColor()
}
*/
QGCLabel { QGCLabel {
text: "Accumulated Consumption:" text: "Accumulated Consumption:"
color: colorWhite color: colorWhite
} }
QGCLabel { QGCLabel {
text: activeVehicle ? (activeVehicle.batteryConsumed + " mA") : "N/A" text: (activeVehicle && activeVehicle.battery.mahConsumed.value != -1) ? (activeVehicle.battery.mahConsumed.valueString + " " + activeVehicle.battery.mahConsumed.units) : "N/A"
color: getBatteryColor() color: getBatteryColor()
} }
} }
} }
Component.onCompleted: { Component.onCompleted: {
var pos = mapFromItem(toolBar, centerX - (width / 2), toolBar.height) var pos = mapFromItem(toolBar, centerX - (width / 2), toolBar.height)
x = pos.x x = pos.x
......
...@@ -65,27 +65,22 @@ Row { ...@@ -65,27 +65,22 @@ Row {
} }
function getBatteryVoltageText() { function getBatteryVoltageText() {
if (activeVehicle.batteryVoltage > 0) { if (activeVehicle.battery.voltage.value >= 0) {
//-- TODO: Need number of cells so I can show cell voltage instead of total voltage return activeVehicle.battery.voltage.valueString + activeVehicle.battery.voltage.units
//if (battNumCells && battNumCells.value) {
// return (activeVehicle.batteryVoltage / battNumCells.value).toFixed(2) + 'V'
//} else {
return activeVehicle.batteryVoltage.toFixed(1) + 'V'
//}
} }
return 'N/A'; return 'N/A';
} }
function getBatteryPercentageText() { function getBatteryPercentageText() {
if(activeVehicle) { if(activeVehicle) {
if(activeVehicle.batteryPercent > 98.9) { if(activeVehicle.battery.percentRemaining.value > 98.9) {
return "100%" return "100%"
} }
if(activeVehicle.batteryPercent > 0.1) { if(activeVehicle.battery.percentRemaining.value > 0.1) {
return activeVehicle.batteryPercent.toFixed(0) + "%" return activeVehicle.battery.percentRemaining.valueString + activeVehicle.battery.percentRemaining.units
} }
if(activeVehicle.batteryVoltage > 0) { if(activeVehicle.battery.voltage.value >= 0) {
return activeVehicle.batteryVoltage.toFixed(1) + "V" return activeVehicle.battery.voltage.valueString + activeVehicle.battery.voltage.units
} }
} }
return "N/A" return "N/A"
...@@ -276,7 +271,7 @@ Row { ...@@ -276,7 +271,7 @@ Row {
id: batteryStatus id: batteryStatus
width: battRow.width * 1.1 width: battRow.width * 1.1
height: mainWindow.tbCellHeight height: mainWindow.tbCellHeight
opacity: activeVehicle ? ((activeVehicle.batteryVoltage > 0) ? 1 : 0.5) : 0.5 opacity: (activeVehicle && activeVehicle.battery.voltage.value >= 0) ? 1 : 0.5
Row { Row {
id: battRow id: battRow
height: mainWindow.tbCellHeight height: mainWindow.tbCellHeight
...@@ -299,8 +294,10 @@ Row { ...@@ -299,8 +294,10 @@ Row {
MouseArea { MouseArea {
anchors.fill: parent anchors.fill: parent
onClicked: { onClicked: {
var centerX = mapToItem(toolBar, x, y).x + (width / 2) if (activeVehicle) {
mainWindow.showPopUp(batteryInfo, centerX) var centerX = mapToItem(toolBar, x, y).x + (width / 2)
mainWindow.showPopUp(batteryInfo, centerX)
}
} }
} }
} }
......
...@@ -33,7 +33,6 @@ UASQuickView::UASQuickView(QWidget *parent) : QWidget(parent), ...@@ -33,7 +33,6 @@ UASQuickView::UASQuickView(QWidget *parent) : QWidget(parent),
{ {
valueEnabled("altitudeAMSL"); valueEnabled("altitudeAMSL");
valueEnabled("altitudeAMSLFT"); valueEnabled("altitudeAMSLFT");
valueEnabled("altitudeWGS84");
valueEnabled("altitudeRelative"); valueEnabled("altitudeRelative");
valueEnabled("groundSpeed"); valueEnabled("groundSpeed");
valueEnabled("distToWaypoint"); valueEnabled("distToWaypoint");
......
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