• Home
  • Features
  • Pricing
  • Docs
  • Announcements
  • Sign In

stephendade / Rpanion-server / 15678546196

16 Jun 2025 10:38AM UTC coverage: 35.894% (+0.2%) from 35.71%
15678546196

Pull #288

github

web-flow
Merge 706cb0516 into c16840c55
Pull Request #288: Deb packaging

272 of 996 branches covered (27.31%)

Branch coverage included in aggregate %.

35 of 155 new or added lines in 12 files covered. (22.58%)

19 existing lines in 10 files now uncovered.

896 of 2258 relevant lines covered (39.68%)

2.6 hits per line

Source File
Press 'n' to go to next uncovered line, 'b' for previous

57.4
/server/flightController.js
1
const { autoDetect } = require('@serialport/bindings-cpp')
3✔
2
const fs = require('fs')
3✔
3
const events = require('events')
3✔
4
const path = require('path')
3✔
5
const appRoot = require('app-root-path')
3✔
6
const { spawn, spawnSync } = require('child_process')
3✔
7
const si = require('systeminformation')
3✔
8

9
const mavManager = require('../mavlink/mavManager.js')
3✔
10
const logpaths = require('./paths.js')
3✔
11

12
function isPi () {
13
  let cpuInfo = ''
3✔
14
  try {
3✔
15
    cpuInfo = fs.readFileSync('/proc/device-tree/compatible', { encoding: 'utf8' })
3✔
16
  } catch (e) {
17
    // if this fails, this is probably not a pi
18
    return false
3✔
19
  }
20

21
  const model = cpuInfo
×
22
    .split(',')
23
    .filter(line => line.length > 0)
×
24

25
  if (!model || model.length === 0) {
×
26
    return false
×
27
  }
28

29
  return model[0] === 'raspberrypi'
×
30
}
31

32
class FCDetails {
33
  constructor (settings) {
34
    // if the device was successfully opend and got packets
35
    this.previousConnection = false
15✔
36

37
    // all detected serial ports and baud rates
38
    this.serialDevices = []
15✔
39
    this.baudRates = [{ value: 9600, label: '9600' },
15✔
40
      { value: 19200, label: '19200' },
41
      { value: 38400, label: '38400' },
42
      { value: 57600, label: '57600' },
43
      { value: 111100, label: '111100' },
44
      { value: 115200, label: '115200' },
45
      { value: 230400, label: '230400' },
46
      { value: 256000, label: '256000' },
47
      { value: 460800, label: '460800' },
48
      { value: 500000, label: '500000' },
49
      { value: 921600, label: '921600' },
50
      { value: 1500000, label: '1500000' }]
51
    this.mavlinkVersions = [{ value: 1, label: '1.0' },
15✔
52
      { value: 2, label: '2.0' }]
53
    // JSON of active device (port and baud and mavversion). User selected
54
    // null if user selected no link (or no serial port of that name)
55
    this.activeDevice = null
15✔
56

57
    // mavlink-router process
58
    this.router = null
15✔
59

60
    // the mavlink manager object
61
    this.m = null
15✔
62

63
    // For sending events outside of object
64
    this.eventEmitter = new events.EventEmitter()
15✔
65

66
    // Interval to check connection status and re-connect
67
    // if required
68
    this.intervalObj = null
15✔
69

70
    // UDP Outputs
71
    this.UDPoutputs = []
15✔
72

73
    // Send out MAVLink heartbeat packets?
74
    this.enableHeartbeat = false
15✔
75
  
76
    // Use TCP output?
77
    this.enableTCP = false
15✔
78

79
    // Use UDP Broadcast?
80
    this.enableUDPB = true
15✔
81
    this.UDPBPort = 14550
15✔
82

83
    // Send datastream requests to flight controller?
84
    this.enableDSRequest = false
15✔
85

86
    // Current binlog via mavlink-router
87
    this.binlog = null
15✔
88

89
    this.tlogging = false
15✔
90

91
    // load settings
92
    this.settings = settings
15✔
93
    this.activeDevice = this.settings.value('flightcontroller.activeDevice', null)
15✔
94
    this.UDPoutputs = this.settings.value('flightcontroller.outputs', [])
15✔
95
    this.enableHeartbeat = this.settings.value('flightcontroller.enableHeartbeat', false)
15✔
96
    this.enableTCP = this.settings.value('flightcontroller.enableTCP', false)
15✔
97
    this.enableUDPB = this.settings.value('flightcontroller.enableUDPB', true)
15✔
98
    this.UDPBPort = this.settings.value('flightcontroller.UDPBPort', 14550)
15✔
99
    this.enableDSRequest = this.settings.value('flightcontroller.enableDSRequest', false)
15✔
100
    this.tlogging = this.settings.value('flightcontroller.tlogging', false)
15✔
101

102
    if (this.activeDevice !== null) {
15!
103
      // restart link if saved serial device is found
104
      let found = false
×
105
      this.getSerialDevices((err, devices) => {
×
106
        for (let i = 0, len = devices.length; i < len; i++) {
×
107
          if (this.activeDevice.serial.value === devices[i].value) {
×
108
            found = true
×
109
            this.startLink((err) => {
×
110
              if (err) {
×
111
                console.log("Can't open found FC " + this.activeDevice.serial.value + ', resetting link')
×
112
                this.activeDevice = null
×
113
              }
114
              this.startInterval()
×
115
            })
116
            break
×
117
          }
118
        }
119
        if (!found) {
×
120
          console.log("Can't find saved FC, resetting")
×
121
          this.activeDevice = null
×
122
        }
123
      })
124
    }
125
  }
126

127
  validMavlinkRouter () {
128
    // check mavlink-router is installed
129
    const ls = spawnSync('which', ['mavlink-routerd'])
3✔
130
    console.log(ls.stdout.toString())
3✔
131
    if (ls.stdout.toString().trim() == '') {
3!
132
      return false
×
133
    } else {
134
      return true
3✔
135
    }
136
  }
137

138
  isModemManagerInstalled () {
139
    // check ModemManager is installed
140
    const ls = spawnSync('which', ['ModemManager'])
3✔
141
    console.log(ls.stdout.toString())
3✔
142
    if (ls.stdout.toString().includes('ModemManager')) {
3!
143
      return true
×
144
    } else {
145
      return false
3✔
146
    }
147
  }
148

149
  getUDPOutputs () {
150
    // get list of current UDP outputs
151
    const ret = []
33✔
152
    for (let i = 0, len = this.UDPoutputs.length; i < len; i++) {
33✔
153
      ret.push({ IPPort: this.UDPoutputs[i].IP + ':' + this.UDPoutputs[i].port })
36✔
154
    }
155
    return ret
33✔
156
  }
157

158
  addUDPOutput (newIP, newPort) {
159
    // add a new udp output, if not already in
160
    // check if this ip:port is already in the list
161
    for (let i = 0, len = this.UDPoutputs.length; i < len; i++) {
9✔
162
      if (this.UDPoutputs[i].IP === newIP && this.UDPoutputs[i].port === newPort) {
6✔
163
        return this.getUDPOutputs()
3✔
164
      }
165
    }
166

167
    // check that it's not the internal 127.0.0.1:14540
168
    if (newIP === '127.0.0.1' && newPort === 14540) {
6!
169
      return this.getUDPOutputs()
×
170
    }
171

172
    // add it in
173
    this.UDPoutputs.push({ IP: newIP, port: newPort })
6✔
174
    console.log('Added UDP Output ' + newIP + ':' + newPort)
6✔
175

176
    // restart mavlink-router, if link active
177
    if (this.m) {
6!
178
      this.closeLink(() => {
×
179
        this.startLink((err) => {
×
180
          if (err) {
×
181
            console.log(err)
×
182
          }
183
        })
184
      })
185
    }
186

187
    // try to save. Will be invalid if running under test runner
188
    try {
6✔
189
      this.saveSerialSettings()
6✔
190
    } catch (e) {
191
      console.log(e)
×
192
    }
193

194
    return this.getUDPOutputs()
6✔
195
  }
196

197
  removeUDPOutput (remIP, remPort) {
198
    // remove new udp output
199

200
    // check that it's not the internal 127.0.0.1:14540
201
    if (remIP === '127.0.0.1' && remPort === 14540) {
6!
202
      return this.getUDPOutputs()
×
203
    }
204

205
    // check if this ip:port is already in the list
206
    for (let i = 0, len = this.UDPoutputs.length; i < len; i++) {
6✔
207
      if (this.UDPoutputs[i].IP === remIP && this.UDPoutputs[i].port === remPort) {
9✔
208
        // and remove
209
        this.UDPoutputs.splice(i, 1)
3✔
210
        console.log('Removed UDP Output ' + remIP + ':' + remPort)
3✔
211

212
        // restart mavlink-router, if link active
213
        if (this.m) {
3!
214
          this.closeLink(() => {
×
215
            this.startLink((err) => {
×
216
              if (err) {
×
217
                console.log(err)
×
218
              }
219
            })
220
          })
221
        }
222

223
        // try to save. Will be invalid if running under test runner
224
        try {
3✔
225
          this.saveSerialSettings()
3✔
226
        } catch (e) {
227
          console.log(e)
×
228
        }
229

230
        return this.getUDPOutputs()
3✔
231
      }
232
    }
233

234
    return this.getUDPOutputs()
3✔
235
  }
236

237
  getSystemStatus () {
238
    // get the system status
239
    if (this.m !== null) {
3!
240
      return {
×
241
        numpackets: this.m.statusNumRxPackets,
242
        FW: this.m.autopilotFromID(),
243
        vehType: this.m.vehicleFromID(),
244
        conStatus: this.m.conStatusStr(),
245
        statusText: this.m.statusText,
246
        byteRate: this.m.statusBytesPerSec.avgBytesSec,
247
        fcVersion: this.m.fcVersion
248
      }
249
    } else {
250
      return {
3✔
251
        numpackets: 0,
252
        FW: '',
253
        vehType: '',
254
        conStatus: 'Not connected',
255
        statusText: '',
256
        byteRate: 0,
257
        fcVersion: ''
258
      }
259
    }
260
  }
261

262
  rebootFC () {
263
    // command the flight controller to reboot
264
    if (this.m !== null) {
×
265
      console.log('Rebooting FC')
×
266
      this.m.sendReboot()
×
267
    }
268
  }
269

270
  startBinLogging () {
271
    // command the flight controller to start streaming bin log
272
    if (this.m !== null) {
×
273
      console.log('Bin log start request')
×
274
      this.m.sendBinStreamRequest()
×
275
    }
276
  }
277

278
  stopBinLogging () {
279
    // command the flight controller to stop streaming bin log
280
    if (this.m !== null) {
×
281
      console.log('Bin log stop request')
×
282
      this.m.sendBinStreamRequestStop()
×
283
    }
284
  }
285

286
  startLink (callback) {
287
    // start the serial link
288
    console.log('Opening Link ' + this.activeDevice.serial.value + ' @ ' + this.activeDevice.baud.value + ', MAV v' + this.activeDevice.mavversion.value)
3✔
289
    // this.outputs.push({ IP: newIP, port: newPort })
290

291
    // build up the commandline for mavlink-router
292
    const cmd = ['-e', '127.0.0.1:14540', '--tcp-port']
3✔
293
    if (this.enableTCP === true) {
3!
294
      cmd.push('5760')
3✔
295
    } else {
296
      cmd.push('0')
×
297
    }
298
    for (let i = 0, len = this.UDPoutputs.length; i < len; i++) {
3✔
299
      cmd.push('-e')
×
300
      cmd.push(this.UDPoutputs[i].IP + ':' + this.UDPoutputs[i].port)
×
301
    }
302
    cmd.push('--log')
3✔
303
    cmd.push(logpaths.flightsLogsDir)
3✔
304
    if (this.tlogging === true) {
3!
305
      cmd.push('--telemetry-log')
×
306
    }
307
    if (this.enableUDPB === true) {
3!
308
      cmd.push('0.0.0.0:' + this.UDPBPort)
×
309
    }
310
    cmd.push(this.activeDevice.serial.value + ':' + this.activeDevice.baud.value)
3✔
311
    console.log(cmd)
3✔
312

313
    // check mavlink-router exists
314
    if (!this.validMavlinkRouter()) {
3!
315
      console.log('Could not find mavlink-routerd')
×
316
      return callback('Could not find mavlink-routerd', false)
×
317
    }
318

319
    // start mavlink-router
320
    this.router = spawn('mavlink-routerd', cmd)
3✔
321
    this.router.stdout.on('data', (data) => {
3✔
322
      console.log(`stdout: ${data}`)
×
323
    })
324

325
    this.router.stderr.on('data', (data) => {
3✔
326
      console.error(`stderr: ${data}`)
3✔
327
      if (data.toString().includes('Logging target') && data.toString().includes('.bin')) {
3!
328
        // remove old log, if it exists and is >60kB
329
        try {
×
330
          if (this.binlog !== null) {
×
331
            const fileStat = fs.lstatSync(this.binlog)
×
332
            if (Math.round(fileStat.size / 1024) < 60) {
×
333
              fs.unlinkSync(this.binlog)
×
334
            }
335
          }
336
        } catch (err) {
337
          console.log(err)
×
338
        }
339
        const res = data.toString().split(' ')
×
340
        const curLog = (res[res.length - 1]).trim()
×
NEW
341
        this.binlog = path.join(logpaths.flightsLogsDir, curLog)
×
342
        console.log('Current log is: ' + this.binlog)
×
343
      }
344
    })
345

346
    this.router.on('close', (code) => {
3✔
347
      console.log(`child process exited with code ${code}`)
3✔
348
      console.log('Closed Router')
3✔
349
      this.eventEmitter.emit('stopLink')
3✔
350
    })
351

352
    console.log('Opened Router')
3✔
353

354
    // only restart the mavlink processor if it's a new link,
355
    // not a reconnect attempt
356
    if (this.m === null) {
3!
357
      this.m = new mavManager(this.activeDevice.mavversion.value, '127.0.0.1', 14540, this.enableDSRequest)
3✔
358
      this.m.eventEmitter.on('gotMessage', (packet, data) => {
3✔
359
        // got valid message - send on to attached classes
360
        this.previousConnection = true
×
361
        this.eventEmitter.emit('gotMessage', packet, data)
×
362
      })
363
    }
364

365
    // arming events - just pass them on
366
    this.m.eventEmitter.on('armed', () => {
3✔
367
      this.eventEmitter.emit('armed')
×
368
    })
369
    this.m.eventEmitter.on('disarmed', () => {
3✔
370
      this.eventEmitter.emit('disarmed')
×
371
    })
372
    this.eventEmitter.emit('newLink')
3✔
373

374
    return callback(null, true)
3✔
375
  }
376

377
  closeLink (callback) {
378
    // stop the serial link
379
    if (this.router && this.router.exitCode === null) {
3!
380
      this.router.kill('SIGINT')
3✔
381
      console.log('Trying to close router')
3✔
382
      return callback(null)
3✔
383
    } else {
384
      console.log('Already Closed Router')
×
385
      this.eventEmitter.emit('stopLink')
×
386
      return callback(null)
×
387
    }
388
  }
389

390
  async getSerialDevices (callback) {
391
    // get all serial devices
392
    this.serialDevices = []
3✔
393
    let retError = null
3✔
394

395
    const Binding = autoDetect()
3✔
396
    const ports = await Binding.list()
3✔
397

398
    for (let i = 0, len = ports.length; i < len; i++) {
3✔
399
      if (ports[i].pnpId !== undefined) {
96!
400
        // usb-ArduPilot_Pixhawk1-1M_32002A000847323433353231-if00
401
        // console.log("Port: ", ports[i].pnpID);
402
        let namePorts = ''
×
403
        if (ports[i].pnpId.split('_').length > 2) {
×
404
          namePorts = ports[i].pnpId.split('_')[1] + ' (' + ports[i].path + ')'
×
405
        } else {
406
          namePorts = ports[i].manufacturer + ' (' + ports[i].path + ')'
×
407
        }
408
        // console.log("Port: ", ports[i].pnpID);
409
        this.serialDevices.push({ value: ports[i].path, label: namePorts, pnpId: ports[i].pnpId })
×
410
      } else if (ports[i].manufacturer !== undefined) {
96!
411
        // on recent RasPiOS, the pnpID is undefined :(
412
        const nameports = ports[i].manufacturer + ' (' + ports[i].path + ')'
×
413
        this.serialDevices.push({ value: ports[i].path, label: nameports, pnpId: nameports })
×
414
      }
415
    }
416
    // if the serial console or modemmanager are active on the Pi, return error
417
    if (this.isModemManagerInstalled()) {
3!
418
      retError = Error('The ModemManager package is installed. This must be uninstalled (via sudo apt remove modemmanager), due to conflicts with serial ports')
×
419
    }
420
    if (fs.existsSync('/boot/cmdline.txt') && isPi()) {
3!
421
      const data = fs.readFileSync('/boot/cmdline.txt', { encoding: 'utf8', flag: 'r' })
×
422
      if (data.includes('console=serial0')) {
×
423
        retError = Error('Serial console is active on /dev/serial0. Use raspi-config to deactivate it')
×
424
      }
425
    }
426
    // for the Ras Pi's inbuilt UART
427
    if (fs.existsSync('/dev/serial0') && isPi()) {
3!
428
      this.serialDevices.push({ value: '/dev/serial0', label: '/dev/serial0', pnpId: '/dev/serial0' })
×
429
    }
430
    if (fs.existsSync('/dev/ttyAMA0') && isPi()) {
3!
431
      //Pi5 uses a different UART name. See https://forums.raspberrypi.com/viewtopic.php?t=359132
432
      this.serialDevices.push({ value: '/dev/ttyAMA0', label: '/dev/ttyAMA0', pnpId: '/dev/ttyAMA0' })
×
433
    }
434
    if (fs.existsSync('/dev/ttyAMA1') && isPi()) {
3!
435
      this.serialDevices.push({ value: '/dev/ttyAMA1', label: '/dev/ttyAMA1', pnpId: '/dev/ttyAMA1' })
×
436
    }
437
    if (fs.existsSync('/dev/ttyAMA2') && isPi()) {
3!
438
      this.serialDevices.push({ value: '/dev/ttyAMA2', label: '/dev/ttyAMA2', pnpId: '/dev/ttyAMA2' })
×
439
    }
440
    if (fs.existsSync('/dev/ttyAMA3') && isPi()) {
3!
441
      this.serialDevices.push({ value: '/dev/ttyAMA3', label: '/dev/ttyAMA3', pnpId: '/dev/ttyAMA3' })
×
442
    }
443
    if (fs.existsSync('/dev/ttyAMA4') && isPi()) {
3!
444
      this.serialDevices.push({ value: '/dev/ttyAMA4', label: '/dev/ttyAMA4', pnpId: '/dev/ttyAMA4' })
×
445
    }
446
    // rpi uart has different name under Ubuntu
447
    const data = await si.osInfo()
3✔
448
    if (data.distro.toString().includes('Ubuntu') && fs.existsSync('/dev/ttyS0') && isPi()) {
3!
449
      // console.log("Running Ubuntu")
450
      this.serialDevices.push({ value: '/dev/ttyS0', label: '/dev/ttyS0', pnpId: '/dev/ttyS0' })
×
451
    }
452
    // jetson serial ports
453
    if (fs.existsSync('/dev/ttyTHS1')) {
3!
454
      this.serialDevices.push({ value: '/dev/ttyTHS1', label: '/dev/ttyTHS1', pnpId: '/dev/ttyTHS1' })
×
455
    }
456
    if (fs.existsSync('/dev/ttyTHS2')) {
3!
457
      this.serialDevices.push({ value: '/dev/ttyTHS2', label: '/dev/ttyTHS2', pnpId: '/dev/ttyTHS2' })
×
458
    }
459
    if (fs.existsSync('/dev/ttyTHS3')) {
3!
460
      this.serialDevices.push({ value: '/dev/ttyTHS3', label: '/dev/ttyTHS3', pnpId: '/dev/ttyTHS3' })
×
461
    }
462

463
    // has the active device been disconnected?
464
    if (this.port) {
3!
465
      console.log('Lost active device')
×
466
      // this.active = false;
UNCOV
467
      this.m.close()
×
468
      this.m = null
×
469
    }
470
    // set the active device as selected
471
    if (this.activeDevice) {
3!
472
      return callback(retError, this.serialDevices, this.baudRates, this.activeDevice.serial, this.activeDevice.baud, this.mavlinkVersions, this.activeDevice.mavversion, true, this.enableHeartbeat, this.enableTCP, this.enableUDPB, this.UDPBPort, this.enableDSRequest, this.tlogging)
×
473
    } else if (this.serialDevices.length > 0) {
3!
474
      return callback(retError, this.serialDevices, this.baudRates, this.serialDevices[0], this.baudRates[3], this.mavlinkVersions, this.mavlinkVersions[1], false, this.enableHeartbeat, this.enableTCP, this.enableUDPB, this.UDPBPort, this.enableDSRequest, this.tlogging)
×
475
    } else {
476
      return callback(retError, this.serialDevices, this.baudRates, [], this.baudRates[3], this.mavlinkVersions, this.mavlinkVersions[1], false, this.enableHeartbeat, this.enableTCP, this.enableUDPB, this.UDPBPort, this.enableDSRequest, this.tlogging)
3✔
477
    }
478
  }
479

480
  startInterval () {
481
    // start the 1-sec loop checking for disconnects
482
    this.intervalObj = setInterval(() => {
3✔
483
    
484
    // Send heartbeats, if they are enabled
485
    if(this.enableHeartbeat){
×
486
      this.m.sendHeartbeat()
×
487
    }
488
      // check for timeouts in serial link (ie disconnected cable or reboot)
489
      if (this.m && this.m.conStatusInt() === -1) {
×
490
        console.log('Trying to reconnect FC...')
×
491
        this.closeLink(() => {
×
492
          this.startLink((err) => {
×
493
            if (err) {
×
494
              console.log(err)
×
495
            } else {
496
              // DS request is in this.m.restart()
497
              this.m.restart()
×
498
            }
499
          })
500
        })
501
      }
502
    }, 1000)
503
  }
504

505
  startStopTelemetry (device, baud, mavversion, enableHeartbeat, enableTCP, enableUDPB, UDPBPort, enableDSRequest, tlogging, callback) {
506
    // user wants to start or stop telemetry
507
    // callback is (err, isSuccessful)
508

509
    this.enableHeartbeat = enableHeartbeat
6✔
510
    this.enableTCP = enableTCP
6✔
511
    this.enableUDPB = enableUDPB
6✔
512
    this.UDPBPort = UDPBPort
6✔
513
    this.enableDSRequest = enableDSRequest
6✔
514
    this.tlogging = tlogging
6✔
515

516
    if (this.m) {
6✔
517
      this.m.enableDSRequest = enableDSRequest
3✔
518
    }
519

520
    // check port, mavversion and baud are valid (if starting telem)
521
    if (!this.activeDevice) {
6✔
522
      this.activeDevice = { serial: null, baud: null }
3✔
523
      for (let i = 0, len = this.serialDevices.length; i < len; i++) {
3✔
524
        if (this.serialDevices[i].pnpId === device.pnpId) {
3!
525
          this.activeDevice.serial = this.serialDevices[i]
3✔
526
          break
3✔
527
        }
528
      }
529
      for (let i = 0, len = this.baudRates.length; i < len; i++) {
3✔
530
        if (this.baudRates[i].value === baud.value) {
18✔
531
          this.activeDevice.baud = this.baudRates[i]
3✔
532
          break
3✔
533
        }
534
      }
535
      for (let i = 0, len = this.mavlinkVersions.length; i < len; i++) {
3✔
536
        if (this.mavlinkVersions[i].value === mavversion.value) {
6✔
537
          this.activeDevice.mavversion = this.mavlinkVersions[i]
3✔
538
          break
3✔
539
        }
540
      }
541

542
      if (this.activeDevice.serial === null || this.activeDevice.baud.value === null || this.activeDevice.serial.value === null || this.activeDevice.mavversion.value === null || this.enableTCP === null) {
3!
543
        this.activeDevice = null
×
544
        return callback(new Error('Bad serial device or baud or mavlink version'), false)
×
545
      }
546

547
      // this.activeDevice = {serial: device, baud: baud};
548
      this.startLink((err) => {
3✔
549
        if (err) {
3!
550
          console.log("Can't open found FC " + this.activeDevice.serial.value + ', resetting link')
×
551
          this.activeDevice = null
×
552
        } else {
553
          // start timeout function for auto-reconnect
554
          this.startInterval()
3✔
555
          this.saveSerialSettings()
3✔
556
        }
557
        return callback(err, this.activeDevice !== null)
3✔
558
      })
559
    } else {
560
      // close link
561
      this.activeDevice = null
3✔
562
      this.closeLink(() => {
3✔
563
        this.saveSerialSettings()
3✔
564
        clearInterval(this.intervalObj)
3✔
565
        this.previousConnection = false
3✔
566
        this.m.close()
3✔
567
        this.m = null
3✔
568
        return callback(null, this.activeDevice !== null)
3✔
569
      })
570
    }
571
  }
572

573
  saveSerialSettings () {
574
    // Save the current settings to file
575
    try {
15✔
576
      this.settings.setValue('flightcontroller.activeDevice', this.activeDevice)
15✔
577
      this.settings.setValue('flightcontroller.outputs', this.UDPoutputs)
15✔
578
      this.settings.setValue('flightcontroller.enableHeartbeat', this.enableHeartbeat)
15✔
579
      this.settings.setValue('flightcontroller.enableTCP', this.enableTCP)
15✔
580
      this.settings.setValue('flightcontroller.enableUDPB', this.enableUDPB)
15✔
581
      this.settings.setValue('flightcontroller.UDPBPort', this.UDPBPort)
15✔
582
      this.settings.setValue('flightcontroller.enableDSRequest', this.enableDSRequest)
15✔
583
      this.settings.setValue('flightcontroller.tlogging', this.tlogging)
15✔
584
      console.log('Saved FC settings')
15✔
585
    } catch (e) {
UNCOV
586
      console.log(e)
×
587
    }
588
  }
589
}
590

591
module.exports = FCDetails
3✔
STATUS · Troubleshooting · Open an Issue · Sales · Support · CAREERS · ENTERPRISE · START FREE · SCHEDULE DEMO
ANNOUNCEMENTS · TWITTER · TOS & SLA · Supported CI Services · What's a CI service? · Automated Testing

© 2026 Coveralls, Inc