1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
/****************************************************************************
*
* (c) 2009-2020 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.
*
****************************************************************************/
#pragma once
#include "AirspaceFlightPlanProvider.h"
#include "QGCMAVLink.h"
#include <QObject>
#include <QList>
#include <QGeoCoordinate>
class Vehicle;
//-----------------------------------------------------------------------------
/**
* @class AirspaceVehicleManager
* Base class for per-vehicle management (each vehicle has one (or zero) of these)
*/
class AirspaceVehicleManager : public QObject {
Q_OBJECT
public:
AirspaceVehicleManager (const Vehicle& vehicle);
virtual ~AirspaceVehicleManager () = default;
/**
* Setup the connection and start sending telemetry
*/
virtual void startTelemetryStream () = 0;
virtual void stopTelemetryStream () = 0;
virtual bool isTelemetryStreaming () = 0;
public slots:
virtual void endFlight () = 0;
signals:
void trafficUpdate (bool alert, QString traffic_id, QString vehicle_id, QGeoCoordinate location, float heading);
void flightPermitStatusChanged ();
protected slots:
virtual void vehicleMavlinkMessageReceived(const mavlink_message_t& message) = 0;
protected:
const Vehicle& _vehicle;
private slots:
void _vehicleArmedChanged (bool armed);
private:
bool _vehicleWasInMissionMode = false; ///< true if the vehicle was in mission mode when arming
};