MultiVehicleManager.cc 14.3 KB
Newer Older
1 2 3 4 5 6 7 8
/****************************************************************************
 *
 *   (c) 2009-2016 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.
 *
 ****************************************************************************/
dogmaphobic's avatar
dogmaphobic committed
9

10 11
#include "MultiVehicleManager.h"
#include "AutoPilotPlugin.h"
12 13
#include "MAVLinkProtocol.h"
#include "UAS.h"
14
#include "QGCApplication.h"
Jimmy Johnson's avatar
Jimmy Johnson committed
15
#include "FollowMe.h"
16
#include "QGroundControlQmlGlobal.h"
17
#include "ParameterManager.h"
18
#include "SettingsManager.h"
19 20
#include "QGCCorePlugin.h"
#include "QGCOptions.h"
21

22
#if defined (__ios__) || defined(__android__)
Don Gagne's avatar
Don Gagne committed
23
#include "MobileScreenMgr.h"
24 25
#endif

Don Gagne's avatar
Don Gagne committed
26 27
#include <QQmlEngine>

Don Gagne's avatar
Don Gagne committed
28 29
QGC_LOGGING_CATEGORY(MultiVehicleManagerLog, "MultiVehicleManagerLog")

30
const char* MultiVehicleManager::_gcsHeartbeatEnabledKey = "gcsHeartbeatEnabled";
31

32 33
MultiVehicleManager::MultiVehicleManager(QGCApplication* app, QGCToolbox* toolbox)
    : QGCTool(app, toolbox)
34 35 36
    , _activeVehicleAvailable(false)
    , _parameterReadyVehicleAvailable(false)
    , _activeVehicle(NULL)
37
    , _offlineEditingVehicle(NULL)
38 39 40
    , _firmwarePluginManager(NULL)
    , _joystickManager(NULL)
    , _mavlinkProtocol(NULL)
41
    , _gcsHeartbeatEnabled(true)
42
{
43 44 45
    QSettings settings;

    _gcsHeartbeatEnabled = settings.value(_gcsHeartbeatEnabledKey, true).toBool();
46

47 48 49 50 51 52
    _gcsHeartbeatTimer.setInterval(_gcsHeartbeatRateMSecs);
    _gcsHeartbeatTimer.setSingleShot(false);
    connect(&_gcsHeartbeatTimer, &QTimer::timeout, this, &MultiVehicleManager::_sendGCSHeartbeat);
    if (_gcsHeartbeatEnabled) {
        _gcsHeartbeatTimer.start();
    }
53 54
}

55
void MultiVehicleManager::setToolbox(QGCToolbox *toolbox)
56
{
57
    QGCTool::setToolbox(toolbox);
58

59 60 61
    _firmwarePluginManager =     _toolbox->firmwarePluginManager();
    _joystickManager =           _toolbox->joystickManager();
    _mavlinkProtocol =           _toolbox->mavlinkProtocol();
62

63 64
    QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);
    qmlRegisterUncreatableType<MultiVehicleManager>("QGroundControl.MultiVehicleManager", 1, 0, "MultiVehicleManager", "Reference only");
dogmaphobic's avatar
dogmaphobic committed
65

66
    connect(_mavlinkProtocol, &MAVLinkProtocol::vehicleHeartbeatInfo, this, &MultiVehicleManager::_vehicleHeartbeatInfo);
67

68 69 70 71 72
    SettingsManager* settingsManager = toolbox->settingsManager();
    _offlineEditingVehicle = new Vehicle(static_cast<MAV_AUTOPILOT>(settingsManager->appSettings()->offlineEditingFirmwareType()->rawValue().toInt()),
                                         static_cast<MAV_TYPE>(settingsManager->appSettings()->offlineEditingVehicleType()->rawValue().toInt()),
                                         _firmwarePluginManager,
                                         this);
73 74
}

75
void MultiVehicleManager::_vehicleHeartbeatInfo(LinkInterface* link, int vehicleId, int componentId, int vehicleFirmwareType, int vehicleType)
76
{
77
    if (componentId != MAV_COMP_ID_AUTOPILOT1) {
78 79 80
        // Special case for PX4 Flow
        if (vehicleId != 81 || componentId != 50) {
            // Don't create vehicles for components other than the autopilot
81 82 83 84 85 86
            qCDebug(MultiVehicleManagerLog()) << "Ignoring heartbeat from unknown component "
                                              << link->getName()
                                              << vehicleId
                                              << componentId
                                              << vehicleFirmwareType
                                              << vehicleType;
87
            return;
88 89 90
        }
    }

91 92 93
    if (_vehicles.count() > 0 && !qgcApp()->toolbox()->corePlugin()->options()->multiVehicleEnabled()) {
        return;
    }
94
    if (_ignoreVehicleIds.contains(vehicleId) || getVehicleById(vehicleId) || vehicleId == 0) {
95 96 97
        return;
    }

98 99 100 101 102 103 104 105 106 107 108 109
    switch (vehicleType) {
    case MAV_TYPE_GCS:
    case MAV_TYPE_ONBOARD_CONTROLLER:
    case MAV_TYPE_GIMBAL:
    case MAV_TYPE_ADSB:
        // These are not vehicles, so don't create a vehicle for them
        return;
    default:
        // All other MAV_TYPEs create vehicles
        break;
    }

110
    qCDebug(MultiVehicleManagerLog()) << "Adding new vehicle link:vehicleId:componentId:vehicleFirmwareType:vehicleType "
111 112
                                      << link->getName()
                                      << vehicleId
113
                                      << componentId
114 115
                                      << vehicleFirmwareType
                                      << vehicleType;
dogmaphobic's avatar
dogmaphobic committed
116

117
    if (vehicleId == _mavlinkProtocol->getSystemId()) {
118
        _app->showMessage(tr("Warning: A vehicle is using the same system id as %1: %2").arg(qgcApp()->applicationName()).arg(vehicleId));
119
    }
dogmaphobic's avatar
dogmaphobic committed
120

121
    Vehicle* vehicle = new Vehicle(link, vehicleId, componentId, (MAV_AUTOPILOT)vehicleFirmwareType, (MAV_TYPE)vehicleType, _firmwarePluginManager, _joystickManager);
122
    connect(vehicle, &Vehicle::allLinksInactive, this, &MultiVehicleManager::_deleteVehiclePhase1);
123
    connect(vehicle, &Vehicle::requestProtocolVersion, this, &MultiVehicleManager::_requestProtocolVersion);
124
    connect(vehicle->parameterManager(), &ParameterManager::parametersReadyChanged, this, &MultiVehicleManager::_vehicleParametersReadyChanged);
125

126
    _vehicles.append(vehicle);
dogmaphobic's avatar
dogmaphobic committed
127

128 129 130
    // Send QGC heartbeat ASAP, this allows PX4 to start accepting commands
    _sendGCSHeartbeat();

131 132
    qgcApp()->toolbox()->settingsManager()->appSettings()->defaultFirmwareType()->setRawValue(vehicleFirmwareType);

133
    emit vehicleAdded(vehicle);
dogmaphobic's avatar
dogmaphobic committed
134

135 136 137 138 139
    if (_vehicles.count() > 1) {
        qgcApp()->showMessage(tr("Connected to Vehicle %1").arg(vehicleId));
    } else {
        setActiveVehicle(vehicle);
    }
140

141 142 143
    // Mark link as active
    link->setActive(true);

144
#if defined (__ios__) || defined(__android__)
145
    if(_vehicles.count() == 1) {
Don Gagne's avatar
Don Gagne committed
146
        //-- Once a vehicle is connected, keep screen from going off
147
        qCDebug(MultiVehicleManagerLog) << "QAndroidJniObject::keepScreenOn";
Don Gagne's avatar
Don Gagne committed
148
        MobileScreenMgr::setKeepScreenOn(true);
149 150 151
    }
#endif

152 153
}

154 155 156 157 158 159 160 161 162 163 164 165 166 167 168
/// This slot is connected to the Vehicle::requestProtocolVersion signal such that the vehicle manager
/// tries to switch MAVLink to v2 if all vehicles support it
void MultiVehicleManager::_requestProtocolVersion(unsigned version)
{
    unsigned maxversion = 0;

    if (_vehicles.count() == 0) {
        _mavlinkProtocol->setVersion(version);
        return;
    }

    for (int i=0; i<_vehicles.count(); i++) {

        Vehicle *v = qobject_cast<Vehicle*>(_vehicles[i]);
        if (v && v->maxProtoVersion() > maxversion) {
169
            maxversion = v->maxProtoVersion();
170 171 172 173 174 175 176 177
        }
    }

    if (_mavlinkProtocol->getCurrentVersion() != maxversion) {
        _mavlinkProtocol->setVersion(maxversion);
    }
}

178 179
/// This slot is connected to the Vehicle::allLinksDestroyed signal such that the Vehicle is deleted
/// and all other right things happen when the Vehicle goes away.
180
void MultiVehicleManager::_deleteVehiclePhase1(Vehicle* vehicle)
181
{
Don Gagne's avatar
Don Gagne committed
182
    qCDebug(MultiVehicleManagerLog) << "_deleteVehiclePhase1" << vehicle;
Don Gagne's avatar
Don Gagne committed
183

Don Gagne's avatar
Don Gagne committed
184
    _vehiclesBeingDeleted << vehicle;
185 186

    // Remove from map
187 188
    bool found = false;
    for (int i=0; i<_vehicles.count(); i++) {
Don Gagne's avatar
Don Gagne committed
189
        if (_vehicles[i] == vehicle) {
190
            _vehicles.removeAt(i);
191 192 193 194 195 196 197
            found = true;
            break;
        }
    }
    if (!found) {
        qWarning() << "Vehicle not found in map!";
    }
dogmaphobic's avatar
dogmaphobic committed
198

199
    vehicle->setActive(false);
Don Gagne's avatar
Don Gagne committed
200
    vehicle->uas()->shutdownVehicle();
dogmaphobic's avatar
dogmaphobic committed
201

202 203 204 205 206 207
    // First we must signal that a vehicle is no longer available.
    _activeVehicleAvailable = false;
    _parameterReadyVehicleAvailable = false;
    emit activeVehicleAvailableChanged(false);
    emit parameterReadyVehicleAvailableChanged(false);
    emit vehicleRemoved(vehicle);
208
    vehicle->prepareDelete();
dogmaphobic's avatar
dogmaphobic committed
209

210
#if defined (__ios__) || defined(__android__)
211
    if(_vehicles.count() == 0) {
Don Gagne's avatar
Don Gagne committed
212
        //-- Once no vehicles are connected, we no longer need to keep screen from going off
213
        qCDebug(MultiVehicleManagerLog) << "QAndroidJniObject::restoreScreenOn";
214
        MobileScreenMgr::setKeepScreenOn(false);
215 216 217
    }
#endif

218 219 220 221 222 223 224 225 226
    // We must let the above signals flow through the system as well as get back to the main loop event queue
    // before we can actually delete the Vehicle. The reason is that Qml may be holding on the references to it.
    // Even though the above signals should unload any Qml which has references, that Qml will not be destroyed
    // until we get back to the main loop. So we set a short timer which will then fire after Qt has finished
    // doing all of its internal nastiness to clean up the Qml. This works for both the normal running case
    // as well as the unit testing case whichof course has a different signal flow!
    QTimer::singleShot(20, this, &MultiVehicleManager::_deleteVehiclePhase2);
}

Don Gagne's avatar
Don Gagne committed
227
void MultiVehicleManager::_deleteVehiclePhase2(void)
228
{
Don Gagne's avatar
Don Gagne committed
229
    qCDebug(MultiVehicleManagerLog) << "_deleteVehiclePhase2" << _vehiclesBeingDeleted[0];
Don Gagne's avatar
Don Gagne committed
230

231 232
    /// Qml has been notified of vehicle about to go away and should be disconnected from it by now.
    /// This means we can now clear the active vehicle property and delete the Vehicle for real.
dogmaphobic's avatar
dogmaphobic committed
233

234
    Vehicle* newActiveVehicle = NULL;
235 236
    if (_vehicles.count()) {
        newActiveVehicle = qobject_cast<Vehicle*>(_vehicles[0]);
237
    }
dogmaphobic's avatar
dogmaphobic committed
238

239 240
    _activeVehicle = newActiveVehicle;
    emit activeVehicleChanged(newActiveVehicle);
dogmaphobic's avatar
dogmaphobic committed
241

242
    if (_activeVehicle) {
243
        _activeVehicle->setActive(true);
244
        emit activeVehicleAvailableChanged(true);
245
        if (_activeVehicle->parameterManager()->parametersReady()) {
246 247 248
            emit parameterReadyVehicleAvailableChanged(true);
        }
    }
dogmaphobic's avatar
dogmaphobic committed
249

Don Gagne's avatar
Don Gagne committed
250 251
    delete _vehiclesBeingDeleted[0];
    _vehiclesBeingDeleted.removeAt(0);
252 253 254 255
}

void MultiVehicleManager::setActiveVehicle(Vehicle* vehicle)
{
Don Gagne's avatar
Don Gagne committed
256 257
    qCDebug(MultiVehicleManagerLog) << "setActiveVehicle" << vehicle;

258
    if (vehicle != _activeVehicle) {
Don Gagne's avatar
Don Gagne committed
259
        if (_activeVehicle) {
260
            _activeVehicle->setActive(false);
dogmaphobic's avatar
dogmaphobic committed
261

Don Gagne's avatar
Don Gagne committed
262 263
            // The sequence of signals is very important in order to not leave Qml elements connected
            // to a non-existent vehicle.
dogmaphobic's avatar
dogmaphobic committed
264

Don Gagne's avatar
Don Gagne committed
265 266 267 268 269 270 271
            // First we must signal that there is no active vehicle available. This will disconnect
            // any existing ui from the currently active vehicle.
            _activeVehicleAvailable = false;
            _parameterReadyVehicleAvailable = false;
            emit activeVehicleAvailableChanged(false);
            emit parameterReadyVehicleAvailableChanged(false);
        }
dogmaphobic's avatar
dogmaphobic committed
272

273 274 275 276 277 278 279 280
        // See explanation in _deleteVehiclePhase1
        _vehicleBeingSetActive = vehicle;
        QTimer::singleShot(20, this, &MultiVehicleManager::_setActiveVehiclePhase2);
    }
}

void MultiVehicleManager::_setActiveVehiclePhase2(void)
{
Don Gagne's avatar
Don Gagne committed
281
    qCDebug(MultiVehicleManagerLog) << "_setActiveVehiclePhase2 _vehicleBeingSetActive" << _vehicleBeingSetActive;
Don Gagne's avatar
Don Gagne committed
282

283 284 285
    // Now we signal the new active vehicle
    _activeVehicle = _vehicleBeingSetActive;
    emit activeVehicleChanged(_activeVehicle);
dogmaphobic's avatar
dogmaphobic committed
286

287 288
    // And finally vehicle availability
    if (_activeVehicle) {
289
        _activeVehicle->setActive(true);
290 291
        _activeVehicleAvailable = true;
        emit activeVehicleAvailableChanged(true);
dogmaphobic's avatar
dogmaphobic committed
292

293
        if (_activeVehicle->parameterManager()->parametersReady()) {
294 295 296 297 298 299
            _parameterReadyVehicleAvailable = true;
            emit parameterReadyVehicleAvailableChanged(true);
        }
    }
}

300
void MultiVehicleManager::_vehicleParametersReadyChanged(bool parametersReady)
301
{
302
    ParameterManager* paramMgr = dynamic_cast<ParameterManager*>(sender());
dogmaphobic's avatar
dogmaphobic committed
303

304
    if (!paramMgr) {
305 306 307
        qWarning() << "Dynamic cast failed!";
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
308

309
    if (paramMgr->vehicle() == _activeVehicle) {
310 311
        _parameterReadyVehicleAvailable = parametersReady;
        emit parameterReadyVehicleAvailableChanged(parametersReady);
312 313 314
    }
}

315 316 317 318 319 320 321 322 323 324 325
void MultiVehicleManager::saveSetting(const QString &name, const QString& value)
{
    QSettings settings;
    settings.setValue(name, value);
}

QString MultiVehicleManager::loadSetting(const QString &name, const QString& defaultValue)
{
    QSettings settings;
    return settings.value(name, defaultValue).toString();
}
326 327 328 329 330 331 332 333 334 335 336 337

Vehicle* MultiVehicleManager::getVehicleById(int vehicleId)
{
    for (int i=0; i< _vehicles.count(); i++) {
        Vehicle* vehicle = qobject_cast<Vehicle*>(_vehicles[i]);
        if (vehicle->id() == vehicleId) {
            return vehicle;
        }
    }

    return NULL;
}
338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357

void MultiVehicleManager::setGcsHeartbeatEnabled(bool gcsHeartBeatEnabled)
{
    if (gcsHeartBeatEnabled != _gcsHeartbeatEnabled) {
        _gcsHeartbeatEnabled = gcsHeartBeatEnabled;
        emit gcsHeartBeatEnabledChanged(gcsHeartBeatEnabled);

        QSettings settings;
        settings.setValue(_gcsHeartbeatEnabledKey, gcsHeartBeatEnabled);

        if (gcsHeartBeatEnabled) {
            _gcsHeartbeatTimer.start();
        } else {
            _gcsHeartbeatTimer.stop();
        }
    }
}

void MultiVehicleManager::_sendGCSHeartbeat(void)
{
358
    // Send a heartbeat out on each link
359 360 361
    LinkManager* linkMgr = _toolbox->linkManager();
    for (int i=0; i<linkMgr->links().count(); i++) {
        LinkInterface* link = linkMgr->links()[i];
362
        if (link->isConnected() && !link->highLatency()) {
363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378
            mavlink_message_t message;
            mavlink_msg_heartbeat_pack_chan(_mavlinkProtocol->getSystemId(),
                                            _mavlinkProtocol->getComponentId(),
                                            link->mavlinkChannel(),
                                            &message,
                                            MAV_TYPE_GCS,            // MAV_TYPE
                                            MAV_AUTOPILOT_INVALID,   // MAV_AUTOPILOT
                                            MAV_MODE_MANUAL_ARMED,   // MAV_MODE
                                            0,                       // custom mode
                                            MAV_STATE_ACTIVE);       // MAV_STATE

            uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
            int len = mavlink_msg_to_send_buffer(buffer, &message);

            link->writeBytesSafe((const char*)buffer, len);
        }
379 380
    }
}
381 382 383 384 385 386 387 388 389 390 391 392 393 394 395

bool MultiVehicleManager::linkInUse(LinkInterface* link, Vehicle* skipVehicle)
{
    for (int i=0; i< _vehicles.count(); i++) {
        Vehicle* vehicle = qobject_cast<Vehicle*>(_vehicles[i]);

        if (vehicle != skipVehicle) {
            if (vehicle->containsLink(link)) {
                return true;
            }
        }
    }

    return false;
}