forked from bluerobotics/cockpit
/
types.ts
323 lines (291 loc) · 6.65 KB
/
types.ts
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
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
import Swal from 'sweetalert2'
import type { Type } from '@/libs/connection/m2r/messages/mavlink2rest'
import { MavCmd, MavResult } from '@/libs/connection/m2r/messages/mavlink2rest-enum'
import { AlertLevel } from '@/types/alert'
/**
* Dilution of precision
*/
export interface DOP {
/**
* Horizontal dilution of precision
*/
HDOP?: number
/**
* Vertical dilution of precision
*/
VDOP?: number
/**
* Position (3D) dilution of precision
*/
PDOP?: number
/**
* Time dilution of precision
*/
TDOP?: number
/**
* Geometric dilution of precision
*/
GDOP?: number
}
/**
* 3D precision percentage for each axis
*/
export interface V3Precision {
/**
* X precision between 0-1
*/
x: number
/**
* Y precision between 0-1
*/
y: number
/**
* Z precision between 0-1
*/
z: number
}
type Precision = number | DOP | V3Precision
/**
* Provide coordinates related information
*/
export class Coordinates {
precision: Precision // Percentage between 0 and 1, DOP or 3 axis precision
dop?: DOP // Dilution of precision
altitude: number // Should be in meters
latitude: number // Should be in de decimal degrees. E.g: -27.593500
longitude: number // Should be in de decimal degrees. E.g: -48.558540
/**
* Create object
* @param {Partial<Coordinates>} init
*/
public constructor(init?: Partial<Coordinates>) {
Object.assign(this, init)
}
/**
* Set position
* @param {number} latitude
* @param {number} longitude
* @param {Precision} precision
* @returns {Coordinates}
*/
setPosition(latitude: number, longitude: number, precision?: Precision): Coordinates {
this.latitude = latitude
this.longitude = longitude
if (precision !== undefined) {
if (typeof precision === 'number' && (precision < 0 || precision > 1)) {
console.error(`Can't deal with this type of precision: ${precision}`)
return this
}
this.precision = precision
}
return this
}
/**
* Set altitude information
* @param {number?} altitude
* @returns {Coordinates}
*/
setAltitude(altitude?: number): Coordinates {
if (altitude !== undefined) {
this.altitude = altitude
}
return this
}
}
/**
* Command Acknowledgment
*/
export class CommandAck {
command: Type<MavCmd>
result: Type<MavResult>
progress: number
resultText: string
targetSystem: number
targetComponent: number
/**
* Creates an instance of CommandAck.
* @param {Partial<CommandAck>} [init]
*/
constructor(init?: Partial<CommandAck>) {
Object.assign(this, init)
}
/**
* Alert message
*/
public alertMessage(): void {
if (
this.result.type === MavResult.MAV_RESULT_TEMPORARILY_REJECTED ||
this.result.type === MavResult.MAV_RESULT_DENIED ||
this.result.type === MavResult.MAV_RESULT_UNSUPPORTED ||
this.result.type === MavResult.MAV_RESULT_FAILED
) {
Swal.fire({
title: 'Command Failed',
text: 'Command: ' + this.command.type + ' failed with result: ' + this.result.type,
icon: 'error',
confirmButtonText: 'OK',
})
} else if (this.result.type === MavResult.MAV_RESULT_ACCEPTED) {
Swal.fire({
title: 'Command Accepted',
text: 'Command: ' + this.command.type + ' succeeded with: ' + this.result.type,
icon: 'success',
confirmButtonText: 'OK',
})
} else if (this.result.type === MavResult.MAV_RESULT_IN_PROGRESS) {
Swal.fire({
title: 'Command In Progress',
text: 'Command: ' + this.command.type + ' is in progress',
icon: 'info',
confirmButtonText: 'OK',
})
} else {
Swal.fire({
title: 'Result Unknown',
text: 'Command: ' + this.command.type + ' result is unknown',
icon: 'error',
confirmButtonText: 'OK',
})
}
}
}
/**
* Body frame attitude
*/
export class Attitude {
roll: number
pitch: number
yaw: number
/**
* Create object
* @param {Partial<Attitude>} init
*/
public constructor(init?: Partial<Attitude>) {
Object.assign(this, init)
}
}
/**
* Altitude related data
*/
export class Altitude {
msl: number // Mean Sea Level, in meters
rel: number // Relative altitude, in meters
/**
* Create object
* @param {Partial<Altitude>} init
*/
public constructor(init?: Partial<Altitude>) {
Object.assign(this, init)
}
}
/**
* PowerSupply
*/
export class PowerSupply {
voltage: number | undefined // in Volts
current: number | undefined // in Amps
remaining: number | undefined // Percentage available
}
/**
* Parameter
*/
export class Parameter {
value: number
name: string
}
/**
* Velocity related data
*/
export class Velocity {
x: number // Ground X Speed in m/s (Latitude, positive north)
y: number // Ground Y Speed in m/s (Longitude, positive east)
z: number // Ground Z Speed in m/s (Altitude, positive down)
ground: number // Combined X-Y Speed in m/s (positive north-east)
overall: number // Combined X-Y-Z Speed in m/s (positive north-east-down)
/**
* Create object
* @param {Partial<Velocity>} init
*/
public constructor(init?: Partial<Velocity>) {
Object.assign(this, init)
}
}
/**
* Status message
*/
export class StatusText {
severity: AlertLevel
text: string | undefined
}
/**
* Possible fix types for GPS
*/
export enum FixTypeGPS {
NO_GPS = 'No GPS',
NO_FIX = 'No fix',
FIX_2D = '2D fix',
FIX_3D = '3D fix',
DGPS = 'DGPS fix',
RTK_FLOAT = 'RTK float',
RTK_FIXED = 'RTK fix',
STATIC = 'Static',
PPP = 'PPP fix',
}
/**
* GPS status
*/
export class StatusGPS {
visibleSatellites = 0
fixType = FixTypeGPS.NO_GPS
HDOP: number
VDOP: number
}
/**
* Battery abstraction
*/
export class Battery {
cells: number[] // List of cell voltage in volts
voltage: number // In volts
/**
* Create object
* @param {Partial<Battery>} init
*/
public constructor(init?: Partial<Battery>) {
Object.assign(this, init)
}
/**
* Number of cells in the battery
* @returns {number}
*/
numberOfCells(): number {
return this.cells.length
}
/**
* Update total voltage from cells voltage,
* can be used when the total voltage is not available
*/
updateVoltage(): void {
this.voltage = this.cells.sum()
}
}
/**
* Description for vehicle configuration page
*/
export interface PageDescription {
/**
* Page title
*/
title: string
/**
* Icon
*/
icon: string
/**
* Component
*/
component: any // eslint-disable-line @typescript-eslint/no-explicit-any
}
/**
* Base interface for settings package used to configure a vehicle
*/
export interface VehicleConfigurationSettings {}