MultiVehicleManager.cc 10.3 KB
Newer Older
1
/*=====================================================================
dogmaphobic's avatar
dogmaphobic committed
2

3
 QGroundControl Open Source Ground Control Station
dogmaphobic's avatar
dogmaphobic committed
4

5
 (c) 2009 - 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
dogmaphobic's avatar
dogmaphobic committed
6

7
 This file is part of the QGROUNDCONTROL project
dogmaphobic's avatar
dogmaphobic committed
8

9 10 11 12
 QGROUNDCONTROL is free software: you can redistribute it and/or modify
 it under the terms of the GNU General Public License as published by
 the Free Software Foundation, either version 3 of the License, or
 (at your option) any later version.
dogmaphobic's avatar
dogmaphobic committed
13

14 15 16 17
 QGROUNDCONTROL is distributed in the hope that it will be useful,
 but WITHOUT ANY WARRANTY; without even the implied warranty of
 MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
 GNU General Public License for more details.
dogmaphobic's avatar
dogmaphobic committed
18

19 20
 You should have received a copy of the GNU General Public License
 along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
dogmaphobic's avatar
dogmaphobic committed
21

22 23 24 25 26 27 28
 ======================================================================*/

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

#include "MultiVehicleManager.h"
#include "AutoPilotPlugin.h"
29 30
#include "MAVLinkProtocol.h"
#include "UAS.h"
31
#include "QGCApplication.h"
32

Don Gagne's avatar
Don Gagne committed
33 34
QGC_LOGGING_CATEGORY(MultiVehicleManagerLog, "MultiVehicleManagerLog")

35 36
const char* MultiVehicleManager::_gcsHeartbeatEnabledKey = "gcsHeartbeatEnabled";

37 38
MultiVehicleManager::MultiVehicleManager(QGCApplication* app)
    : QGCTool(app)
39 40 41
    , _activeVehicleAvailable(false)
    , _parameterReadyVehicleAvailable(false)
    , _activeVehicle(NULL)
42 43 44 45
    , _firmwarePluginManager(NULL)
    , _autopilotPluginManager(NULL)
    , _joystickManager(NULL)
    , _mavlinkProtocol(NULL)
46
    , _gcsHeartbeatEnabled(true)
47
{
48 49 50
    QSettings settings;

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

52 53 54 55 56 57
    _gcsHeartbeatTimer.setInterval(_gcsHeartbeatRateMSecs);
    _gcsHeartbeatTimer.setSingleShot(false);
    connect(&_gcsHeartbeatTimer, &QTimer::timeout, this, &MultiVehicleManager::_sendGCSHeartbeat);
    if (_gcsHeartbeatEnabled) {
        _gcsHeartbeatTimer.start();
    }
58 59
}

60
void MultiVehicleManager::setToolbox(QGCToolbox *toolbox)
61
{
62 63 64 65 66 67
   QGCTool::setToolbox(toolbox);

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

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

Don Gagne's avatar
Don Gagne committed
72
   connect(_toolbox->linkManager(), &LinkManager::linkActive, this, &MultiVehicleManager::_linkActive);
73 74
}

Don Gagne's avatar
Don Gagne committed
75
void MultiVehicleManager::_linkActive(LinkInterface* link, int vehicleId, int vehicleFirmwareType, int vehicleType)
76
{
Don Gagne's avatar
Don Gagne committed
77 78 79 80 81 82
    if (!getVehicleById(vehicleId)) {
        qCDebug(MultiVehicleManagerLog) << "Adding new vehicle linkName:vehicleId:vehicleFirmwareType:vehicleType"
                                        << link->getName()
                                        << vehicleId
                                        << vehicleFirmwareType
                                        << vehicleType;
dogmaphobic's avatar
dogmaphobic committed
83

Don Gagne's avatar
Don Gagne committed
84
        Vehicle* vehicle = new Vehicle(link, vehicleId, (MAV_AUTOPILOT)vehicleFirmwareType, (MAV_TYPE)vehicleType, _firmwarePluginManager, _autopilotPluginManager, _joystickManager);
dogmaphobic's avatar
dogmaphobic committed
85

86 87
        if (!vehicle) {
            qWarning() << "New Vehicle allocation failed";
Don Gagne's avatar
Don Gagne committed
88
            return;
89
        }
dogmaphobic's avatar
dogmaphobic committed
90

Don Gagne's avatar
Don Gagne committed
91
        connect(vehicle, &Vehicle::allLinksInactive, this, &MultiVehicleManager::_deleteVehiclePhase1);
92
        connect(vehicle->autopilotPlugin(), &AutoPilotPlugin::parametersReadyChanged, this, &MultiVehicleManager::_autopilotParametersReadyChanged);
93

94
        _vehicles.append(vehicle);
dogmaphobic's avatar
dogmaphobic committed
95

96
        emit vehicleAdded(vehicle);
dogmaphobic's avatar
dogmaphobic committed
97

98 99 100 101 102 103
        setActiveVehicle(vehicle);
    }
}

/// 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.
104
void MultiVehicleManager::_deleteVehiclePhase1(Vehicle* vehicle)
105
{
Don Gagne's avatar
Don Gagne committed
106
    qCDebug(MultiVehicleManagerLog) << "_deleteVehiclePhase1" << vehicle;
Don Gagne's avatar
Don Gagne committed
107

Don Gagne's avatar
Don Gagne committed
108
    _vehiclesBeingDeleted << vehicle;
109 110

    // Remove from map
111 112
    bool found = false;
    for (int i=0; i<_vehicles.count(); i++) {
Don Gagne's avatar
Don Gagne committed
113
        if (_vehicles[i] == vehicle) {
114
            _vehicles.removeAt(i);
115 116 117 118 119 120 121
            found = true;
            break;
        }
    }
    if (!found) {
        qWarning() << "Vehicle not found in map!";
    }
dogmaphobic's avatar
dogmaphobic committed
122

123
    vehicle->setActive(false);
Don Gagne's avatar
Don Gagne committed
124
    vehicle->uas()->shutdownVehicle();
dogmaphobic's avatar
dogmaphobic committed
125

126 127 128 129 130 131
    // 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
132

133 134 135 136 137 138 139 140 141
    // 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
142
void MultiVehicleManager::_deleteVehiclePhase2(void)
143
{
Don Gagne's avatar
Don Gagne committed
144
    qCDebug(MultiVehicleManagerLog) << "_deleteVehiclePhase2" << _vehiclesBeingDeleted[0];
Don Gagne's avatar
Don Gagne committed
145

146 147
    /// 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
148

149
    Vehicle* newActiveVehicle = NULL;
150 151
    if (_vehicles.count()) {
        newActiveVehicle = qobject_cast<Vehicle*>(_vehicles[0]);
152
    }
dogmaphobic's avatar
dogmaphobic committed
153

154 155
    _activeVehicle = newActiveVehicle;
    emit activeVehicleChanged(newActiveVehicle);
dogmaphobic's avatar
dogmaphobic committed
156

157
    if (_activeVehicle) {
158
        _activeVehicle->setActive(true);
159
        emit activeVehicleAvailableChanged(true);
160
        if (_activeVehicle->autopilotPlugin()->parametersReady()) {
161 162 163
            emit parameterReadyVehicleAvailableChanged(true);
        }
    }
dogmaphobic's avatar
dogmaphobic committed
164

Don Gagne's avatar
Don Gagne committed
165 166
    delete _vehiclesBeingDeleted[0];
    _vehiclesBeingDeleted.removeAt(0);
167 168 169 170
}

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

173
    if (vehicle != _activeVehicle) {
Don Gagne's avatar
Don Gagne committed
174
        if (_activeVehicle) {
175
            _activeVehicle->setActive(false);
dogmaphobic's avatar
dogmaphobic committed
176

Don Gagne's avatar
Don Gagne committed
177 178
            // 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
179

Don Gagne's avatar
Don Gagne committed
180 181 182 183 184 185 186
            // 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
187

188 189 190 191 192 193 194 195
        // See explanation in _deleteVehiclePhase1
        _vehicleBeingSetActive = vehicle;
        QTimer::singleShot(20, this, &MultiVehicleManager::_setActiveVehiclePhase2);
    }
}

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

198 199 200
    // Now we signal the new active vehicle
    _activeVehicle = _vehicleBeingSetActive;
    emit activeVehicleChanged(_activeVehicle);
dogmaphobic's avatar
dogmaphobic committed
201

202 203
    // And finally vehicle availability
    if (_activeVehicle) {
204
        _activeVehicle->setActive(true);
205 206
        _activeVehicleAvailable = true;
        emit activeVehicleAvailableChanged(true);
dogmaphobic's avatar
dogmaphobic committed
207

208
        if (_activeVehicle->autopilotPlugin()->parametersReady()) {
209 210 211 212 213 214
            _parameterReadyVehicleAvailable = true;
            emit parameterReadyVehicleAvailableChanged(true);
        }
    }
}

215
void MultiVehicleManager::_autopilotParametersReadyChanged(bool parametersReady)
216 217
{
    AutoPilotPlugin* autopilot = dynamic_cast<AutoPilotPlugin*>(sender());
dogmaphobic's avatar
dogmaphobic committed
218

219 220 221 222
    if (!autopilot) {
        qWarning() << "Dynamic cast failed!";
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
223

Don Gagne's avatar
Don Gagne committed
224
    if (autopilot->vehicle() == _activeVehicle) {
225 226
        _parameterReadyVehicleAvailable = parametersReady;
        emit parameterReadyVehicleAvailableChanged(parametersReady);
227 228 229
    }
}

230 231 232 233 234 235 236 237 238 239 240
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();
}
241 242 243 244 245 246 247 248 249 250 251 252

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;
}
253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287

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,
                                   MAV_TYPE_GCS,                // MAV_TYPE
                                   MAV_AUTOPILOT_INVALID,   // MAV_AUTOPILOT
                                   MAV_MODE_MANUAL_ARMED,   // MAV_MODE
                                   0,                       // custom mode
                                   MAV_STATE_ACTIVE);       // MAV_STATE
        vehicle->sendMessage(message);
    }
}