Skip to content
Snippets Groups Projects
Vehicle.cc 121 KiB
Newer Older
  • Learn to ignore specific revisions
  •     if(_firmwarePlugin)
            return _firmwarePlugin->vehicleImageOpaque(this);
        else
            return QString();
    }
    
    QString Vehicle::vehicleImageOutline() const
    {
        if(_firmwarePlugin)
            return _firmwarePlugin->vehicleImageOutline(this);
        else
            return QString();
    }
    
    QString Vehicle::vehicleImageCompass() const
    {
        if(_firmwarePlugin)
            return _firmwarePlugin->vehicleImageCompass(this);
        else
            return QString();
    }
    
    
    const QVariantList& Vehicle::toolBarIndicators()
    
    {
        if(_firmwarePlugin) {
            return _firmwarePlugin->toolBarIndicators(this);
        }
        static QVariantList emptyList;
        return emptyList;
    }
    
    
    Gus Grubba's avatar
    Gus Grubba committed
    const QVariantList& Vehicle::staticCameraList(void) const
    
    {
        if (_firmwarePlugin) {
            return _firmwarePlugin->cameraList(this);
        }
        static QVariantList emptyList;
        return emptyList;
    }
    
    
    bool Vehicle::vehicleYawsToNextWaypointInMission(void) const
    {
        return _firmwarePlugin->vehicleYawsToNextWaypointInMission(this);
    }
    
    void Vehicle::_setupAutoDisarmSignalling(void)
    {
        QString param = _firmwarePlugin->autoDisarmParameter(this);
    
        if (!param.isEmpty() && _parameterManager->parameterExists(FactSystem::defaultComponentId, param)) {
            Fact* fact = _parameterManager->getParameter(FactSystem::defaultComponentId,param);
            connect(fact, &Fact::rawValueChanged, this, &Vehicle::autoDisarmChanged);
            emit autoDisarmChanged();
        }
    }
    
    bool Vehicle::autoDisarm(void)
    {
        QString param = _firmwarePlugin->autoDisarmParameter(this);
    
        if (!param.isEmpty() && _parameterManager->parameterExists(FactSystem::defaultComponentId, param)) {
            Fact* fact = _parameterManager->getParameter(FactSystem::defaultComponentId,param);
            return fact->rawValue().toDouble() > 0;
        }
    
        return false;
    }
    
    
    void Vehicle::_handleADSBVehicle(const mavlink_message_t& message)
    {
        mavlink_adsb_vehicle_t adsbVehicle;
    
    Don Gagne's avatar
    Don Gagne committed
        static const int maxTimeSinceLastSeen = 15;
    
    
        mavlink_msg_adsb_vehicle_decode(&message, &adsbVehicle);
        if (adsbVehicle.flags | ADSB_FLAGS_VALID_COORDS) {
            if (_adsbICAOMap.contains(adsbVehicle.ICAO_address)) {
    
    DonLakeFlyer's avatar
    DonLakeFlyer committed
                if (adsbVehicle.tslc > maxTimeSinceLastSeen) {
                    ADSBVehicle* vehicle = _adsbICAOMap[adsbVehicle.ICAO_address];
                    _adsbVehicles.removeOne(vehicle);
                    _adsbICAOMap.remove(adsbVehicle.ICAO_address);
                    vehicle->deleteLater();
                } else {
    
    Don Gagne's avatar
    Don Gagne committed
                    _adsbICAOMap[adsbVehicle.ICAO_address]->update(adsbVehicle);
    
    Don Gagne's avatar
    Don Gagne committed
            } else if (adsbVehicle.tslc <= maxTimeSinceLastSeen) {
    
                ADSBVehicle* vehicle = new ADSBVehicle(adsbVehicle, this);
                _adsbICAOMap[adsbVehicle.ICAO_address] = vehicle;
                _adsbVehicles.append(vehicle);
            }
        }
    }
    
    
    void Vehicle::_updateDistanceToHome(void)
    {
        if (coordinate().isValid() && homePosition().isValid()) {
            _distanceToHomeFact.setRawValue(coordinate().distanceTo(homePosition()));
        } else {
            _distanceToHomeFact.setRawValue(qQNaN());
        }
    }
    
    
    void Vehicle::_updateHobbsMeter(void)
    {
        _hobbsFact.setRawValue(hobbsMeter());
    }
    
    
    Don Gagne's avatar
    Don Gagne committed
    void Vehicle::forceInitialPlanRequestComplete(void)
    {
        _initialPlanRequestComplete = true;
        emit initialPlanRequestCompleteChanged(true);
    }
    
    void Vehicle::sendPlan(QString planFile)
    {
        PlanMasterController::sendPlanToVehicle(this, planFile);
    }
    
    
    QString Vehicle::hobbsMeter()
    {
        static const char* HOOBS_HI = "LND_FLIGHT_T_HI";
        static const char* HOOBS_LO = "LND_FLIGHT_T_LO";
        //-- TODO: Does this exist on non PX4?
        if (_parameterManager->parameterExists(FactSystem::defaultComponentId, HOOBS_HI) &&
    
                _parameterManager->parameterExists(FactSystem::defaultComponentId, HOOBS_LO)) {
    
            Fact* factHi = _parameterManager->getParameter(FactSystem::defaultComponentId, HOOBS_HI);
            Fact* factLo = _parameterManager->getParameter(FactSystem::defaultComponentId, HOOBS_LO);
    
            uint64_t hobbsTimeSeconds = ((uint64_t)factHi->rawValue().toUInt() << 32 | (uint64_t)factLo->rawValue().toUInt()) / 1000000;
    
            int hours   = hobbsTimeSeconds / 3600;
            int minutes = (hobbsTimeSeconds % 3600) / 60;
            int seconds = hobbsTimeSeconds % 60;
            QString timeStr;
            timeStr.sprintf("%04d:%02d:%02d", hours, minutes, seconds);
    
            qCDebug(VehicleLog) << "Hobbs Meter:" << timeStr << "(" << factHi->rawValue().toUInt() << factLo->rawValue().toUInt() << ")";
    
            return timeStr;
        }
        return QString("0000:00:00");
    }
    
    void Vehicle::_vehicleParamLoaded(bool ready)
    {
        //-- TODO: This seems silly but can you think of a better
        //   way to update this?
        if(ready) {
            emit hobbsMeterChanged();
        }
    }
    
    
    void Vehicle::_updateHighLatencyLink(void)
    {
        if (_priorityLink->highLatency() != _highLatencyLink) {
            _highLatencyLink = _priorityLink->highLatency();
    
    DonLakeFlyer's avatar
    DonLakeFlyer committed
            _mavCommandAckTimer.setInterval(_highLatencyLink ? _mavCommandAckTimeoutMSecsHighLatency : _mavCommandAckTimeoutMSecs);
    
            emit highLatencyLinkChanged(_highLatencyLink);
        }
    }
    
    
    //-----------------------------------------------------------------------------
    //-----------------------------------------------------------------------------
    
    
    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();
    }
    
    DonLakeFlyer's avatar
    DonLakeFlyer committed
    
    const char* VehicleSetpointFactGroup::_rollFactName =       "roll";
    const char* VehicleSetpointFactGroup::_pitchFactName =      "pitch";
    const char* VehicleSetpointFactGroup::_yawFactName =        "yaw";
    const char* VehicleSetpointFactGroup::_rollRateFactName =   "rollRate";
    const char* VehicleSetpointFactGroup::_pitchRateFactName =  "pitchRate";
    const char* VehicleSetpointFactGroup::_yawRateFactName =    "yawRate";
    
    VehicleSetpointFactGroup::VehicleSetpointFactGroup(QObject* parent)
        : FactGroup     (1000, ":/json/Vehicle/SetpointFact.json", parent)
        , _rollFact     (0, _rollFactName,      FactMetaData::valueTypeDouble)
        , _pitchFact    (0, _pitchFactName,     FactMetaData::valueTypeDouble)
        , _yawFact      (0, _yawFactName,       FactMetaData::valueTypeDouble)
        , _rollRateFact (0, _rollRateFactName,  FactMetaData::valueTypeDouble)
        , _pitchRateFact(0, _pitchRateFactName, FactMetaData::valueTypeDouble)
        , _yawRateFact  (0, _yawRateFactName,   FactMetaData::valueTypeDouble)
    {
        _addFact(&_rollFact,        _rollFactName);
        _addFact(&_pitchFact,       _pitchFactName);
        _addFact(&_yawFact,         _yawFactName);
        _addFact(&_rollRateFact,    _rollRateFactName);
        _addFact(&_pitchRateFact,   _pitchRateFactName);
        _addFact(&_yawRateFact,     _yawRateFactName);
    
        // Start out as not available "--.--"
        _rollFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
        _pitchFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
        _yawFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
        _rollRateFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
        _pitchRateFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
        _yawRateFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
    }