Commit 61a50ca6 authored by DonLakeFlyer's avatar DonLakeFlyer

comit

parent 65ebabe4
...@@ -83,10 +83,9 @@ SetupPage { ...@@ -83,10 +83,9 @@ SetupPage {
id: newFramePageComponent id: newFramePageComponent
Grid { Grid {
anchors.left: parent.left width: availableWidth
anchors.right: parent.right spacing: _margins
spacing: _margins columns: 2
columns: 2
QGCLabel { QGCLabel {
text: qsTr("Frame Class:") text: qsTr("Frame Class:")
......
...@@ -69,7 +69,8 @@ const char* Vehicle::_distanceToHomeFactName = "distanceToHome"; ...@@ -69,7 +69,8 @@ const char* Vehicle::_distanceToHomeFactName = "distanceToHome";
const char* Vehicle::_hobbsFactName = "hobbs"; const char* Vehicle::_hobbsFactName = "hobbs";
const char* Vehicle::_gpsFactGroupName = "gps"; const char* Vehicle::_gpsFactGroupName = "gps";
const char* Vehicle::_batteryFactGroupName = "battery"; const char* Vehicle::_battery1FactGroupName = "battery";
const char* Vehicle::_battery2FactGroupName = "battery2";
const char* Vehicle::_windFactGroupName = "wind"; const char* Vehicle::_windFactGroupName = "wind";
const char* Vehicle::_vibrationFactGroupName = "vibration"; const char* Vehicle::_vibrationFactGroupName = "vibration";
const char* Vehicle::_temperatureFactGroupName = "temperature"; const char* Vehicle::_temperatureFactGroupName = "temperature";
...@@ -185,7 +186,8 @@ Vehicle::Vehicle(LinkInterface* link, ...@@ -185,7 +186,8 @@ Vehicle::Vehicle(LinkInterface* link,
, _distanceToHomeFact (0, _distanceToHomeFactName, FactMetaData::valueTypeDouble) , _distanceToHomeFact (0, _distanceToHomeFactName, FactMetaData::valueTypeDouble)
, _hobbsFact (0, _hobbsFactName, FactMetaData::valueTypeString) , _hobbsFact (0, _hobbsFactName, FactMetaData::valueTypeString)
, _gpsFactGroup(this) , _gpsFactGroup(this)
, _batteryFactGroup(this) , _battery1FactGroup(this)
, _battery2FactGroup(this)
, _windFactGroup(this) , _windFactGroup(this)
, _vibrationFactGroup(this) , _vibrationFactGroup(this)
, _temperatureFactGroup(this) , _temperatureFactGroup(this)
...@@ -370,7 +372,8 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType, ...@@ -370,7 +372,8 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType,
, _distanceToHomeFact (0, _distanceToHomeFactName, FactMetaData::valueTypeDouble) , _distanceToHomeFact (0, _distanceToHomeFactName, FactMetaData::valueTypeDouble)
, _hobbsFact (0, _hobbsFactName, FactMetaData::valueTypeString) , _hobbsFact (0, _hobbsFactName, FactMetaData::valueTypeString)
, _gpsFactGroup(this) , _gpsFactGroup(this)
, _batteryFactGroup(this) , _battery1FactGroup(this)
, _battery2FactGroup(this)
, _windFactGroup(this) , _windFactGroup(this)
, _vibrationFactGroup(this) , _vibrationFactGroup(this)
, _clockFactGroup(this) , _clockFactGroup(this)
...@@ -440,7 +443,8 @@ void Vehicle::_commonInit(void) ...@@ -440,7 +443,8 @@ void Vehicle::_commonInit(void)
_addFact(&_hobbsFact, _hobbsFactName); _addFact(&_hobbsFact, _hobbsFactName);
_addFactGroup(&_gpsFactGroup, _gpsFactGroupName); _addFactGroup(&_gpsFactGroup, _gpsFactGroupName);
_addFactGroup(&_batteryFactGroup, _batteryFactGroupName); _addFactGroup(&_battery1FactGroup, _battery1FactGroupName);
_addFactGroup(&_battery2FactGroup, _battery2FactGroupName);
_addFactGroup(&_windFactGroup, _windFactGroupName); _addFactGroup(&_windFactGroup, _windFactGroupName);
_addFactGroup(&_vibrationFactGroup, _vibrationFactGroupName); _addFactGroup(&_vibrationFactGroup, _vibrationFactGroupName);
_addFactGroup(&_temperatureFactGroup, _temperatureFactGroupName); _addFactGroup(&_temperatureFactGroup, _temperatureFactGroupName);
...@@ -940,7 +944,7 @@ void Vehicle::_handleHighLatency2(mavlink_message_t& message) ...@@ -940,7 +944,7 @@ void Vehicle::_handleHighLatency2(mavlink_message_t& message)
_windFactGroup.direction()->setRawValue((double)highLatency2.wind_heading * 2.0); _windFactGroup.direction()->setRawValue((double)highLatency2.wind_heading * 2.0);
_windFactGroup.speed()->setRawValue((double)highLatency2.windspeed / 5.0); _windFactGroup.speed()->setRawValue((double)highLatency2.windspeed / 5.0);
_batteryFactGroup.percentRemaining()->setRawValue(highLatency2.battery); _battery1FactGroup.percentRemaining()->setRawValue(highLatency2.battery);
_temperatureFactGroup.temperature1()->setRawValue(highLatency2.temperature_air); _temperatureFactGroup.temperature1()->setRawValue(highLatency2.temperature_air);
...@@ -1245,19 +1249,19 @@ void Vehicle::_handleSysStatus(mavlink_message_t& message) ...@@ -1245,19 +1249,19 @@ void Vehicle::_handleSysStatus(mavlink_message_t& message)
mavlink_msg_sys_status_decode(&message, &sysStatus); mavlink_msg_sys_status_decode(&message, &sysStatus);
if (sysStatus.current_battery == -1) { if (sysStatus.current_battery == -1) {
_batteryFactGroup.current()->setRawValue(VehicleBatteryFactGroup::_currentUnavailable); _battery1FactGroup.current()->setRawValue(VehicleBatteryFactGroup::_currentUnavailable);
} else { } else {
// Current is in Amps, current_battery is 10 * milliamperes (1 = 10 milliampere) // Current is in Amps, current_battery is 10 * milliamperes (1 = 10 milliampere)
_batteryFactGroup.current()->setRawValue((float)sysStatus.current_battery / 100.0f); _battery1FactGroup.current()->setRawValue((float)sysStatus.current_battery / 100.0f);
} }
if (sysStatus.voltage_battery == UINT16_MAX) { if (sysStatus.voltage_battery == UINT16_MAX) {
_batteryFactGroup.voltage()->setRawValue(VehicleBatteryFactGroup::_voltageUnavailable); _battery1FactGroup.voltage()->setRawValue(VehicleBatteryFactGroup::_voltageUnavailable);
} else { } else {
_batteryFactGroup.voltage()->setRawValue((double)sysStatus.voltage_battery / 1000.0); _battery1FactGroup.voltage()->setRawValue((double)sysStatus.voltage_battery / 1000.0);
// current_battery is 10 mA and voltage_battery is 1mV. (10/1e3 times 1/1e3 = 1/1e5) // current_battery is 10 mA and voltage_battery is 1mV. (10/1e3 times 1/1e3 = 1/1e5)
_batteryFactGroup.instantPower()->setRawValue((float)(sysStatus.current_battery*sysStatus.voltage_battery)/(100000.0)); _battery1FactGroup.instantPower()->setRawValue((float)(sysStatus.current_battery*sysStatus.voltage_battery)/(100000.0));
} }
_batteryFactGroup.percentRemaining()->setRawValue(sysStatus.battery_remaining); _battery1FactGroup.percentRemaining()->setRawValue(sysStatus.battery_remaining);
if (sysStatus.battery_remaining > 0) { if (sysStatus.battery_remaining > 0) {
if (sysStatus.battery_remaining < _settingsManager->appSettings()->batteryPercentRemainingAnnounce()->rawValue().toInt() && if (sysStatus.battery_remaining < _settingsManager->appSettings()->batteryPercentRemainingAnnounce()->rawValue().toInt() &&
...@@ -1301,14 +1305,14 @@ void Vehicle::_handleBatteryStatus(mavlink_message_t& message) ...@@ -1301,14 +1305,14 @@ void Vehicle::_handleBatteryStatus(mavlink_message_t& message)
mavlink_msg_battery_status_decode(&message, &bat_status); mavlink_msg_battery_status_decode(&message, &bat_status);
if (bat_status.temperature == INT16_MAX) { if (bat_status.temperature == INT16_MAX) {
_batteryFactGroup.temperature()->setRawValue(VehicleBatteryFactGroup::_temperatureUnavailable); _battery1FactGroup.temperature()->setRawValue(VehicleBatteryFactGroup::_temperatureUnavailable);
} else { } else {
_batteryFactGroup.temperature()->setRawValue((double)bat_status.temperature / 100.0); _battery1FactGroup.temperature()->setRawValue((double)bat_status.temperature / 100.0);
} }
if (bat_status.current_consumed == -1) { if (bat_status.current_consumed == -1) {
_batteryFactGroup.mahConsumed()->setRawValue(VehicleBatteryFactGroup::_mahConsumedUnavailable); _battery1FactGroup.mahConsumed()->setRawValue(VehicleBatteryFactGroup::_mahConsumedUnavailable);
} else { } else {
_batteryFactGroup.mahConsumed()->setRawValue(bat_status.current_consumed); _battery1FactGroup.mahConsumed()->setRawValue(bat_status.current_consumed);
} }
int cellCount = 0; int cellCount = 0;
...@@ -1321,15 +1325,15 @@ void Vehicle::_handleBatteryStatus(mavlink_message_t& message) ...@@ -1321,15 +1325,15 @@ void Vehicle::_handleBatteryStatus(mavlink_message_t& message)
cellCount = -1; cellCount = -1;
} }
_batteryFactGroup.cellCount()->setRawValue(cellCount); _battery1FactGroup.cellCount()->setRawValue(cellCount);
//-- Time remaining in seconds (0 means not supported) //-- Time remaining in seconds (0 means not supported)
_batteryFactGroup.timeRemaining()->setRawValue(bat_status.time_remaining); _battery1FactGroup.timeRemaining()->setRawValue(bat_status.time_remaining);
//-- Battery charge state (0 means not supported) //-- Battery charge state (0 means not supported)
if(bat_status.charge_state <= MAV_BATTERY_CHARGE_STATE_UNHEALTHY) { if(bat_status.charge_state <= MAV_BATTERY_CHARGE_STATE_UNHEALTHY) {
_batteryFactGroup.chargeState()->setRawValue(bat_status.charge_state); _battery1FactGroup.chargeState()->setRawValue(bat_status.charge_state);
} else { } else {
_batteryFactGroup.chargeState()->setRawValue(0); _battery1FactGroup.chargeState()->setRawValue(0);
} }
//-- TODO: Somewhere, actions would be taken based on this chargeState: //-- TODO: Somewhere, actions would be taken based on this chargeState:
// MAV_BATTERY_CHARGE_STATE_CRITICAL: Battery state is critical, return / abort immediately // MAV_BATTERY_CHARGE_STATE_CRITICAL: Battery state is critical, return / abort immediately
......
...@@ -526,7 +526,8 @@ public: ...@@ -526,7 +526,8 @@ public:
Q_PROPERTY(Fact* hobbs READ hobbs CONSTANT) Q_PROPERTY(Fact* hobbs READ hobbs CONSTANT)
Q_PROPERTY(FactGroup* gps READ gpsFactGroup CONSTANT) Q_PROPERTY(FactGroup* gps READ gpsFactGroup CONSTANT)
Q_PROPERTY(FactGroup* battery READ batteryFactGroup CONSTANT) Q_PROPERTY(FactGroup* battery READ battery1FactGroup CONSTANT)
Q_PROPERTY(FactGroup* battery2 READ battery2FactGroup CONSTANT)
Q_PROPERTY(FactGroup* wind READ windFactGroup CONSTANT) Q_PROPERTY(FactGroup* wind READ windFactGroup CONSTANT)
Q_PROPERTY(FactGroup* vibration READ vibrationFactGroup CONSTANT) Q_PROPERTY(FactGroup* vibration READ vibrationFactGroup CONSTANT)
Q_PROPERTY(FactGroup* temperature READ temperatureFactGroup CONSTANT) Q_PROPERTY(FactGroup* temperature READ temperatureFactGroup CONSTANT)
...@@ -816,7 +817,8 @@ public: ...@@ -816,7 +817,8 @@ public:
Fact* hobbs (void) { return &_hobbsFact; } Fact* hobbs (void) { return &_hobbsFact; }
FactGroup* gpsFactGroup (void) { return &_gpsFactGroup; } FactGroup* gpsFactGroup (void) { return &_gpsFactGroup; }
FactGroup* batteryFactGroup (void) { return &_batteryFactGroup; } FactGroup* battery1FactGroup (void) { return &_battery1FactGroup; }
FactGroup* battery2FactGroup (void) { return &_battery2FactGroup; }
FactGroup* windFactGroup (void) { return &_windFactGroup; } FactGroup* windFactGroup (void) { return &_windFactGroup; }
FactGroup* vibrationFactGroup (void) { return &_vibrationFactGroup; } FactGroup* vibrationFactGroup (void) { return &_vibrationFactGroup; }
FactGroup* temperatureFactGroup (void) { return &_temperatureFactGroup; } FactGroup* temperatureFactGroup (void) { return &_temperatureFactGroup; }
...@@ -1294,7 +1296,8 @@ private: ...@@ -1294,7 +1296,8 @@ private:
Fact _hobbsFact; Fact _hobbsFact;
VehicleGPSFactGroup _gpsFactGroup; VehicleGPSFactGroup _gpsFactGroup;
VehicleBatteryFactGroup _batteryFactGroup; VehicleBatteryFactGroup _battery1FactGroup;
VehicleBatteryFactGroup _battery2FactGroup;
VehicleWindFactGroup _windFactGroup; VehicleWindFactGroup _windFactGroup;
VehicleVibrationFactGroup _vibrationFactGroup; VehicleVibrationFactGroup _vibrationFactGroup;
VehicleTemperatureFactGroup _temperatureFactGroup; VehicleTemperatureFactGroup _temperatureFactGroup;
...@@ -1319,7 +1322,8 @@ private: ...@@ -1319,7 +1322,8 @@ private:
static const char* _hobbsFactName; static const char* _hobbsFactName;
static const char* _gpsFactGroupName; static const char* _gpsFactGroupName;
static const char* _batteryFactGroupName; static const char* _battery1FactGroupName;
static const char* _battery2FactGroupName;
static const char* _windFactGroupName; static const char* _windFactGroupName;
static const char* _vibrationFactGroupName; static const char* _vibrationFactGroupName;
static const char* _temperatureFactGroupName; static const char* _temperatureFactGroupName;
......
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