Commit 878d94a5 authored by dheideman's avatar dheideman Committed by Jacob Walser

Add clock facts to widget

parent 71a57cb2
......@@ -222,6 +222,7 @@
<file alias="Vehicle/TemperatureFact.json">src/Vehicle/TemperatureFact.json</file>
<file alias="Vehicle/SubmarineFact.json">src/Vehicle/SubmarineFact.json</file>
<file alias="BrandImage.SettingsGroup.json">src/Settings/BrandImage.SettingsGroup.json</file>
<file alias="Vehicle/ClockFact.json">src/Vehicle/ClockFact.json</file>
</qresource>
<qresource prefix="/MockLink">
<file alias="APMArduCopterMockLink.params">src/comm/APMArduCopterMockLink.params</file>
......
......@@ -48,8 +48,8 @@ protected:
int _updateRateMSecs; ///< Update rate for Fact::valueChanged signals, 0: immediate update
private slots:
void _updateAllValues(void);
protected slots:
virtual void _updateAllValues(void);
private:
void _setupTimer();
......
[
{
"name": "currentTime",
"shortDescription": "Time",
"type": "string"
},
{
"name": "currentDate",
"shortDescription": "Date",
"type": "string"
}
]
......@@ -7,6 +7,9 @@
*
****************************************************************************/
#include <QTime>
#include <QDateTime>
#include <QLocale>
#include "Vehicle.h"
#include "MAVLinkProtocol.h"
......@@ -66,6 +69,7 @@ const char* Vehicle::_batteryFactGroupName = "battery";
const char* Vehicle::_windFactGroupName = "wind";
const char* Vehicle::_vibrationFactGroupName = "vibration";
const char* Vehicle::_temperatureFactGroupName = "temperature";
const char* Vehicle::_clockFactGroupName = "clock";
Vehicle::Vehicle(LinkInterface* link,
int vehicleId,
......@@ -174,6 +178,7 @@ Vehicle::Vehicle(LinkInterface* link,
, _windFactGroup(this)
, _vibrationFactGroup(this)
, _temperatureFactGroup(this)
, _clockFactGroup(this)
{
_addLink(link);
......@@ -348,6 +353,7 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType,
, _batteryFactGroup(this)
, _windFactGroup(this)
, _vibrationFactGroup(this)
, _clockFactGroup(this)
{
_commonInit();
_firmwarePlugin->initializeVehicle(this);
......@@ -411,6 +417,7 @@ void Vehicle::_commonInit(void)
_addFactGroup(&_windFactGroup, _windFactGroupName);
_addFactGroup(&_vibrationFactGroup, _vibrationFactGroupName);
_addFactGroup(&_temperatureFactGroup, _temperatureFactGroupName);
_addFactGroup(&_clockFactGroup, _clockFactGroupName);
// Add firmware-specific fact groups, if provided
QMap<QString, FactGroup*>* fwFactGroups = _firmwarePlugin->factGroups();
......@@ -3046,3 +3053,27 @@ VehicleTemperatureFactGroup::VehicleTemperatureFactGroup(QObject* parent)
_temperature2Fact.setRawValue (std::numeric_limits<float>::quiet_NaN());
_temperature3Fact.setRawValue (std::numeric_limits<float>::quiet_NaN());
}
const char* VehicleClockFactGroup::_currentTimeFactName = "currentTime";
const char* VehicleClockFactGroup::_currentDateFactName = "currentDate";
VehicleClockFactGroup::VehicleClockFactGroup(QObject* parent)
: FactGroup(1000, ":/json/Vehicle/ClockFact.json", parent)
, _currentTimeFact (0, _currentTimeFactName, FactMetaData::valueTypeString)
, _currentDateFact (0, _currentDateFactName, FactMetaData::valueTypeString)
{
_addFact(&_currentTimeFact, _currentTimeFactName);
_addFact(&_currentDateFact, _currentDateFactName);
// Start out as not available "--.--"
_currentTimeFact.setRawValue (std::numeric_limits<float>::quiet_NaN());
_currentDateFact.setRawValue (std::numeric_limits<float>::quiet_NaN());
}
void VehicleClockFactGroup::_updateAllValues(void)
{
_currentTimeFact.setRawValue(QTime::currentTime().toString());
_currentDateFact.setRawValue(QDateTime::currentDateTime().toString(QLocale::system().dateFormat(QLocale::ShortFormat)));
FactGroup::_updateAllValues();
}
......@@ -224,6 +224,32 @@ private:
Fact _temperature3Fact;
};
class VehicleClockFactGroup : public FactGroup
{
Q_OBJECT
public:
VehicleClockFactGroup(QObject* parent = NULL);
Q_PROPERTY(Fact* currentTime READ currentTime CONSTANT)
Q_PROPERTY(Fact* currentDate READ currentDate CONSTANT)
Fact* currentTime (void) { return &_currentTimeFact; }
Fact* currentDate (void) { return &_currentDateFact; }
static const char* _currentTimeFactName;
static const char* _currentDateFactName;
static const char* _settingsGroup;
private slots:
void _updateAllValues(void) override;
private:
Fact _currentTimeFact;
Fact _currentDateFact;
};
class Vehicle : public FactGroup
{
Q_OBJECT
......@@ -356,6 +382,7 @@ public:
Q_PROPERTY(FactGroup* wind READ windFactGroup CONSTANT)
Q_PROPERTY(FactGroup* vibration READ vibrationFactGroup CONSTANT)
Q_PROPERTY(FactGroup* temperature READ temperatureFactGroup CONSTANT)
Q_PROPERTY(FactGroup* clock READ clockFactGroup CONSTANT)
Q_PROPERTY(int firmwareMajorVersion READ firmwareMajorVersion NOTIFY firmwareVersionChanged)
Q_PROPERTY(int firmwareMinorVersion READ firmwareMinorVersion NOTIFY firmwareVersionChanged)
......@@ -627,6 +654,7 @@ public:
FactGroup* windFactGroup (void) { return &_windFactGroup; }
FactGroup* vibrationFactGroup (void) { return &_vibrationFactGroup; }
FactGroup* temperatureFactGroup (void) { return &_temperatureFactGroup; }
FactGroup* clockFactGroup (void) { return &_clockFactGroup; }
void setConnectionLostEnabled(bool connectionLostEnabled);
......@@ -1076,6 +1104,7 @@ private:
VehicleWindFactGroup _windFactGroup;
VehicleVibrationFactGroup _vibrationFactGroup;
VehicleTemperatureFactGroup _temperatureFactGroup;
VehicleClockFactGroup _clockFactGroup;
static const char* _rollFactName;
static const char* _pitchFactName;
......@@ -1095,6 +1124,7 @@ private:
static const char* _windFactGroupName;
static const char* _vibrationFactGroupName;
static const char* _temperatureFactGroupName;
static const char* _clockFactGroupName;
static const int _vehicleUIUpdateRateMSecs = 100;
......
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