MultiVehicleManager.cc 13.2 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
#if defined (__ios__) || defined(__android__)
Don Gagne's avatar
Don Gagne committed
21
#include "MobileScreenMgr.h"
22 23
#endif

Don Gagne's avatar
Don Gagne committed
24 25
#include <QQmlEngine>

Don Gagne's avatar
Don Gagne committed
26 27
QGC_LOGGING_CATEGORY(MultiVehicleManagerLog, "MultiVehicleManagerLog")

28
const char* MultiVehicleManager::_gcsHeartbeatEnabledKey = "gcsHeartbeatEnabled";
29

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

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

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

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

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

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

64
   connect(_mavlinkProtocol, &MAVLinkProtocol::vehicleHeartbeatInfo, this, &MultiVehicleManager::_vehicleHeartbeatInfo);
65

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

73
void MultiVehicleManager::_vehicleHeartbeatInfo(LinkInterface* link, int vehicleId, int componentId, int vehicleMavlinkVersion, int vehicleFirmwareType, int vehicleType)
74
{
75
    if (_ignoreVehicleIds.contains(vehicleId) || getVehicleById(vehicleId) || vehicleId == 0) {
76 77 78
        return;
    }

79 80 81 82 83 84 85 86 87 88 89 90
    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;
    }

91
    qCDebug(MultiVehicleManagerLog()) << "Adding new vehicle link:vehicleId:componentId:vehicleMavlinkVersion:vehicleFirmwareType:vehicleType "
92 93
                                      << link->getName()
                                      << vehicleId
94
                                      << componentId
95 96 97
                                      << vehicleMavlinkVersion
                                      << vehicleFirmwareType
                                      << vehicleType;
dogmaphobic's avatar
dogmaphobic committed
98

99 100 101
    if (vehicleId == _mavlinkProtocol->getSystemId()) {
        _app->showMessage(QString("Warning: A vehicle is using the same system id as QGroundControl: %1").arg(vehicleId));
    }
dogmaphobic's avatar
dogmaphobic committed
102

103 104 105 106 107 108 109 110 111
//    QSettings settings;
//    bool mavlinkVersionCheck = settings.value("VERSION_CHECK_ENABLED", true).toBool();
//    if (mavlinkVersionCheck && vehicleMavlinkVersion != MAVLINK_VERSION) {
//        _ignoreVehicleIds += vehicleId;
//        _app->showMessage(QString("The MAVLink protocol version on vehicle #%1 and QGroundControl differ! "
//                                  "It is unsafe to use different MAVLink versions. "
//                                  "QGroundControl therefore refuses to connect to vehicle #%1, which sends MAVLink version %2 (QGroundControl uses version %3).").arg(vehicleId).arg(vehicleMavlinkVersion).arg(MAVLINK_VERSION));
//        return;
//    }
dogmaphobic's avatar
dogmaphobic committed
112

113
    Vehicle* vehicle = new Vehicle(link, vehicleId, componentId, (MAV_AUTOPILOT)vehicleFirmwareType, (MAV_TYPE)vehicleType, _firmwarePluginManager, _joystickManager);
114
    connect(vehicle, &Vehicle::allLinksInactive, this, &MultiVehicleManager::_deleteVehiclePhase1);
115
    connect(vehicle->parameterManager(), &ParameterManager::parametersReadyChanged, this, &MultiVehicleManager::_vehicleParametersReadyChanged);
116

117
    _vehicles.append(vehicle);
dogmaphobic's avatar
dogmaphobic committed
118

119 120 121
    // Send QGC heartbeat ASAP, this allows PX4 to start accepting commands
    _sendGCSHeartbeat();

122
    emit vehicleAdded(vehicle);
dogmaphobic's avatar
dogmaphobic committed
123

124 125 126 127 128
    if (_vehicles.count() > 1) {
        qgcApp()->showMessage(tr("Connected to Vehicle %1").arg(vehicleId));
    } else {
        setActiveVehicle(vehicle);
    }
129

130 131 132
    // Mark link as active
    link->setActive(true);

133
#if defined (__ios__) || defined(__android__)
134
    if(_vehicles.count() == 1) {
Don Gagne's avatar
Don Gagne committed
135
        //-- Once a vehicle is connected, keep screen from going off
136
        qCDebug(MultiVehicleManagerLog) << "QAndroidJniObject::keepScreenOn";
Don Gagne's avatar
Don Gagne committed
137
        MobileScreenMgr::setKeepScreenOn(true);
138 139 140
    }
#endif

141 142 143 144
}

/// 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.
145
void MultiVehicleManager::_deleteVehiclePhase1(Vehicle* vehicle)
146
{
Don Gagne's avatar
Don Gagne committed
147
    qCDebug(MultiVehicleManagerLog) << "_deleteVehiclePhase1" << vehicle;
Don Gagne's avatar
Don Gagne committed
148

Don Gagne's avatar
Don Gagne committed
149
    _vehiclesBeingDeleted << vehicle;
150 151

    // Remove from map
152 153
    bool found = false;
    for (int i=0; i<_vehicles.count(); i++) {
Don Gagne's avatar
Don Gagne committed
154
        if (_vehicles[i] == vehicle) {
155
            _vehicles.removeAt(i);
156 157 158 159 160 161 162
            found = true;
            break;
        }
    }
    if (!found) {
        qWarning() << "Vehicle not found in map!";
    }
dogmaphobic's avatar
dogmaphobic committed
163

164
    vehicle->setActive(false);
Don Gagne's avatar
Don Gagne committed
165
    vehicle->uas()->shutdownVehicle();
dogmaphobic's avatar
dogmaphobic committed
166

167 168 169 170 171 172
    // First we must signal that a vehicle is no longer available.
    _activeVehicleAvailable = false;
    _parameterReadyVehicleAvailable = false;
    emit activeVehicleAvailableChanged(false);
    emit parameterReadyVehicleAvailableChanged(false);
    emit vehicleRemoved(vehicle);
dogmaphobic's avatar
dogmaphobic committed
173

174
#if defined (__ios__) || defined(__android__)
175
    if(_vehicles.count() == 0) {
Don Gagne's avatar
Don Gagne committed
176
        //-- Once no vehicles are connected, we no longer need to keep screen from going off
177
        qCDebug(MultiVehicleManagerLog) << "QAndroidJniObject::restoreScreenOn";
178
        MobileScreenMgr::setKeepScreenOn(false);
179 180 181
    }
#endif

182 183 184 185 186 187 188 189 190
    // 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
191
void MultiVehicleManager::_deleteVehiclePhase2(void)
192
{
Don Gagne's avatar
Don Gagne committed
193
    qCDebug(MultiVehicleManagerLog) << "_deleteVehiclePhase2" << _vehiclesBeingDeleted[0];
Don Gagne's avatar
Don Gagne committed
194

195 196
    /// 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
197

198
    Vehicle* newActiveVehicle = NULL;
199 200
    if (_vehicles.count()) {
        newActiveVehicle = qobject_cast<Vehicle*>(_vehicles[0]);
201
    }
dogmaphobic's avatar
dogmaphobic committed
202

203 204
    _activeVehicle = newActiveVehicle;
    emit activeVehicleChanged(newActiveVehicle);
dogmaphobic's avatar
dogmaphobic committed
205

206
    if (_activeVehicle) {
207
        _activeVehicle->setActive(true);
208
        emit activeVehicleAvailableChanged(true);
209
        if (_activeVehicle->parameterManager()->parametersReady()) {
210 211 212
            emit parameterReadyVehicleAvailableChanged(true);
        }
    }
dogmaphobic's avatar
dogmaphobic committed
213

Don Gagne's avatar
Don Gagne committed
214 215
    delete _vehiclesBeingDeleted[0];
    _vehiclesBeingDeleted.removeAt(0);
216 217 218 219
}

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

222
    if (vehicle != _activeVehicle) {
Don Gagne's avatar
Don Gagne committed
223
        if (_activeVehicle) {
224
            _activeVehicle->setActive(false);
dogmaphobic's avatar
dogmaphobic committed
225

Don Gagne's avatar
Don Gagne committed
226 227
            // 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
228

Don Gagne's avatar
Don Gagne committed
229 230 231 232 233 234 235
            // 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
236

237 238 239 240 241 242 243 244
        // See explanation in _deleteVehiclePhase1
        _vehicleBeingSetActive = vehicle;
        QTimer::singleShot(20, this, &MultiVehicleManager::_setActiveVehiclePhase2);
    }
}

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

247 248 249
    // Now we signal the new active vehicle
    _activeVehicle = _vehicleBeingSetActive;
    emit activeVehicleChanged(_activeVehicle);
dogmaphobic's avatar
dogmaphobic committed
250

251 252
    // And finally vehicle availability
    if (_activeVehicle) {
253
        _activeVehicle->setActive(true);
254 255
        _activeVehicleAvailable = true;
        emit activeVehicleAvailableChanged(true);
dogmaphobic's avatar
dogmaphobic committed
256

257
        if (_activeVehicle->parameterManager()->parametersReady()) {
258 259 260 261 262 263
            _parameterReadyVehicleAvailable = true;
            emit parameterReadyVehicleAvailableChanged(true);
        }
    }
}

264
void MultiVehicleManager::_vehicleParametersReadyChanged(bool parametersReady)
265
{
266
    ParameterManager* paramMgr = dynamic_cast<ParameterManager*>(sender());
dogmaphobic's avatar
dogmaphobic committed
267

268
    if (!paramMgr) {
269 270 271
        qWarning() << "Dynamic cast failed!";
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
272

273
    if (paramMgr->vehicle() == _activeVehicle) {
274 275
        _parameterReadyVehicleAvailable = parametersReady;
        emit parameterReadyVehicleAvailableChanged(parametersReady);
276 277 278
    }
}

279 280 281 282 283 284 285 286 287 288 289
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();
}
290 291 292 293 294 295 296 297 298 299 300 301

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;
}
302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321

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)
{
322
    // Send a heartbeat out on each link
323 324 325
    LinkManager* linkMgr = _toolbox->linkManager();
    for (int i=0; i<linkMgr->links().count(); i++) {
        LinkInterface* link = linkMgr->links()[i];
326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341 342
        if (link->isConnected()) {
            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);
        }
343 344
    }
}
345 346 347 348 349 350 351 352 353 354 355 356 357 358 359

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;
}