Browse Source

moved start of timer for sending GCS heartbeat to setToolbox() after _mavlinkProtocol object is initialized. Added check for null on linkConfiguration before use. (#9233)

QGC4.4
Jacob Dahl 4 years ago committed by GitHub
parent
commit
bcd2b281c5
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
  1. 14
      src/Vehicle/MultiVehicleManager.cc

14
src/Vehicle/MultiVehicleManager.cc

@ -41,15 +41,9 @@ MultiVehicleManager::MultiVehicleManager(QGCApplication* app, QGCToolbox* toolbo @@ -41,15 +41,9 @@ MultiVehicleManager::MultiVehicleManager(QGCApplication* app, QGCToolbox* toolbo
, _gcsHeartbeatEnabled(true)
{
QSettings settings;
_gcsHeartbeatEnabled = settings.value(_gcsHeartbeatEnabledKey, true).toBool();
_gcsHeartbeatTimer.setInterval(_gcsHeartbeatRateMSecs);
_gcsHeartbeatTimer.setSingleShot(false);
connect(&_gcsHeartbeatTimer, &QTimer::timeout, this, &MultiVehicleManager::_sendGCSHeartbeat);
if (_gcsHeartbeatEnabled) {
_gcsHeartbeatTimer.start();
}
}
void MultiVehicleManager::setToolbox(QGCToolbox *toolbox)
@ -64,6 +58,11 @@ void MultiVehicleManager::setToolbox(QGCToolbox *toolbox) @@ -64,6 +58,11 @@ void MultiVehicleManager::setToolbox(QGCToolbox *toolbox)
qmlRegisterUncreatableType<MultiVehicleManager>("QGroundControl.MultiVehicleManager", 1, 0, "MultiVehicleManager", "Reference only");
connect(_mavlinkProtocol, &MAVLinkProtocol::vehicleHeartbeatInfo, this, &MultiVehicleManager::_vehicleHeartbeatInfo);
connect(&_gcsHeartbeatTimer, &QTimer::timeout, this, &MultiVehicleManager::_sendGCSHeartbeat);
if (_gcsHeartbeatEnabled) {
_gcsHeartbeatTimer.start();
}
_offlineEditingVehicle = new Vehicle(Vehicle::MAV_AUTOPILOT_TRACK, Vehicle::MAV_TYPE_TRACK, _firmwarePluginManager, this);
}
@ -371,7 +370,8 @@ void MultiVehicleManager::_sendGCSHeartbeat(void) @@ -371,7 +370,8 @@ void MultiVehicleManager::_sendGCSHeartbeat(void)
// Send a heartbeat out on each link
for (int i=0; i<sharedLinks.count(); i++) {
LinkInterface* link = sharedLinks[i].get();
if (link->isConnected() && !link->linkConfiguration()->isHighLatency()) {
auto linkConfiguration = link->linkConfiguration();
if (link->isConnected() && linkConfiguration && !linkConfiguration->isHighLatency()) {
mavlink_message_t message;
mavlink_msg_heartbeat_pack_chan(_mavlinkProtocol->getSystemId(),
_mavlinkProtocol->getComponentId(),

Loading…
Cancel
Save