-
Notifications
You must be signed in to change notification settings - Fork 2
/
Copy pathUASManager1.h
287 lines (240 loc) · 9.41 KB
/
UASManager1.h
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
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
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
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009 - 2011 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
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.
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.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
* @file
* @brief Definition of class UASManager
* @author Lorenz Meier <[email protected]>
*
*/
#ifndef _UASMANAGER_H_
#define _UASMANAGER_H_
#include <QThread>
#include <QList>
#include <QMutex>
#include "UASInterface1.h"
#include "libs/eigen/Eigen/Eigen"
#include "QGCGeo.h"
/**
* @brief Central manager for all connected aerial vehicles
*
* This class keeps a list of all connected / configured UASs. It also stores which
* UAS is currently select with respect to user input or manual controls.
**/
class UASManager : public QObject
{
Q_OBJECT
public:
static UASManager* instance();
~UASManager();
/**
* @brief Get the currently selected UAS
*
* @return NULL pointer if no UAS exists, active UAS else
**/
UASInterface* getActiveUAS();
UASInterface* silentGetActiveUAS();
/**
* @brief Get the UAS with this id
*
* Although not enforced by this implementation, the IDs are constrained to be
* in the range of 1 - 127 by the MAVLINK protocol.
*
* @param id unique system / aircraft id
* @return UAS with the given ID, NULL pointer else
**/
UASInterface* getUASForId(int id);
QList<UASInterface*> getUASList();
/** @brief Get home position latitude */
double getHomeLatitude() const {
return homeLat;
}
/** @brief Get home position longitude */
double getHomeLongitude() const {
return homeLon;
}
/** @brief Get home position altitude */
double getHomeAltitude() const {
return homeAlt;
}
/** @brief Get the home position coordinate frame */
int getHomeFrame() const
{
return homeFrame;
}
/** @brief Convert WGS84 coordinates to earth centric frame */
Eigen::Vector3d wgs84ToEcef(const double & latitude, const double & longitude, const double & altitude);
/** @brief Convert earth centric frame to EAST-NORTH-UP frame (x-y-z directions */
Eigen::Vector3d ecefToEnu(const Eigen::Vector3d & ecef);
/** @brief Convert WGS84 lat/lon coordinates to carthesian coordinates with home position as origin */
void wgs84ToEnu(const double& lat, const double& lon, const double& alt, double* east, double* north, double* up);
/** @brief Convert x,y,z coordinates to lat / lon / alt coordinates in east-north-up frame */
void enuToWgs84(const double& x, const double& y, const double& z, double* lat, double* lon, double* alt);
/** @brief Convert x,y,z coordinates to lat / lon / alt coordinates in north-east-down frame */
void nedToWgs84(const double& x, const double& y, const double& z, double* lat, double* lon, double* alt);
void getLocalNEDSafetyLimits(double* x1, double* y1, double* z1, double* x2, double* y2, double* z2)
{
*x1 = nedSafetyLimitPosition1.x();
*y1 = nedSafetyLimitPosition1.y();
*z1 = nedSafetyLimitPosition1.z();
*x2 = nedSafetyLimitPosition2.x();
*y2 = nedSafetyLimitPosition2.y();
*z2 = nedSafetyLimitPosition2.z();
}
/** @brief Check if a position is in the local NED safety limits */
bool isInLocalNEDSafetyLimits(double x, double y, double z)
{
if (x < nedSafetyLimitPosition1.x() &&
y > nedSafetyLimitPosition1.y() &&
z < nedSafetyLimitPosition1.z() &&
x > nedSafetyLimitPosition2.x() &&
y < nedSafetyLimitPosition2.y() &&
z > nedSafetyLimitPosition2.z())
{
// Within limits
return true;
}
else
{
// Not within limits
return false;
}
}
// void wgs84ToNed(const double& lat, const double& lon, const double& alt, double* north, double* east, double* down);
public slots:
/**
* @brief Add a new UAS to the list
*
* This command will only be executed if this UAS does not yet exist.
* @param UAS unmanned air system to add
**/
void addUAS(UASInterface* UAS);
/** @brief Remove a system from the list */
void removeUAS(UASInterface* uas);
void removeUAS(QObject* uas);
/**
* @brief Set a UAS as currently selected
*
* @param UAS Unmanned Air System to set
**/
void setActiveUAS(UASInterface* UAS);
/**
* @brief Launch the active UAS
*
* The groundstation has always one Unmanned Air System selected.
* All commands are executed on the UAS in focus. This command starts
* the launch sequence.
*
* @return True if the UAS could be launched, false else
*/
bool launchActiveUAS();
bool haltActiveUAS();
bool continueActiveUAS();
/**
* @brief Land the active UAS
*
* The groundstation has always one Unmanned Air System selected.
* All commands are executed on the UAS in focus. This command starts
* the land sequence. Depending on the onboard control, this could mean
* returning to the landing spot as well as descending on the current
* position.
*
* @return True if the UAS could be landed, false else
*/
bool returnActiveUAS();
/**
* @brief EMERGENCY: Stop active UAS
*
* The groundstation has always one Unmanned Air System selected.
* All commands are executed on the UAS in focus. This command
* starts an emergency landing. Depending on the onboard control,
* this usually means descending rapidly on the current position.
*
* @warning This command can severely damage the UAS!
*
* @return True if the UAS could be landed, false else
*/
bool stopActiveUAS();
/**
* @brief EMERGENCY: Kill active UAS
*
* The groundstation has always one Unmanned Air System selected.
* All commands are executed on the UAS in focus. This command
* shuts off all onboard motors immediately. This leads to a
* system crash, but might prevent external damage, e.g. to people.
* This command is secured by an additional popup message window.
*
* @warning THIS COMMAND RESULTS IN THE LOSS OF THE SYSTEM!
*
* @return True if the UAS could be landed, false else
*/
bool killActiveUAS();
/**
* @brief Configure the currently active UAS
*
* This command will bring up the configuration dialog for the particular UAS.
*/
void configureActiveUAS();
/** @brief Shut down the onboard operating system down */
bool shutdownActiveUAS();
/** @brief Set the current home position on all UAVs*/
bool setHomePosition(double lat, double lon, double alt);
/** @brief Set the safety limits in local position frame */
void setLocalNEDSafetyBorders(double x1, double y1, double z1, double x2, double y2, double z2);
/** @brief Update home position based on the position from one of the UAVs */
void uavChangedHomePosition(int uav, double lat, double lon, double alt);
/** @brief Load settings */
void loadSettings();
/** @brief Store settings */
void storeSettings();
protected:
UASManager();
QList<UASInterface*> systems;
UASInterface* activeUAS;
QMutex activeUASMutex;
double homeLat;
double homeLon;
double homeAlt;
int homeFrame;
Eigen::Quaterniond ecef_ref_orientation_;
Eigen::Vector3d ecef_ref_point_;
Eigen::Vector3d nedSafetyLimitPosition1;
Eigen::Vector3d nedSafetyLimitPosition2;
void initReference(const double & latitude, const double & longitude, const double & altitude);
signals:
/** A new system was created */
void UASCreated(UASInterface* UAS);
/** A system was deleted */
void UASDeleted(UASInterface* UAS);
/** @brief The UAS currently under main operator control changed */
void activeUASSet(UASInterface* UAS);
/** @brief The UAS currently under main operator control changed */
void activeUASSet(int systemId);
/** @brief The UAS currently under main operator control changed */
void activeUASSetListIndex(int listIndex);
/** @brief The UAS currently under main operator control changed */
void activeUASStatusChanged(UASInterface* UAS, bool active);
/** @brief The UAS currently under main operator control changed */
void activeUASStatusChanged(int systemId, bool active);
/** @brief Current home position changed */
void homePositionChanged(double lat, double lon, double alt);
public:
/* Need to align struct pointer to prevent a memory assertion:
* See http://eigen.tuxfamily.org/dox-devel/TopicUnalignedArrayAssert.html
* for details
*/
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
};
#endif // _UASMANAGER_H_