Newer
Older
/****************************************************************************
*
* (c) 2009-2020 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#include <QTime>
#include <QDateTime>
#include <QLocale>
#include <Eigen/Eigen>
#include "Vehicle.h"
#include "MAVLinkProtocol.h"
#include "FirmwarePluginManager.h"
#include "LinkManager.h"
#include "FirmwarePlugin.h"
#include "PlanMasterController.h"
#include "GeoFenceManager.h"
#include "RallyPointManager.h"
#include "MissionCommandTree.h"
#include "QGCQGeoCoordinate.h"
#include "QGCCorePlugin.h"
#include "VideoReceiver.h"
#include "VideoManager.h"
#include "VideoSettings.h"
#include "ComponentInformationManager.h"
#include "InitialConnectStateMachine.h"
#if defined(QGC_AIRMAP_ENABLED)
#include "AirspaceVehicleManager.h"
#endif
QGC_LOGGING_CATEGORY(VehicleLog, "VehicleLog")
#define UPDATE_TIMER 50
#define DEFAULT_LAT 38.965767f
#define DEFAULT_LON -120.083923f
const QString guided_mode_not_supported_by_vehicle = QObject::tr("Guided mode not supported by Vehicle.");
const char* Vehicle::_settingsGroup = "Vehicle%1"; // %1 replaced with mavlink system id
const char* Vehicle::_joystickEnabledSettingsKey = "JoystickEnabled";
const char* Vehicle::_rollFactName = "roll";
const char* Vehicle::_pitchFactName = "pitch";
const char* Vehicle::_headingFactName = "heading";
const char* Vehicle::_rollRateFactName = "rollRate";
const char* Vehicle::_pitchRateFactName = "pitchRate";
const char* Vehicle::_yawRateFactName = "yawRate";
const char* Vehicle::_airSpeedFactName = "airSpeed";
const char* Vehicle::_groundSpeedFactName = "groundSpeed";
const char* Vehicle::_climbRateFactName = "climbRate";
const char* Vehicle::_altitudeRelativeFactName = "altitudeRelative";
const char* Vehicle::_altitudeAMSLFactName = "altitudeAMSL";
const char* Vehicle::_flightDistanceFactName = "flightDistance";
const char* Vehicle::_flightTimeFactName = "flightTime";
const char* Vehicle::_distanceToHomeFactName = "distanceToHome";
const char* Vehicle::_missionItemIndexFactName = "missionItemIndex";
const char* Vehicle::_headingToNextWPFactName = "headingToNextWP";
const char* Vehicle::_hobbsFactName = "hobbs";
const char* Vehicle::_gpsFactGroupName = "gps";
const char* Vehicle::_battery1FactGroupName = "battery";
const char* Vehicle::_battery2FactGroupName = "battery2";
const char* Vehicle::_windFactGroupName = "wind";
const char* Vehicle::_vibrationFactGroupName = "vibration";
const char* Vehicle::_temperatureFactGroupName = "temperature";
const char* Vehicle::_clockFactGroupName = "clock";
const char* Vehicle::_distanceSensorFactGroupName = "distanceSensor";
const char* Vehicle::_estimatorStatusFactGroupName = "estimatorStatus";
Vehicle::Vehicle(LinkInterface* link,
int vehicleId,
MAV_AUTOPILOT firmwareType,
MAV_TYPE vehicleType,
FirmwarePluginManager* firmwarePluginManager,
JoystickManager* joystickManager)
: FactGroup(_vehicleUIUpdateRateMSecs, ":/json/Vehicle/VehicleFact.json")
, _id(vehicleId)
, _defaultComponentId(defaultComponentId)
, _vehicleType(vehicleType)
, _firmwarePlugin(nullptr)
, _firmwarePluginInstanceData(nullptr)
, _autopilotPlugin(nullptr)
, _mavlink(nullptr)
, _toolbox(qgcApp()->toolbox())
, _settingsManager(_toolbox->settingsManager())
, _uas(nullptr)
, _mav(nullptr)
, _currentMessageCount(0)
, _messageCount(0)
, _currentErrorCount(0)
, _currentWarningCount(0)
, _currentNormalCount(0)
, _currentMessageType(MessageNone)
, _updateCount(0)
, _onboardControlSensorsPresent(0)
, _onboardControlSensorsEnabled(0)
, _onboardControlSensorsHealth(0)
, _onboardControlSensorsUnhealthy(0)
, _defaultCruiseSpeed(_settingsManager->appSettings()->offlineEditingCruiseSpeed()->rawValue().toDouble())
, _defaultHoverSpeed(_settingsManager->appSettings()->offlineEditingHoverSpeed()->rawValue().toDouble())
, _telemetryRRSSI(0)
, _telemetryLRSSI(0)
, _telemetryRXErrors(0)
, _telemetryFixed(0)
, _telemetryTXBuffer(0)
, _telemetryLNoise(0)
, _telemetryRNoise(0)
, _receivingAttitudeQuaternion(false)
, _connectionLost(false)
, _connectionLostEnabled(true)
, _missionManager(nullptr)
, _geoFenceManager(nullptr)
, _rallyPointManager(nullptr)
, _airspaceVehicleManager(nullptr)
, _armed(false)
, _base_mode(0)
, _custom_mode(0)
, _nextSendMessageMultipleIndex(0)
, _firmwarePluginManager(firmwarePluginManager)
, _joystickManager(joystickManager)
, _messagesReceived(0)
, _messagesSent(0)
, _messagesLost(0)
, _messageSeq(0)
, _compID(0)
, _heardFrom(false)
, _firmwareMajorVersion(versionNotSetValue)
, _firmwareMinorVersion(versionNotSetValue)
, _firmwarePatchVersion(versionNotSetValue)
, _firmwareCustomMajorVersion(versionNotSetValue)
, _firmwareCustomMinorVersion(versionNotSetValue)
, _firmwareCustomPatchVersion(versionNotSetValue)
, _firmwareVersionType(FIRMWARE_VERSION_TYPE_OFFICIAL)
, _lastAnnouncedLowBatteryPercent(100)
, _priorityLinkCommanded(false)
, _rollFact (0, _rollFactName, FactMetaData::valueTypeDouble)
, _pitchFact (0, _pitchFactName, FactMetaData::valueTypeDouble)
, _headingFact (0, _headingFactName, FactMetaData::valueTypeDouble)
, _rollRateFact (0, _rollRateFactName, FactMetaData::valueTypeDouble)
, _pitchRateFact (0, _pitchRateFactName, FactMetaData::valueTypeDouble)
, _yawRateFact (0, _yawRateFactName, FactMetaData::valueTypeDouble)
, _groundSpeedFact (0, _groundSpeedFactName, FactMetaData::valueTypeDouble)
, _airSpeedFact (0, _airSpeedFactName, FactMetaData::valueTypeDouble)
, _climbRateFact (0, _climbRateFactName, FactMetaData::valueTypeDouble)
, _altitudeRelativeFact (0, _altitudeRelativeFactName, FactMetaData::valueTypeDouble)
, _altitudeAMSLFact (0, _altitudeAMSLFactName, FactMetaData::valueTypeDouble)
, _flightDistanceFact (0, _flightDistanceFactName, FactMetaData::valueTypeDouble)
, _flightTimeFact (0, _flightTimeFactName, FactMetaData::valueTypeElapsedTimeInSeconds)
, _distanceToHomeFact (0, _distanceToHomeFactName, FactMetaData::valueTypeDouble)
, _missionItemIndexFact (0, _missionItemIndexFactName, FactMetaData::valueTypeUint16)
, _headingToNextWPFact (0, _headingToNextWPFactName, FactMetaData::valueTypeDouble)
, _headingToHomeFact (0, _headingToHomeFactName, FactMetaData::valueTypeDouble)
, _distanceToGCSFact (0, _distanceToGCSFactName, FactMetaData::valueTypeDouble)
, _hobbsFact (0, _hobbsFactName, FactMetaData::valueTypeString)
, _temperatureFactGroup(this)
, _distanceSensorFactGroup(this)
, _terrainFactGroup(this)
, _terrainProtocolHandler(new TerrainProtocolHandler(this, &_terrainFactGroup, this))
connect(_joystickManager, &JoystickManager::activeJoystickChanged, this, &Vehicle::_loadSettings);
connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::activeVehicleAvailableChanged, this, &Vehicle::_loadSettings);
_mavlink = _toolbox->mavlinkProtocol();
qCDebug(VehicleLog) << "Link started with Mavlink " << (_mavlink->getCurrentVersion() >= 200 ? "V2" : "V1");
connect(_mavlink, &MAVLinkProtocol::messageReceived, this, &Vehicle::_mavlinkMessageReceived);
connect(_mavlink, &MAVLinkProtocol::mavlinkMessageStatus, this, &Vehicle::_mavlinkMessageStatus);
_addLink(link);
connect(this, &Vehicle::flightModeChanged, this, &Vehicle::_handleFlightModeChanged);
connect(this, &Vehicle::armedChanged, this, &Vehicle::_announceArmedChanged);
connect(_toolbox->multiVehicleManager(), &MultiVehicleManager::parameterReadyVehicleAvailableChanged, this, &Vehicle::_vehicleParamLoaded);
_uas = new UAS(_mavlink, this, _firmwarePluginManager);
connect(_uas, &UAS::imageReady, this, &Vehicle::_imageReady);
connect(this, &Vehicle::remoteControlRSSIChanged, this, &Vehicle::_remoteControlRSSIChanged);
_autopilotPlugin = _firmwarePlugin->autopilotPlugin(this);
// PreArm Error self-destruct timer
connect(&_prearmErrorTimer, &QTimer::timeout, this, &Vehicle::_prearmErrorTimeout);
_prearmErrorTimer.setInterval(_prearmErrorTimeoutMSecs);
_prearmErrorTimer.setSingleShot(true);
// Send MAV_CMD ack timer
_mavCommandAckTimer.setSingleShot(true);
_mavCommandAckTimer.setInterval(_highLatencyLink ? _mavCommandAckTimeoutMSecsHighLatency : _mavCommandAckTimeoutMSecs);
connect(&_mavCommandAckTimer, &QTimer::timeout, this, &Vehicle::_sendMavCommandAgain);
// Chunked status text timeout timer
_chunkedStatusTextTimer.setSingleShot(true);
_chunkedStatusTextTimer.setInterval(1000);
connect(&_chunkedStatusTextTimer, &QTimer::timeout, this, &Vehicle::_chunkedStatusTextTimeout);
connect(_toolbox->uasMessageHandler(), &UASMessageHandler::textMessageCountChanged, this, &Vehicle::_handleTextMessage);
connect(_toolbox->uasMessageHandler(), &UASMessageHandler::textMessageReceived, this, &Vehicle::_handletextMessageReceived);
// MAV_TYPE_GENERIC is used by unit test for creating a vehicle which doesn't do the connect sequence. This
// way we can test the methods that are used within the connect sequence.
if (!qgcApp()->runningUnitTests() || _vehicleType != MAV_TYPE_GENERIC) {
_initialConnectStateMachine->start();
}
_firmwarePlugin->initializeVehicle(this);
for(auto& factName: factNames()) {
_firmwarePlugin->adjustMetaData(vehicleType, getFact(factName)->metaData());
}
_sendMultipleTimer.start(_sendMessageMultipleIntraMessageDelay);
connect(&_sendMultipleTimer, &QTimer::timeout, this, &Vehicle::_sendMessageMultipleNext);
connect(&_orbitTelemetryTimer, &QTimer::timeout, this, &Vehicle::_orbitTelemetryTimeout);
_cameraManager = _firmwarePlugin->createCameraManager(this);
emit cameraManagerChanged();
// Start csv logger
connect(&_csvLogTimer, &QTimer::timeout, this, &Vehicle::_writeCsvLine);
_csvLogTimer.start(1000);
_lastBatteryAnnouncement.start();
// Disconnected Vehicle for offline editing
Vehicle::Vehicle(MAV_AUTOPILOT firmwareType,
MAV_TYPE vehicleType,
FirmwarePluginManager* firmwarePluginManager,
QObject* parent)
: FactGroup(_vehicleUIUpdateRateMSecs, ":/json/Vehicle/VehicleFact.json", parent)
, _id(0)
, _defaultComponentId(MAV_COMP_ID_ALL)
, _firmwareType(firmwareType)
, _vehicleType(vehicleType)
, _firmwarePlugin(nullptr)
, _firmwarePluginInstanceData(nullptr)
, _autopilotPlugin(nullptr)
, _mavlink(nullptr)
, _toolbox(qgcApp()->toolbox())
, _settingsManager(_toolbox->settingsManager())
, _uas(nullptr)
, _mav(nullptr)
, _currentMessageCount(0)
, _messageCount(0)
, _currentErrorCount(0)
, _currentWarningCount(0)
, _currentNormalCount(0)
, _currentMessageType(MessageNone)
, _updateCount(0)
, _onboardControlSensorsPresent(0)
, _onboardControlSensorsEnabled(0)
, _onboardControlSensorsHealth(0)
, _onboardControlSensorsUnhealthy(0)
, _defaultCruiseSpeed(_settingsManager->appSettings()->offlineEditingCruiseSpeed()->rawValue().toDouble())
, _defaultHoverSpeed(_settingsManager->appSettings()->offlineEditingHoverSpeed()->rawValue().toDouble())
, _capabilityBits(MAV_PROTOCOL_CAPABILITY_MISSION_FENCE | MAV_PROTOCOL_CAPABILITY_MISSION_RALLY)
, _receivingAttitudeQuaternion(false)
, _connectionLost(false)
, _connectionLostEnabled(true)
, _missionManager(nullptr)
, _geoFenceManager(nullptr)
, _rallyPointManager(nullptr)
, _airspaceVehicleManager(nullptr)
, _armed(false)
, _base_mode(0)
, _custom_mode(0)
, _nextSendMessageMultipleIndex(0)
, _firmwarePluginManager(firmwarePluginManager)
, _flowImageIndex(0)
, _allLinksInactiveSent(false)
, _messagesReceived(0)
, _messagesSent(0)
, _messagesLost(0)
, _messageSeq(0)
, _compID(0)
, _heardFrom(false)
, _firmwareMajorVersion(versionNotSetValue)
, _firmwareMinorVersion(versionNotSetValue)
, _firmwarePatchVersion(versionNotSetValue)
, _firmwareCustomMajorVersion(versionNotSetValue)
, _firmwareCustomMinorVersion(versionNotSetValue)
, _firmwareCustomPatchVersion(versionNotSetValue)
, _firmwareVersionType(FIRMWARE_VERSION_TYPE_OFFICIAL)
, _lastAnnouncedLowBatteryPercent(100)
, _rollFact (0, _rollFactName, FactMetaData::valueTypeDouble)
, _pitchFact (0, _pitchFactName, FactMetaData::valueTypeDouble)
, _headingFact (0, _headingFactName, FactMetaData::valueTypeDouble)
, _rollRateFact (0, _rollRateFactName, FactMetaData::valueTypeDouble)
, _pitchRateFact (0, _pitchRateFactName, FactMetaData::valueTypeDouble)
, _yawRateFact (0, _yawRateFactName, FactMetaData::valueTypeDouble)
, _groundSpeedFact (0, _groundSpeedFactName, FactMetaData::valueTypeDouble)
, _airSpeedFact (0, _airSpeedFactName, FactMetaData::valueTypeDouble)
, _climbRateFact (0, _climbRateFactName, FactMetaData::valueTypeDouble)
, _altitudeRelativeFact (0, _altitudeRelativeFactName, FactMetaData::valueTypeDouble)
, _altitudeAMSLFact (0, _altitudeAMSLFactName, FactMetaData::valueTypeDouble)
, _flightDistanceFact (0, _flightDistanceFactName, FactMetaData::valueTypeDouble)
, _flightTimeFact (0, _flightTimeFactName, FactMetaData::valueTypeElapsedTimeInSeconds)
, _distanceToHomeFact (0, _distanceToHomeFactName, FactMetaData::valueTypeDouble)
, _missionItemIndexFact (0, _missionItemIndexFactName, FactMetaData::valueTypeUint16)
, _headingToNextWPFact (0, _headingToNextWPFactName, FactMetaData::valueTypeDouble)
, _headingToHomeFact (0, _headingToHomeFactName, FactMetaData::valueTypeDouble)
, _distanceToGCSFact (0, _distanceToGCSFactName, FactMetaData::valueTypeDouble)
, _hobbsFact (0, _hobbsFactName, FactMetaData::valueTypeString)
, _windFactGroup(this)
, _vibrationFactGroup(this)
, _distanceSensorFactGroup(this)
// This will also set the settings based firmware/vehicle types. So it needs to happen first.
if (_firmwareType == MAV_AUTOPILOT_TRACK) {
trackFirmwareVehicleTypeChanges();
}
connect(_settingsManager->appSettings()->offlineEditingCruiseSpeed(), &Fact::rawValueChanged, this, &Vehicle::_offlineCruiseSpeedSettingChanged);
connect(_settingsManager->appSettings()->offlineEditingHoverSpeed(), &Fact::rawValueChanged, this, &Vehicle::_offlineHoverSpeedSettingChanged);
_offlineFirmwareTypeSettingChanged(_firmwareType); // This adds correct terrain capability bit
_firmwarePlugin->initializeVehicle(this);
connect(_settingsManager->appSettings()->offlineEditingFirmwareClass(), &Fact::rawValueChanged, this, &Vehicle::_offlineFirmwareTypeSettingChanged);
connect(_settingsManager->appSettings()->offlineEditingVehicleClass(), &Fact::rawValueChanged, this, &Vehicle::_offlineVehicleTypeSettingChanged);
_offlineFirmwareTypeSettingChanged(_settingsManager->appSettings()->offlineEditingFirmwareClass()->rawValue());
_offlineVehicleTypeSettingChanged(_settingsManager->appSettings()->offlineEditingVehicleClass()->rawValue());
}
void Vehicle::stopTrackingFirmwareVehicleTypeChanges(void)
{
disconnect(_settingsManager->appSettings()->offlineEditingFirmwareClass(), &Fact::rawValueChanged, this, &Vehicle::_offlineFirmwareTypeSettingChanged);
disconnect(_settingsManager->appSettings()->offlineEditingVehicleClass(), &Fact::rawValueChanged, this, &Vehicle::_offlineVehicleTypeSettingChanged);
{
_firmwarePlugin = _firmwarePluginManager->firmwarePluginForAutopilot(_firmwareType, _vehicleType);
connect(_firmwarePlugin, &FirmwarePlugin::toolIndicatorsChanged, this, &Vehicle::toolIndicatorsChanged);
connect(_firmwarePlugin, &FirmwarePlugin::modeIndicatorsChanged, this, &Vehicle::modeIndicatorsChanged);
connect(this, &Vehicle::coordinateChanged, this, &Vehicle::_updateDistanceHeadingToHome);
connect(this, &Vehicle::coordinateChanged, this, &Vehicle::_updateDistanceToGCS);
connect(this, &Vehicle::homePositionChanged, this, &Vehicle::_updateDistanceHeadingToHome);
connect(this, &Vehicle::hobbsMeterChanged, this, &Vehicle::_updateHobbsMeter);
connect(_toolbox->qgcPositionManager(), &QGCPositionManager::gcsPositionChanged, this, &Vehicle::_updateDistanceToGCS);
_missionManager = new MissionManager(this);
connect(_missionManager, &MissionManager::error, this, &Vehicle::_missionManagerError);
connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &Vehicle::_firstMissionLoadComplete);
connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &Vehicle::_clearCameraTriggerPoints);
connect(_missionManager, &MissionManager::sendComplete, this, &Vehicle::_clearCameraTriggerPoints);
connect(_missionManager, &MissionManager::currentIndexChanged, this, &Vehicle::_updateHeadingToNextWP);
connect(_missionManager, &MissionManager::currentIndexChanged, this, &Vehicle::_updateMissionItemIndex);
connect(_missionManager, &MissionManager::sendComplete, _trajectoryPoints, &TrajectoryPoints::clear);
connect(_missionManager, &MissionManager::newMissionItemsAvailable, _trajectoryPoints, &TrajectoryPoints::clear);
_componentInformationManager = new ComponentInformationManager (this);
_initialConnectStateMachine = new InitialConnectStateMachine (this);
_ftpManager = new FTPManager (this);
_parameterManager = new ParameterManager(this);
connect(_parameterManager, &ParameterManager::parametersReadyChanged, this, &Vehicle::_parametersReady);
_objectAvoidance = new VehicleObjectAvoidance(this, this);
// GeoFenceManager needs to access ParameterManager so make sure to create after
_geoFenceManager = new GeoFenceManager(this);
connect(_geoFenceManager, &GeoFenceManager::error, this, &Vehicle::_geoFenceManagerError);
connect(_geoFenceManager, &GeoFenceManager::loadComplete, this, &Vehicle::_firstGeoFenceLoadComplete);
_rallyPointManager = new RallyPointManager(this);
connect(_rallyPointManager, &RallyPointManager::error, this, &Vehicle::_rallyPointManagerError);
connect(_rallyPointManager, &RallyPointManager::loadComplete, this, &Vehicle::_firstRallyPointLoadComplete);
// Flight modes can differ based on advanced mode
connect(_toolbox->corePlugin(), &QGCCorePlugin::showAdvancedUIChanged, this, &Vehicle::flightModesChanged);
// Build FactGroup object model
_addFact(&_rollFact, _rollFactName);
_addFact(&_pitchFact, _pitchFactName);
_addFact(&_headingFact, _headingFactName);
_addFact(&_rollRateFact, _rollRateFactName);
_addFact(&_pitchRateFact, _pitchRateFactName);
_addFact(&_yawRateFact, _yawRateFactName);
_addFact(&_groundSpeedFact, _groundSpeedFactName);
_addFact(&_airSpeedFact, _airSpeedFactName);
_addFact(&_climbRateFact, _climbRateFactName);
_addFact(&_altitudeRelativeFact, _altitudeRelativeFactName);
_addFact(&_altitudeAMSLFact, _altitudeAMSLFactName);
_addFact(&_flightDistanceFact, _flightDistanceFactName);
_addFact(&_flightTimeFact, _flightTimeFactName);
_addFact(&_distanceToHomeFact, _distanceToHomeFactName);
_addFact(&_missionItemIndexFact, _missionItemIndexFactName);
_addFact(&_headingToNextWPFact, _headingToNextWPFactName);
_hobbsFact.setRawValue(QVariant(QString("0000:00:00")));
_addFact(&_hobbsFact, _hobbsFactName);
_addFactGroup(&_gpsFactGroup, _gpsFactGroupName);
_addFactGroup(&_battery1FactGroup, _battery1FactGroupName);
_addFactGroup(&_battery2FactGroup, _battery2FactGroupName);
_addFactGroup(&_windFactGroup, _windFactGroupName);
_addFactGroup(&_vibrationFactGroup, _vibrationFactGroupName);
_addFactGroup(&_temperatureFactGroup, _temperatureFactGroupName);
_addFactGroup(&_clockFactGroup, _clockFactGroupName);
_addFactGroup(&_distanceSensorFactGroup, _distanceSensorFactGroupName);
_addFactGroup(&_estimatorStatusFactGroup, _estimatorStatusFactGroupName);
// Add firmware-specific fact groups, if provided
QMap<QString, FactGroup*>* fwFactGroups = _firmwarePlugin->factGroups();
if (fwFactGroups) {
QMapIterator<QString, FactGroup*> i(*fwFactGroups);
while(i.hasNext()) {
i.next();
_addFactGroup(i.value(), i.key());
}
_flightDistanceFact.setRawValue(0);
_flightTimeUpdater.setInterval(1000);
_flightTimeUpdater.setSingleShot(false);
connect(&_flightTimeUpdater, &QTimer::timeout, this, &Vehicle::_updateFlightTime);
// Set video stream to udp if running ArduSub and Video is disabled
if (sub() && _settingsManager->videoSettings()->videoSource()->rawValue() == VideoSettings::videoDisabled) {
_settingsManager->videoSettings()->videoSource()->setRawValue(VideoSettings::videoSourceUDPH264);
_settingsManager->videoSettings()->lowLatencyMode()->setRawValue(true);
}
//-- Airspace Management
#if defined(QGC_AIRMAP_ENABLED)
AirspaceManager* airspaceManager = _toolbox->airspaceManager();
if (airspaceManager) {
_airspaceVehicleManager = airspaceManager->instantiateVehicle(*this);
if (_airspaceVehicleManager) {
connect(_airspaceVehicleManager, &AirspaceVehicleManager::trafficUpdate, this, &Vehicle::_trafficUpdate);
}
}
#endif
_pidTuningMessages << MAVLINK_MSG_ID_ATTITUDE << MAVLINK_MSG_ID_ATTITUDE_TARGET;
#if defined(QGC_AIRMAP_ENABLED)
if (_airspaceVehicleManager) {
delete _airspaceVehicleManager;
if(_cameraManager) {
// because of _cameraManager QML bindings check for nullptr won't work in the binding pipeline
// the dangling pointer access will cause a runtime fault
void Vehicle::_offlineFirmwareTypeSettingChanged(QVariant varFirmwareType)
_firmwarePlugin = _firmwarePluginManager->firmwarePluginForAutopilot(_firmwareType, _vehicleType);
if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
_capabilityBits |= MAV_PROTOCOL_CAPABILITY_TERRAIN;
} else {
_capabilityBits &= ~MAV_PROTOCOL_CAPABILITY_TERRAIN;
}
emit vehicleTypeChanged();
}
void Vehicle::_offlineCruiseSpeedSettingChanged(QVariant value)
{
_defaultCruiseSpeed = value.toDouble();
emit defaultCruiseSpeedChanged(_defaultCruiseSpeed);
}
void Vehicle::_offlineHoverSpeedSettingChanged(QVariant value)
{
_defaultHoverSpeed = value.toDouble();
emit defaultHoverSpeedChanged(_defaultHoverSpeed);
QString Vehicle::firmwareTypeString() const
{
if (px4Firmware()) {
return QStringLiteral("PX4 Pro");
} else if (apmFirmware()) {
return QStringLiteral("ArduPilot");
} else {
return tr("MAVLink Generic");
}
}
QString Vehicle::vehicleTypeString() const
{
if (fixedWing()) {
return tr("Fixed Wing");
} else if (multiRotor()) {
return tr("Multi-Rotor");
} else if (vtol()) {
return tr("VTOL");
} else if (rover()) {
return tr("Rover");
} else if (sub()) {
return tr("Sub");
} else {
return tr("Unknown");
}
}
void Vehicle::resetCounters()
{
_messagesReceived = 0;
_messagesSent = 0;
_messagesLost = 0;
_messageSeq = 0;
_heardFrom = false;
}
void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t message)
{
// If the link is already running at Mavlink V2 set our max proto version to it.
unsigned mavlinkVersion = _mavlink->getCurrentVersion();
if (_maxProtoVersion != mavlinkVersion && mavlinkVersion >= 200) {
_maxProtoVersion = mavlinkVersion;
qCDebug(VehicleLog) << "Vehicle::_mavlinkMessageReceived Link already running Mavlink v2. Setting _maxProtoVersion" << _maxProtoVersion;
// We allow RADIO_STATUS messages which come from a link the vehicle is using to pass through and be handled
if (!(message.msgid == MAVLINK_MSG_ID_RADIO_STATUS && _containsLink(link))) {
return;
}
if (!_containsLink(link)) {
_addLink(link);
}
//-- Check link status
_messagesReceived++;
emit messagesReceivedChanged();
if(!_heardFrom) {
if(message.msgid == MAVLINK_MSG_ID_HEARTBEAT) {
_heardFrom = true;
_compID = message.compid;
_messageSeq = message.seq + 1;
}
} else {
if(_compID == message.compid) {
uint16_t seq_received = static_cast<uint16_t>(message.seq);
uint16_t packet_lost_count = 0;
//-- Account for overflow during packet loss
if(seq_received < _messageSeq) {
packet_lost_count = (seq_received + 255) - _messageSeq;
} else {
packet_lost_count = seq_received - _messageSeq;
}
_messageSeq = message.seq + 1;
_messagesLost += packet_lost_count;
if(packet_lost_count)
emit messagesLostChanged();
}
}
// Give the plugin a change to adjust the message contents
if (!_firmwarePlugin->adjustIncomingMavlinkMessage(this, &message)) {
return;
}
// Give the Core Plugin access to all mavlink traffic
if (!_toolbox->corePlugin()->mavlinkMessage(this, link, message)) {
return;
}
if (!_terrainProtocolHandler->mavlinkMessageReceived(message)) {
return;
}
case MAVLINK_MSG_ID_HOME_POSITION:
_handleHomePosition(message);
break;
case MAVLINK_MSG_ID_HEARTBEAT:
_handleHeartbeat(message);
break;
case MAVLINK_MSG_ID_RADIO_STATUS:
_handleRadioStatus(message);
break;
case MAVLINK_MSG_ID_RC_CHANNELS:
_handleRCChannels(message);
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:
emit mavlinkRawImu(message);
break;
case MAVLINK_MSG_ID_SCALED_IMU:
emit mavlinkScaledImu1(message);
break;
case MAVLINK_MSG_ID_SCALED_IMU2:
emit mavlinkScaledImu2(message);
break;
case MAVLINK_MSG_ID_SCALED_IMU3:
emit mavlinkScaledImu3(message);
break;
case MAVLINK_MSG_ID_VIBRATION:
_handleVibration(message);
break;
case MAVLINK_MSG_ID_EXTENDED_SYS_STATE:
_handleExtendedSysState(message);
break;
case MAVLINK_MSG_ID_COMMAND_ACK:
_handleCommandAck(message);
break;
Lorenz Meier
committed
case MAVLINK_MSG_ID_COMMAND_LONG:
_handleCommandLong(message);
break;
case MAVLINK_MSG_ID_WIND_COV:
_handleWindCov(message);
break;
case MAVLINK_MSG_ID_LOGGING_DATA:
_handleMavlinkLoggingData(message);
break;
case MAVLINK_MSG_ID_LOGGING_DATA_ACKED:
_handleMavlinkLoggingDataAcked(message);
break;
case MAVLINK_MSG_ID_GPS_RAW_INT:
_handleGpsRawInt(message);
break;
case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
_handleGlobalPositionInt(message);
break;
case MAVLINK_MSG_ID_ALTITUDE:
_handleAltitude(message);
break;
case MAVLINK_MSG_ID_VFR_HUD:
_handleVfrHud(message);
break;
case MAVLINK_MSG_ID_SCALED_PRESSURE:
_handleScaledPressure(message);
break;
case MAVLINK_MSG_ID_SCALED_PRESSURE2:
_handleScaledPressure2(message);
break;
case MAVLINK_MSG_ID_SCALED_PRESSURE3:
_handleScaledPressure3(message);
case MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED:
_handleCameraImageCaptured(message);
case MAVLINK_MSG_ID_ADSB_VEHICLE:
_handleADSBVehicle(message);
break;
case MAVLINK_MSG_ID_HIGH_LATENCY:
_handleHighLatency(message);
break;
case MAVLINK_MSG_ID_HIGH_LATENCY2:
_handleHighLatency2(message);
break;
case MAVLINK_MSG_ID_ATTITUDE:
_handleAttitude(message);
break;
case MAVLINK_MSG_ID_ATTITUDE_QUATERNION:
_handleAttitudeQuaternion(message);
break;
case MAVLINK_MSG_ID_ATTITUDE_TARGET:
_handleAttitudeTarget(message);
break;
case MAVLINK_MSG_ID_DISTANCE_SENSOR:
_handleDistanceSensor(message);
break;
case MAVLINK_MSG_ID_ESTIMATOR_STATUS:
_handleEstimatorStatus(message);
break;
case MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS:
_handleOrbitExecutionStatus(message);
break;
case MAVLINK_MSG_ID_MESSAGE_INTERVAL:
_handleMessageInterval(message);
break;
case MAVLINK_MSG_ID_PING:
_handlePing(link, message);
break;
case MAVLINK_MSG_ID_MOUNT_ORIENTATION:
_handleGimbalOrientation(message);
break;
case MAVLINK_MSG_ID_OBSTACLE_DISTANCE:
_handleObstacleDistance(message);
break;
case MAVLINK_MSG_ID_SERIAL_CONTROL:
{
mavlink_serial_control_t ser;
mavlink_msg_serial_control_decode(&message, &ser);
emit mavlinkSerialControl(ser.device, ser.flags, ser.timeout, ser.baudrate, QByteArray(reinterpret_cast<const char*>(ser.data), ser.count));
}
break;
// Following are ArduPilot dialect messages
Gus Grubba
committed
#if !defined(NO_ARDUPILOT_DIALECT)
case MAVLINK_MSG_ID_CAMERA_FEEDBACK:
_handleCameraFeedback(message);
break;
case MAVLINK_MSG_ID_WIND:
_handleWind(message);
break;
Gus Grubba
committed
#endif
// This must be emitted after the vehicle processes the message. This way the vehicle state is up to date when anyone else
// does processing.
_uas->receiveMessage(message);
}
Gus Grubba
committed
#if !defined(NO_ARDUPILOT_DIALECT)
void Vehicle::_handleCameraFeedback(const mavlink_message_t& message)
{
mavlink_camera_feedback_t feedback;
mavlink_msg_camera_feedback_decode(&message, &feedback);
QGeoCoordinate imageCoordinate((double)feedback.lat / qPow(10.0, 7.0), (double)feedback.lng / qPow(10.0, 7.0), feedback.alt_msl);
qCDebug(VehicleLog) << "_handleCameraFeedback coord:index" << imageCoordinate << feedback.img_idx;
_cameraTriggerPoints.append(new QGCQGeoCoordinate(imageCoordinate, this));
}
Gus Grubba
committed
#endif
void Vehicle::_handleOrbitExecutionStatus(const mavlink_message_t& message)
{
mavlink_orbit_execution_status_t orbitStatus;
mavlink_msg_orbit_execution_status_decode(&message, &orbitStatus);
double newRadius = qAbs(static_cast<double>(orbitStatus.radius));
if (!QGC::fuzzyCompare(_orbitMapCircle.radius()->rawValue().toDouble(), newRadius)) {
_orbitMapCircle.radius()->setRawValue(newRadius);
}
bool newOrbitClockwise = orbitStatus.radius > 0 ? true : false;
if (_orbitMapCircle.clockwiseRotation() != newOrbitClockwise) {
_orbitMapCircle.setClockwiseRotation(newOrbitClockwise);
}
QGeoCoordinate newCenter(static_cast<double>(orbitStatus.x) / qPow(10.0, 7.0), static_cast<double>(orbitStatus.y) / qPow(10.0, 7.0));
if (_orbitMapCircle.center() != newCenter) {
_orbitMapCircle.setCenter(newCenter);
}
if (!_orbitActive) {
_orbitActive = true;
_orbitMapCircle.setShowRotation(true);
emit orbitActiveChanged(true);
}
_orbitTelemetryTimer.start(_orbitTelemetryTimeoutMsecs);
}
void Vehicle::_orbitTelemetryTimeout()
void Vehicle::_handleCameraImageCaptured(const mavlink_message_t& message)
{
mavlink_camera_image_captured_t feedback;
mavlink_msg_camera_image_captured_decode(&message, &feedback);
QGeoCoordinate imageCoordinate((double)feedback.lat / qPow(10.0, 7.0), (double)feedback.lon / qPow(10.0, 7.0), feedback.alt);
qCDebug(VehicleLog) << "_handleCameraFeedback coord:index" << imageCoordinate << feedback.image_index << feedback.capture_result;
if (feedback.capture_result == 1) {
_cameraTriggerPoints.append(new QGCQGeoCoordinate(imageCoordinate, this));
}
}
// Spit out all incomplete chunks
QList<uint8_t> rgCompId = _chunkedStatusTextInfoMap.keys();
for (uint8_t compId : rgCompId) {
_chunkedStatusTextInfoMap[compId].rgMessageChunks.append(QString());
_chunkedStatusTextCompleted(compId);
}
void Vehicle::_chunkedStatusTextCompleted(uint8_t compId)
{
ChunkedStatusTextInfo_t& chunkedInfo = _chunkedStatusTextInfoMap[compId];
uint8_t severity = chunkedInfo.severity;
QStringList& rgChunks = chunkedInfo.rgMessageChunks;
// Build up message from chunks
QString messageText;
for (const QString& chunk : rgChunks) {
if (chunk.isEmpty()) {
// Indicates missing chunk
messageText += tr(" ... ", "Indicates missing chunk from chunked STATUS_TEXT");
} else {
messageText += chunk;
}
}
_chunkedStatusTextInfoMap.remove(compId);
bool px4Prearm = messageText.startsWith(QStringLiteral("preflight"), Qt::CaseInsensitive) && severity >= MAV_SEVERITY_CRITICAL;
// Limit repeated PreArm message to once every 10 seconds
if (_noisySpokenPrearmMap.contains(messageText) && _noisySpokenPrearmMap[messageText].msecsTo(QTime::currentTime()) < (10 * 1000)) {
skipSpoken = true;
} else {
_noisySpokenPrearmMap[messageText] = QTime::currentTime();
setPrearmError(messageText);
}
}
// If the message is NOTIFY or higher severity, or starts with a '#',
// then read it aloud.
bool readAloud = false;
if (messageText.startsWith("#")) {
readAloud = true;
}
else if (severity <= MAV_SEVERITY_NOTICE) {
readAloud = true;
}
if (readAloud) {
if (!skipSpoken) {
qgcApp()->toolbox()->audioOutput()->say(messageText);
}
}
emit textMessageReceived(id(), compId, severity, messageText);
}
void Vehicle::_handleStatusText(mavlink_message_t& message)
{
QByteArray b;
QString messageText;
mavlink_statustext_t statustext;
mavlink_msg_statustext_decode(&message, &statustext);
uint8_t compId = message.compid;
b.resize(MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1);
strncpy(b.data(), statustext.text, MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN);
b[b.length()-1] = '\0';
messageText = QString(b);
bool includesNullTerminator = messageText.length() < MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN;