MultiVehicleManager.cc 11.8 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 12 13 14 15

/// @file
///     @author Don Gagne <don@thegagnes.com>

#include "MultiVehicleManager.h"
#include "AutoPilotPlugin.h"
16 17
#include "MAVLinkProtocol.h"
#include "UAS.h"
18
#include "QGCApplication.h"
Jimmy Johnson's avatar
Jimmy Johnson committed
19
#include "FollowMe.h"
20

Don Gagne's avatar
Don Gagne committed
21 22
#ifdef __mobile__
#include "MobileScreenMgr.h"
23 24
#endif

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

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

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

31 32
MultiVehicleManager::MultiVehicleManager(QGCApplication* app)
    : QGCTool(app)
33 34 35
    , _activeVehicleAvailable(false)
    , _parameterReadyVehicleAvailable(false)
    , _activeVehicle(NULL)
Don Gagne's avatar
Don Gagne committed
36
    , _disconnectedVehicle(NULL)
37 38 39 40
    , _firmwarePluginManager(NULL)
    , _autopilotPluginManager(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();
    }
Don Gagne's avatar
Don Gagne committed
53 54

    _disconnectedVehicle = new Vehicle(this);
55 56
}

57
void MultiVehicleManager::setToolbox(QGCToolbox *toolbox)
58
{
59 60 61 62 63 64
   QGCTool::setToolbox(toolbox);

   _firmwarePluginManager =     _toolbox->firmwarePluginManager();
   _autopilotPluginManager =    _toolbox->autopilotPluginManager();
   _joystickManager =           _toolbox->joystickManager();
   _mavlinkProtocol =           _toolbox->mavlinkProtocol();
65

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

69
   connect(_mavlinkProtocol, &MAVLinkProtocol::vehicleHeartbeatInfo, this, &MultiVehicleManager::_vehicleHeartbeatInfo);
70 71
}

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

    qCDebug(MultiVehicleManagerLog()) << "Adding new vehicle link:vehicleId:vehicleMavlinkVersion:vehicleFirmwareType:vehicleType "
                                      << link->getName()
                                      << vehicleId
                                      << vehicleMavlinkVersion
                                      << vehicleFirmwareType
                                      << vehicleType;
dogmaphobic's avatar
dogmaphobic committed
85

86 87 88
    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
89

90 91 92 93 94 95 96 97 98
    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
99

100 101 102
    Vehicle* vehicle = new Vehicle(link, vehicleId, (MAV_AUTOPILOT)vehicleFirmwareType, (MAV_TYPE)vehicleType, _firmwarePluginManager, _autopilotPluginManager, _joystickManager);
    connect(vehicle, &Vehicle::allLinksInactive, this, &MultiVehicleManager::_deleteVehiclePhase1);
    connect(vehicle->autopilotPlugin(), &AutoPilotPlugin::parametersReadyChanged, this, &MultiVehicleManager::_autopilotParametersReadyChanged);
103

104
    _vehicles.append(vehicle);
dogmaphobic's avatar
dogmaphobic committed
105

106
    emit vehicleAdded(vehicle);
dogmaphobic's avatar
dogmaphobic committed
107

108
    setActiveVehicle(vehicle);
109

110 111 112
    // Mark link as active
    link->setActive(true);

Don Gagne's avatar
Don Gagne committed
113
#ifdef __mobile__
114
    if(_vehicles.count() == 1) {
Don Gagne's avatar
Don Gagne committed
115
        //-- Once a vehicle is connected, keep screen from going off
116
        qCDebug(MultiVehicleManagerLog) << "QAndroidJniObject::keepScreenOn";
Don Gagne's avatar
Don Gagne committed
117
        MobileScreenMgr::setKeepScreenOn(true);
118 119 120
    }
#endif

121 122 123 124
}

/// 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.
125
void MultiVehicleManager::_deleteVehiclePhase1(Vehicle* vehicle)
126
{
Don Gagne's avatar
Don Gagne committed
127
    qCDebug(MultiVehicleManagerLog) << "_deleteVehiclePhase1" << vehicle;
Don Gagne's avatar
Don Gagne committed
128

Don Gagne's avatar
Don Gagne committed
129
    _vehiclesBeingDeleted << vehicle;
130 131

    // Remove from map
132 133
    bool found = false;
    for (int i=0; i<_vehicles.count(); i++) {
Don Gagne's avatar
Don Gagne committed
134
        if (_vehicles[i] == vehicle) {
135
            _vehicles.removeAt(i);
136 137 138 139 140 141 142
            found = true;
            break;
        }
    }
    if (!found) {
        qWarning() << "Vehicle not found in map!";
    }
dogmaphobic's avatar
dogmaphobic committed
143

144
    vehicle->setActive(false);
Don Gagne's avatar
Don Gagne committed
145
    vehicle->uas()->shutdownVehicle();
dogmaphobic's avatar
dogmaphobic committed
146

147 148 149 150 151 152
    // 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
153

Don Gagne's avatar
Don Gagne committed
154
#ifdef __mobile__
155
    if(_vehicles.count() == 0) {
Don Gagne's avatar
Don Gagne committed
156
        //-- Once no vehicles are connected, we no longer need to keep screen from going off
157
        qCDebug(MultiVehicleManagerLog) << "QAndroidJniObject::restoreScreenOn";
158
        MobileScreenMgr::setKeepScreenOn(false);
159 160 161
    }
#endif

162 163 164 165 166 167 168 169 170
    // 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
171
void MultiVehicleManager::_deleteVehiclePhase2(void)
172
{
Don Gagne's avatar
Don Gagne committed
173
    qCDebug(MultiVehicleManagerLog) << "_deleteVehiclePhase2" << _vehiclesBeingDeleted[0];
Don Gagne's avatar
Don Gagne committed
174

175 176
    /// 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
177

178
    Vehicle* newActiveVehicle = NULL;
179 180
    if (_vehicles.count()) {
        newActiveVehicle = qobject_cast<Vehicle*>(_vehicles[0]);
181
    }
dogmaphobic's avatar
dogmaphobic committed
182

183 184
    _activeVehicle = newActiveVehicle;
    emit activeVehicleChanged(newActiveVehicle);
dogmaphobic's avatar
dogmaphobic committed
185

186
    if (_activeVehicle) {
187
        _activeVehicle->setActive(true);
188
        emit activeVehicleAvailableChanged(true);
189
        if (_activeVehicle->autopilotPlugin()->parametersReady()) {
190 191 192
            emit parameterReadyVehicleAvailableChanged(true);
        }
    }
dogmaphobic's avatar
dogmaphobic committed
193

Don Gagne's avatar
Don Gagne committed
194 195
    delete _vehiclesBeingDeleted[0];
    _vehiclesBeingDeleted.removeAt(0);
196 197 198 199
}

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

202
    if (vehicle != _activeVehicle) {
Don Gagne's avatar
Don Gagne committed
203
        if (_activeVehicle) {
204
            _activeVehicle->setActive(false);
dogmaphobic's avatar
dogmaphobic committed
205

Don Gagne's avatar
Don Gagne committed
206 207
            // 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
208

Don Gagne's avatar
Don Gagne committed
209 210 211 212 213 214 215
            // 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
216

217 218 219 220 221 222 223 224
        // See explanation in _deleteVehiclePhase1
        _vehicleBeingSetActive = vehicle;
        QTimer::singleShot(20, this, &MultiVehicleManager::_setActiveVehiclePhase2);
    }
}

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

227 228 229
    // Now we signal the new active vehicle
    _activeVehicle = _vehicleBeingSetActive;
    emit activeVehicleChanged(_activeVehicle);
dogmaphobic's avatar
dogmaphobic committed
230

231 232
    // And finally vehicle availability
    if (_activeVehicle) {
233
        _activeVehicle->setActive(true);
234 235
        _activeVehicleAvailable = true;
        emit activeVehicleAvailableChanged(true);
dogmaphobic's avatar
dogmaphobic committed
236

237
        if (_activeVehicle->autopilotPlugin()->parametersReady()) {
238 239 240 241 242 243
            _parameterReadyVehicleAvailable = true;
            emit parameterReadyVehicleAvailableChanged(true);
        }
    }
}

244
void MultiVehicleManager::_autopilotParametersReadyChanged(bool parametersReady)
245 246
{
    AutoPilotPlugin* autopilot = dynamic_cast<AutoPilotPlugin*>(sender());
dogmaphobic's avatar
dogmaphobic committed
247

248 249 250 251
    if (!autopilot) {
        qWarning() << "Dynamic cast failed!";
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
252

Don Gagne's avatar
Don Gagne committed
253
    if (autopilot->vehicle() == _activeVehicle) {
254 255
        _parameterReadyVehicleAvailable = parametersReady;
        emit parameterReadyVehicleAvailableChanged(parametersReady);
256 257 258
    }
}

259 260 261 262 263 264 265 266 267 268 269
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();
}
270 271 272 273 274 275 276 277 278 279 280 281

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;
}
282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308

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)
{
    for (int i=0; i< _vehicles.count(); i++) {
        Vehicle* vehicle = qobject_cast<Vehicle*>(_vehicles[i]);

        mavlink_message_t message;
        mavlink_msg_heartbeat_pack(_mavlinkProtocol->getSystemId(),
                                   _mavlinkProtocol->getComponentId(),
                                   &message,
309
                                   MAV_TYPE_GCS,            // MAV_TYPE
310 311 312 313
                                   MAV_AUTOPILOT_INVALID,   // MAV_AUTOPILOT
                                   MAV_MODE_MANUAL_ARMED,   // MAV_MODE
                                   0,                       // custom mode
                                   MAV_STATE_ACTIVE);       // MAV_STATE
314
        vehicle->sendMessageOnPriorityLink(message);
315 316
    }
}
317 318 319 320 321 322 323 324 325 326 327 328 329 330 331

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