MultiVehicleManager.cc 11.9 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(MAV_AUTOPILOT_PX4, MAV_TYPE_QUADROTOR, 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 107 108
    // Send QGC heartbeat ASAP, this allows PX4 to start accepting commands
    _sendGCSHeartbeat();

109
    emit vehicleAdded(vehicle);
dogmaphobic's avatar
dogmaphobic committed
110

111
    setActiveVehicle(vehicle);
112

113 114 115
    // Mark link as active
    link->setActive(true);

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

124 125 126 127
}

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

Don Gagne's avatar
Don Gagne committed
132
    _vehiclesBeingDeleted << vehicle;
133 134

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

147
    vehicle->setActive(false);
Don Gagne's avatar
Don Gagne committed
148
    vehicle->uas()->shutdownVehicle();
dogmaphobic's avatar
dogmaphobic committed
149

150 151 152 153 154 155
    // 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
156

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

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

178 179
    /// 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
180

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

186 187
    _activeVehicle = newActiveVehicle;
    emit activeVehicleChanged(newActiveVehicle);
dogmaphobic's avatar
dogmaphobic committed
188

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

Don Gagne's avatar
Don Gagne committed
197 198
    delete _vehiclesBeingDeleted[0];
    _vehiclesBeingDeleted.removeAt(0);
199 200 201 202
}

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

205
    if (vehicle != _activeVehicle) {
Don Gagne's avatar
Don Gagne committed
206
        if (_activeVehicle) {
207
            _activeVehicle->setActive(false);
dogmaphobic's avatar
dogmaphobic committed
208

Don Gagne's avatar
Don Gagne committed
209 210
            // 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
211

Don Gagne's avatar
Don Gagne committed
212 213 214 215 216 217 218
            // 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
219

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

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

230 231 232
    // Now we signal the new active vehicle
    _activeVehicle = _vehicleBeingSetActive;
    emit activeVehicleChanged(_activeVehicle);
dogmaphobic's avatar
dogmaphobic committed
233

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

240
        if (_activeVehicle->autopilotPlugin()->parametersReady()) {
241 242 243 244 245 246
            _parameterReadyVehicleAvailable = true;
            emit parameterReadyVehicleAvailableChanged(true);
        }
    }
}

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

251 252 253 254
    if (!autopilot) {
        qWarning() << "Dynamic cast failed!";
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
255

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

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

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

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,
312
                                   MAV_TYPE_GCS,            // MAV_TYPE
313 314 315 316
                                   MAV_AUTOPILOT_INVALID,   // MAV_AUTOPILOT
                                   MAV_MODE_MANUAL_ARMED,   // MAV_MODE
                                   0,                       // custom mode
                                   MAV_STATE_ACTIVE);       // MAV_STATE
317
        vehicle->sendMessageOnPriorityLink(message);
318 319
    }
}
320 321 322 323 324 325 326 327 328 329 330 331 332 333 334

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