Skip to content
Snippets Groups Projects
Vehicle.cc 114 KiB
Newer Older
  • Learn to ignore specific revisions
  •         emit highLatencyLinkChanged(_highLatencyLink);
        }
    }
    
    
    void Vehicle::_trafficUpdate(QString traffic_id, QString vehicle_id, QGeoCoordinate location, float heading)
    {
    
        // qDebug() << "traffic update:" << traffic_id << vehicle_id << heading << location;
        // TODO: filter based on minimum altitude?
        if (_trafficVehicleMap.contains(traffic_id)) {
            _trafficVehicleMap[traffic_id]->update(location, heading);
        } else {
            ADSBVehicle* vehicle = new ADSBVehicle(location, heading, this);
            _trafficVehicleMap[traffic_id] = vehicle;
            _adsbVehicles.append(vehicle);
        }
    
    }
    
    void Vehicle::_adsbTimerTimeout()
    {
        // TODO: take into account _adsbICAOMap as well? Needs to be tested, especially the timeout
    
        for (auto it = _trafficVehicleMap.begin(); it != _trafficVehicleMap.end();) {
            if (it.value()->expired()) {
                _adsbVehicles.removeOne(it.value());
                delete it.value();
                it = _trafficVehicleMap.erase(it);
            } else {
                ++it;
            }
        }
    }
    
    //-----------------------------------------------------------------------------
    //-----------------------------------------------------------------------------
    
    
    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 char* VehicleBatteryFactGroup::_instantPowerFactName =                "instantPower";
    
    
    const char* VehicleBatteryFactGroup::_settingsGroup =                       "Vehicle.battery";
    
    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;
    
    const double VehicleBatteryFactGroup::_instantPowerUnavailable =      -1.0;
    
    Don Gagne's avatar
    Don Gagne committed
    VehicleBatteryFactGroup::VehicleBatteryFactGroup(QObject* parent)
        : FactGroup(1000, ":/json/Vehicle/BatteryFact.json", parent)
    
        , _voltageFact                  (0, _voltageFactName,                   FactMetaData::valueTypeDouble)
        , _percentRemainingFact         (0, _percentRemainingFactName,          FactMetaData::valueTypeInt32)
        , _mahConsumedFact              (0, _mahConsumedFactName,               FactMetaData::valueTypeInt32)
    
    Don Gagne's avatar
    Don Gagne committed
        , _currentFact                  (0, _currentFactName,                   FactMetaData::valueTypeFloat)
    
        , _temperatureFact              (0, _temperatureFactName,               FactMetaData::valueTypeDouble)
        , _cellCountFact                (0, _cellCountFactName,                 FactMetaData::valueTypeInt32)
    
        , _instantPowerFact             (0, _instantPowerFactName,              FactMetaData::valueTypeFloat)
    
        _addFact(&_voltageFact,                 _voltageFactName);
        _addFact(&_percentRemainingFact,        _percentRemainingFactName);
        _addFact(&_mahConsumedFact,             _mahConsumedFactName);
        _addFact(&_currentFact,                 _currentFactName);
        _addFact(&_temperatureFact,             _temperatureFactName);
        _addFact(&_cellCountFact,               _cellCountFactName);
    
        _addFact(&_instantPowerFact,            _instantPowerFactName);
    
    Don Gagne's avatar
    Don Gagne committed
    
        // Start out as not available
        _voltageFact.setRawValue            (_voltageUnavailable);
        _percentRemainingFact.setRawValue   (_percentRemainingUnavailable);
        _mahConsumedFact.setRawValue        (_mahConsumedUnavailable);
        _currentFact.setRawValue            (_currentUnavailable);
        _temperatureFact.setRawValue        (_temperatureUnavailable);
        _cellCountFact.setRawValue          (_cellCountUnavailable);
    
        _instantPowerFact.setRawValue       (_instantPowerUnavailable);
    
    const char* VehicleWindFactGroup::_directionFactName =      "direction";
    const char* VehicleWindFactGroup::_speedFactName =          "speed";
    const char* VehicleWindFactGroup::_verticalSpeedFactName =  "verticalSpeed";
    
    
    Don Gagne's avatar
    Don Gagne committed
    VehicleWindFactGroup::VehicleWindFactGroup(QObject* parent)
        : FactGroup(1000, ":/json/Vehicle/WindFact.json", parent)
        , _directionFact    (0, _directionFactName,     FactMetaData::valueTypeDouble)
        , _speedFact        (0, _speedFactName,         FactMetaData::valueTypeDouble)
        , _verticalSpeedFact(0, _verticalSpeedFactName, FactMetaData::valueTypeDouble)
    {
        _addFact(&_directionFact,       _directionFactName);
        _addFact(&_speedFact,           _speedFactName);
        _addFact(&_verticalSpeedFact,   _verticalSpeedFactName);
    
        // Start out as not available "--.--"
        _directionFact.setRawValue      (std::numeric_limits<float>::quiet_NaN());
        _speedFact.setRawValue          (std::numeric_limits<float>::quiet_NaN());
        _verticalSpeedFact.setRawValue  (std::numeric_limits<float>::quiet_NaN());
    }
    
    
    const char* VehicleVibrationFactGroup::_xAxisFactName =      "xAxis";
    const char* VehicleVibrationFactGroup::_yAxisFactName =      "yAxis";
    const char* VehicleVibrationFactGroup::_zAxisFactName =      "zAxis";
    const char* VehicleVibrationFactGroup::_clipCount1FactName = "clipCount1";
    const char* VehicleVibrationFactGroup::_clipCount2FactName = "clipCount2";
    const char* VehicleVibrationFactGroup::_clipCount3FactName = "clipCount3";
    
    
    VehicleVibrationFactGroup::VehicleVibrationFactGroup(QObject* parent)
        : FactGroup(1000, ":/json/Vehicle/VibrationFact.json", parent)
        , _xAxisFact        (0, _xAxisFactName,         FactMetaData::valueTypeDouble)
        , _yAxisFact        (0, _yAxisFactName,         FactMetaData::valueTypeDouble)
        , _zAxisFact        (0, _zAxisFactName,         FactMetaData::valueTypeDouble)
        , _clipCount1Fact   (0, _clipCount1FactName,    FactMetaData::valueTypeUint32)
        , _clipCount2Fact   (0, _clipCount2FactName,    FactMetaData::valueTypeUint32)
        , _clipCount3Fact   (0, _clipCount3FactName,    FactMetaData::valueTypeUint32)
    {
        _addFact(&_xAxisFact,       _xAxisFactName);
        _addFact(&_yAxisFact,       _yAxisFactName);
        _addFact(&_zAxisFact,       _zAxisFactName);
        _addFact(&_clipCount1Fact,  _clipCount1FactName);
        _addFact(&_clipCount2Fact,  _clipCount2FactName);
        _addFact(&_clipCount3Fact,  _clipCount3FactName);
    
        // Start out as not available "--.--"
        _xAxisFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
        _yAxisFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
        _zAxisFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
    }
    
    
    
    const char* VehicleTemperatureFactGroup::_temperature1FactName =      "temperature1";
    const char* VehicleTemperatureFactGroup::_temperature2FactName =      "temperature2";
    const char* VehicleTemperatureFactGroup::_temperature3FactName =      "temperature3";
    
    VehicleTemperatureFactGroup::VehicleTemperatureFactGroup(QObject* parent)
        : FactGroup(1000, ":/json/Vehicle/TemperatureFact.json", parent)
        , _temperature1Fact    (0, _temperature1FactName,     FactMetaData::valueTypeDouble)
        , _temperature2Fact    (0, _temperature2FactName,     FactMetaData::valueTypeDouble)
        , _temperature3Fact    (0, _temperature3FactName,     FactMetaData::valueTypeDouble)
    {
        _addFact(&_temperature1Fact,       _temperature1FactName);
        _addFact(&_temperature2Fact,       _temperature2FactName);
        _addFact(&_temperature3Fact,       _temperature3FactName);
    
        // Start out as not available "--.--"
        _temperature1Fact.setRawValue      (std::numeric_limits<float>::quiet_NaN());
        _temperature2Fact.setRawValue      (std::numeric_limits<float>::quiet_NaN());
        _temperature3Fact.setRawValue      (std::numeric_limits<float>::quiet_NaN());
    }
    
    dheideman's avatar
    dheideman committed
    
    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();
    }