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

stephendade / Rpanion-server / 19923581221

04 Dec 2025 09:10AM UTC coverage: 35.579% (+1.0%) from 34.54%
19923581221

push

github

stephendade
Server: Add seperate dflogger instead of using mavlink-router for logging

331 of 1209 branches covered (27.38%)

Branch coverage included in aggregate %.

9 of 32 new or added lines in 2 files covered. (28.13%)

589 existing lines in 4 files now uncovered.

1058 of 2695 relevant lines covered (39.26%)

3.49 hits per line

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

51.95
/server/flightController.js
1
const fs = require('fs')
3✔
2
const events = require('events')
3✔
3
const path = require('path')
3✔
4
const { spawn, spawnSync } = require('child_process')
3✔
5

6
const mavManager = require('../mavlink/mavManager.js')
3✔
7
const logpaths = require('./paths.js')
3✔
8
const { detectSerialDevices, isModemManagerInstalled, isPi, getSerialPathFromValue } = require('./serialDetection.js')
3✔
9

10
class FCDetails {
11
  constructor (settings) {
12
    // if the device was successfully opend and got packets
13
    this.previousConnection = false
15✔
14

15
    // all detected serial ports and baud rates
16
    this.serialDevices = []
15✔
17
    this.baudRates = [{ value: 9600, label: '9600' },
15✔
18
      { value: 19200, label: '19200' },
19
      { value: 38400, label: '38400' },
20
      { value: 57600, label: '57600' },
21
      { value: 111100, label: '111100' },
22
      { value: 115200, label: '115200' },
23
      { value: 230400, label: '230400' },
24
      { value: 256000, label: '256000' },
25
      { value: 460800, label: '460800' },
26
      { value: 500000, label: '500000' },
27
      { value: 921600, label: '921600' },
28
      { value: 1500000, label: '1500000' }]
29
    this.mavlinkVersions = [{ value: 1, label: '1.0' },
15✔
30
      { value: 2, label: '2.0' }]
31
    this.inputTypes = [{ value: 'UART', label: 'UART' },
15✔
32
      { value: 'UDP', label: 'UDP Server' }]
33
    // JSON of active device (input type, port and baud and mavversion). User selected
34
    // null if user selected no link (or no serial port of that name)
35
    this.activeDevice = null
15✔
36

37
    // mavlink-router process
38
    this.router = null
15✔
39

40
    // the mavlink manager object
41
    this.m = null
15✔
42

43
    // For sending events outside of object
44
    this.eventEmitter = new events.EventEmitter()
15✔
45

46
    // Interval to check connection status and re-connect
47
    // if required
48
    this.intervalObj = null
15✔
49

50
    // UDP Outputs
51
    this.UDPoutputs = []
15✔
52

53
    // Send out MAVLink heartbeat packets?
54
    this.enableHeartbeat = false
15✔
55
  
56
    // Use TCP output?
57
    this.enableTCP = false
15✔
58

59
    // Use UDP Broadcast?
60
    this.enableUDPB = true
15✔
61
    this.UDPBPort = 14550
15✔
62

63
    // Send datastream requests to flight controller?
64
    this.enableDSRequest = false
15✔
65

66
    // Current binlog via mavlink-router
67
    this.binlog = null
15✔
68

69
    this.doLogging = false
15✔
70

71
    // DataFlash logger process
72
    this.dflogger = null
15✔
73

74
    // Is the connection active?
75
    this.active = false
15✔
76

77
    // mavlink-routerd path
78
    this.mavlinkRouterPath = null
15✔
79

80
    // load settings
81
    this.settings = settings
15✔
82
    this.activeDevice = this.settings.value('flightcontroller.activeDevice', null)
15✔
83
    this.UDPoutputs = this.settings.value('flightcontroller.outputs', [])
15✔
84
    this.enableHeartbeat = this.settings.value('flightcontroller.enableHeartbeat', false)
15✔
85
    this.enableTCP = this.settings.value('flightcontroller.enableTCP', false)
15✔
86
    this.enableUDPB = this.settings.value('flightcontroller.enableUDPB', true)
15✔
87
    this.UDPBPort = this.settings.value('flightcontroller.UDPBPort', 14550)
15✔
88
    this.enableDSRequest = this.settings.value('flightcontroller.enableDSRequest', false)
15✔
89
    this.doLogging = this.settings.value('flightcontroller.doLogging', false)
15✔
90
    this.active = this.settings.value('flightcontroller.active', false)
15✔
91

92
    if (this.active) {
15!
93
      // restart link if saved serial device is found
UNCOV
94
      this.getDeviceSettings((err, devices) => {
×
UNCOV
95
        if (this.activeDevice.inputType === 'UART') {
×
UNCOV
96
          let found = false
×
UNCOV
97
          for (let i = 0, len = devices.length; i < len; i++) {
×
UNCOV
98
            if (this.activeDevice.serial === devices[i].value) {
×
UNCOV
99
              found = true
×
UNCOV
100
              this.startLink((err) => {
×
UNCOV
101
                if (err) {
×
UNCOV
102
                  console.log("Can't open found FC " + this.activeDevice.serial + ', resetting link')
×
UNCOV
103
                  this.activeDevice = null
×
UNCOV
104
                  this.active = false
×
105
                }
UNCOV
106
                this.startInterval()
×
107
              })
UNCOV
108
              break
×
109
            }
110
          }
UNCOV
111
          if (!found) {
×
UNCOV
112
            console.log("Can't open saved connection, resetting")
×
UNCOV
113
            this.activeDevice = null
×
UNCOV
114
            this.active = false
×
115
          }
UNCOV
116
        } else if (this.activeDevice.inputType === 'UDP') {
×
UNCOV
117
          this.startLink((err) => {
×
UNCOV
118
            if (err) {
×
UNCOV
119
              console.log("Can't open UDP port " + this.activeDevice.udpInputPort + ', resetting link')
×
UNCOV
120
              this.activeDevice = null
×
UNCOV
121
              this.active = false
×
122
            }
UNCOV
123
            this.startInterval()
×
124
          })
125
        }
126
      })
127
    }
128
  }
129

130
  validMavlinkRouter () {
131
    // check mavlink-router is installed and updates folder
132
    const ls = spawnSync('which', ['mavlink-routerd'])
3✔
133
    console.log(ls.stdout.toString())
3✔
134
    if (ls.stdout.toString().trim() == '') {
3!
135
      // also check the parent directory
136
      const parentDir = path.dirname(__dirname)
3✔
137
      const mavlinkRouterPath = path.join(parentDir, 'mavlink-routerd')
3✔
138
      if (fs.existsSync(mavlinkRouterPath)) {
3!
139
        console.log('Found mavlink-routerd in ' + parentDir)
3✔
140
        this.mavlinkRouterPath = parentDir + "/mavlink-routerd"
3✔
141
        return true
3✔
142
      }
UNCOV
143
      this.mavlinkRouterPath = null
×
144
      return false
×
145
    } else {
146
      console.log('Found mavlink-routerd in ' + ls.stdout.toString().trim())
×
147
      this.mavlinkRouterPath = ls.stdout.toString().trim()
×
UNCOV
148
      return true
×
149
    }
150
  }
151

152

153

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

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

172
    // check that it's not the internal 127.0.0.1:14540
173
    if (newIP === '127.0.0.1' && newPort === 14540) {
6!
UNCOV
174
      return this.getUDPOutputs()
×
175
    }
176

177
    // add it in
178
    this.UDPoutputs.push({ IP: newIP, port: newPort })
6✔
179
    console.log('Added UDP Output ' + newIP + ':' + newPort)
6✔
180

181
    // restart mavlink-router, if link active
182
    if (this.m) {
6!
UNCOV
183
      this.closeLink(() => {
×
UNCOV
184
        this.startLink((err) => {
×
UNCOV
185
          if (err) {
×
UNCOV
186
            console.log(err)
×
187
          }
188
        })
189
      })
190
    }
191

192
    // try to save. Will be invalid if running under test runner
193
    try {
6✔
194
      this.saveSerialSettings()
6✔
195
    } catch (e) {
UNCOV
196
      console.log(e)
×
197
    }
198

199
    return this.getUDPOutputs()
6✔
200
  }
201

202
  removeUDPOutput (remIP, remPort) {
203
    // remove new udp output
204

205
    // check that it's not the internal 127.0.0.1:14540
206
    if (remIP === '127.0.0.1' && remPort === 14540) {
6!
UNCOV
207
      return this.getUDPOutputs()
×
208
    }
209

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

217
        // restart mavlink-router, if link active
218
        if (this.m) {
3!
UNCOV
219
          this.closeLink(() => {
×
UNCOV
220
            this.startLink((err) => {
×
UNCOV
221
              if (err) {
×
UNCOV
222
                console.log(err)
×
223
              }
224
            })
225
          })
226
        }
227

228
        // try to save. Will be invalid if running under test runner
229
        try {
3✔
230
          this.saveSerialSettings()
3✔
231
        } catch (e) {
UNCOV
232
          console.log(e)
×
233
        }
234

235
        return this.getUDPOutputs()
3✔
236
      }
237
    }
238

239
    return this.getUDPOutputs()
3✔
240
  }
241

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

267
  rebootFC () {
268
    // command the flight controller to reboot
UNCOV
269
    if (this.m !== null) {
×
UNCOV
270
      console.log('Rebooting FC')
×
UNCOV
271
      this.m.sendReboot()
×
272
    }
273
  }
274

275
  startBinLogging () {
276
    // command the flight controller to start streaming bin log
UNCOV
277
    if (this.m !== null) {
×
UNCOV
278
      console.log('Bin log start request')
×
UNCOV
279
      this.m.sendBinStreamRequest()
×
280
    }
281
  }
282

283
  stopBinLogging () {
284
    // command the flight controller to stop streaming bin log
UNCOV
285
    if (this.m !== null) {
×
UNCOV
286
      console.log('Bin log stop request')
×
287
      this.m.sendBinStreamRequestStop()
×
288
    }
289
  }
290

291
  startDFLogger () {
292
    // Start the dataflash logger Python process
NEW
293
    if (this.dflogger !== null) {
×
NEW
294
      console.log('DFLogger already running')
×
NEW
295
      return
×
296
    }
297

NEW
298
    console.log('Starting DataFlash logger')
×
NEW
299
    const pythonPath = 'python3'
×
NEW
300
    const dfloggerPath = path.join(__dirname, '..', 'python', 'dflogger.py')
×
301
    
NEW
302
    this.dflogger = spawn(pythonPath, [
×
303
      dfloggerPath,
304
      '--connection', 'udp:127.0.0.1:14541',
305
      '--logdir', logpaths.flightsLogsDir,
306
      '--rotate-on-disarm'
307
    ])
308

NEW
309
    this.dflogger.stdout.on('data', (data) => {
×
NEW
310
      console.log(`DFLogger: ${data}`)
×
311
    })
312

NEW
313
    this.dflogger.stderr.on('data', (data) => {
×
NEW
314
      console.error(`DFLogger stderr: ${data}`)
×
315
    })
316

NEW
317
    this.dflogger.on('close', (code) => {
×
NEW
318
      console.log(`DFLogger exited with code ${code}`)
×
NEW
319
      this.dflogger = null
×
320
    })
321
  }
322

323
  stopDFLogger () {
324
    // Stop the dataflash logger Python process
NEW
325
    if (this.dflogger === null) {
×
NEW
326
      console.log('DFLogger not running')
×
NEW
327
      return
×
328
    }
329

NEW
330
    console.log('Stopping DataFlash logger')
×
NEW
331
    this.dflogger.kill('SIGTERM')
×
NEW
332
    this.dflogger = null
×
333
  }
334

335
  getDFLoggerStatus () {
336
    // Get the current status of the dataflash logger
NEW
337
    return {
×
338
      running: this.dflogger !== null
339
    }
340
  }
341

342
  startLink (callback) {
343
    // start the serial link
344
    if (this.activeDevice.inputType === 'UDP') {
3!
UNCOV
345
      console.log('Opening UDP Link ' + '0.0.0.0:' + this.activeDevice.udpInputPort + ', MAV v' + this.activeDevice.mavversion)
×
346
    } else {
347
      console.log('Opening UART Link ' + this.activeDevice.serial + ' @ ' + this.activeDevice.baud + ', MAV v' + this.activeDevice.mavversion)
3✔
348
    }
349
    // this.outputs.push({ IP: newIP, port: newPort })
350

351
    // build up the commandline for mavlink-router
352
    const cmd = ['-e', '127.0.0.1:14540', '-e', '127.0.0.1:14541', '--tcp-port']
3✔
353
    if (this.enableTCP === true) {
3!
354
      cmd.push('5760')
3✔
355
    } else {
UNCOV
356
      cmd.push('0')
×
357
    }
358
    for (let i = 0, len = this.UDPoutputs.length; i < len; i++) {
3✔
UNCOV
359
      cmd.push('-e')
×
UNCOV
360
      cmd.push(this.UDPoutputs[i].IP + ':' + this.UDPoutputs[i].port)
×
361
    }
362
    //cmd.push('--log')
363
    //cmd.push(logpaths.flightsLogsDir)
364
    //if (this.doLogging === true) {
365
    //  cmd.push('--telemetry-log')
366
    //}
367
    if (this.enableUDPB === true) {
3!
UNCOV
368
      cmd.push('0.0.0.0:' + this.UDPBPort)
×
369
    }
370
    if (this.activeDevice.inputType === 'UART') {
3!
371
      const serialPath = getSerialPathFromValue(this.activeDevice.serial, this.serialDevices)
3✔
372
      cmd.push(serialPath + ':' + this.activeDevice.baud)
3✔
UNCOV
373
    } else if (this.activeDevice.inputType === 'UDP') {
×
UNCOV
374
      cmd.push('0.0.0.0:' + this.activeDevice.udpInputPort)
×
375
    }
376
    console.log(cmd)
3✔
377

378
    // check mavlink-router exists
379
    if (!this.validMavlinkRouter()) {
3!
380
      console.log('Could not find mavlink-routerd')
×
UNCOV
381
      this.active = false
×
UNCOV
382
      return callback('Could not find mavlink-routerd', false)
×
383
    }
384

385
    // start mavlink-router
386
    this.router = spawn(this.mavlinkRouterPath, cmd)
3✔
387
    this.router.stdout.on('data', (data) => {
3✔
UNCOV
388
      console.log(`stdout: ${data}`)
×
389
    })
390

391
    this.router.stderr.on('data', (data) => {
3✔
392
      console.error(`stderr: ${data}`)
3✔
393
      if (data.toString().includes('Logging target') && data.toString().includes('.bin')) {
3!
394
        // remove old log, if it exists and is >60kB
UNCOV
395
        try {
×
UNCOV
396
          if (this.binlog !== null) {
×
UNCOV
397
            const fileStat = fs.lstatSync(this.binlog)
×
398
            if (Math.round(fileStat.size / 1024) < 60) {
×
UNCOV
399
              fs.unlinkSync(this.binlog)
×
400
            }
401
          }
402
        } catch (err) {
UNCOV
403
          console.log(err)
×
404
        }
UNCOV
405
        const res = data.toString().split(' ')
×
UNCOV
406
        const curLog = (res[res.length - 1]).trim()
×
407
        this.binlog = path.join(logpaths.flightsLogsDir, curLog)
×
UNCOV
408
        console.log('Current log is: ' + this.binlog)
×
409
      }
410
    })
411

412
    this.router.on('close', (code) => {
3✔
413
      console.log(`child process exited with code ${code}`)
3✔
414
      console.log('Closed Router')
3✔
415
      this.eventEmitter.emit('stopLink')
3✔
416
    })
417

418
    console.log('Opened Router')
3✔
419

420
    // only restart the mavlink processor if it's a new link,
421
    // not a reconnect attempt
422
    if (this.m === null) {
3!
423
      this.m = new mavManager(this.activeDevice.mavversion, '127.0.0.1', 14540, this.enableDSRequest)
3✔
424
      this.m.eventEmitter.on('gotMessage', (packet, data) => {
3✔
425
        // got valid message - send on to attached classes
UNCOV
426
        this.previousConnection = true
×
UNCOV
427
        this.eventEmitter.emit('gotMessage', packet, data)
×
428
      })
429
    }
430

431
    // arming events - just pass them on
432
    this.m.eventEmitter.on('armed', () => {
3✔
UNCOV
433
      this.eventEmitter.emit('armed')
×
434
    })
435
    this.m.eventEmitter.on('disarmed', () => {
3✔
436
      this.eventEmitter.emit('disarmed')
×
437
    })
438
    this.eventEmitter.emit('newLink')
3✔
439

440
    // Start dataflash logger if logging enabled
441
    if (this.doLogging === true) {
3!
NEW
442
      this.startDFLogger()
×
443
    }
444

445
    this.active = true
3✔
446
    return callback(null, true)
3✔
447
  }
448

449
  closeLink (callback) {
450
    // stop the serial link
451
    this.active = false
3✔
452
    
453
    // Stop dataflash logger if running
454
    if (this.dflogger !== null) {
3!
NEW
455
      this.stopDFLogger()
×
456
    }
457
    
458
    if (this.router && this.router.exitCode === null) {
3!
459
      this.router.kill('SIGINT')
3✔
460
      console.log('Trying to close router')
3✔
461
      return callback(null)
3✔
462
    } else {
UNCOV
463
      console.log('Already Closed Router')
×
UNCOV
464
      this.eventEmitter.emit('stopLink')
×
UNCOV
465
      return callback(null)
×
466
    }
467
  }
468

469
  checkSerialPortIssues () {
470
    // Check if ModemManager is installed
471
    if (isModemManagerInstalled()) {
3!
UNCOV
472
      return new Error('The ModemManager package is installed. This must be uninstalled (via sudo apt remove modemmanager), due to conflicts with serial ports')
×
473
    }
474

475
    // Check if serial console is active on Raspberry Pi
476
    if (fs.existsSync('/boot/cmdline.txt') && isPi()) {
3!
UNCOV
477
      const data = fs.readFileSync('/boot/cmdline.txt', { encoding: 'utf8', flag: 'r' })
×
478
      if (data.includes('console=serial0')) {
×
479
        return new Error('Serial console is active on /dev/serial0. Use raspi-config to deactivate it')
×
480
      }
481
    }
482

483
    return null
3✔
484
  }
485

486
  async getDeviceSettings (callback) {
487
    // get all serial devices
488
    this.serialDevices = []
3✔
489
    let retError = null
3✔
490

491
    // Detect all serial devices using hardwareDetection module
492
    this.serialDevices = await detectSerialDevices()
3✔
493

494
    // Check for configuration issues
495
    retError = this.checkSerialPortIssues()
3✔
496

497
    // set the active device as selected
498
    if (this.active && this.activeDevice && this.activeDevice.inputType === 'UART') {
3!
UNCOV
499
      return callback(retError, this.serialDevices, this.baudRates, this.activeDevice.serial,
×
500
        this.activeDevice.baud, this.mavlinkVersions, this.activeDevice.mavversion,
501
        this.active, this.enableHeartbeat, this.enableTCP, this.enableUDPB, this.UDPBPort, this.enableDSRequest, this.doLogging, this.activeDevice.udpInputPort,
502
        this.inputTypes[0].value, this.inputTypes)
503
    } else if (this.active && this.activeDevice && this.activeDevice.inputType === 'UDP') {
3!
504
      return callback(retError, this.serialDevices, this.baudRates, this.serialDevices.length > 0 ? this.serialDevices[0].value : [], this.baudRates[3].value,
×
505
        this.mavlinkVersions, this.activeDevice.mavversion, this.active, this.enableHeartbeat,
506
        this.enableTCP, this.enableUDPB, this.UDPBPort, this.enableDSRequest, this.doLogging, this.activeDevice.udpInputPort,
507
        this.inputTypes[1].value, this.inputTypes)
508
    } else {
509
      // no connection
510
      return callback(retError, this.serialDevices, this.baudRates, this.serialDevices.length > 0 ? this.serialDevices[0].value : [],
3!
511
        this.baudRates[3].value, this.mavlinkVersions, this.mavlinkVersions[1].value, this.active, this.enableHeartbeat,
512
        this.enableTCP, this.enableUDPB, this.UDPBPort, this.enableDSRequest, this.doLogging, 9000, this.inputTypes[0].value, this.inputTypes)
513
    }
514
  }
515

516
  startInterval () {
517
    // start the 1-sec loop checking for disconnects
518
    this.intervalObj = setInterval(() => {
3✔
519
    
520
    // Send heartbeats, if they are enabled
UNCOV
521
    if(this.enableHeartbeat){
×
522
      this.m.sendHeartbeat()
×
523
    }
524
      // check for timeouts in serial link (ie disconnected cable or reboot)
UNCOV
525
      if (this.m && this.m.conStatusInt() === -1) {
×
526
        console.log('Trying to reconnect FC...')
×
UNCOV
527
        this.closeLink(() => {
×
UNCOV
528
          this.startLink((err) => {
×
529
            if (err) {
×
UNCOV
530
              console.log(err)
×
531
            } else {
532
              // DS request is in this.m.restart()
533
              this.m.restart()
×
534
            }
535
          })
536
        })
537
      }
538
    }, 1000)
539
  }
540

541
  startStopTelemetry (device, baud, mavversion, enableHeartbeat, enableTCP, enableUDPB, UDPBPort, enableDSRequest,
542
                      doLogging, inputType, udpInputPort, callback) {
543
    // user wants to start or stop telemetry
544
    // callback is (err, isSuccessful)
545

546
    this.enableHeartbeat = enableHeartbeat
6✔
547
    this.enableTCP = enableTCP
6✔
548
    this.enableUDPB = enableUDPB
6✔
549
    this.UDPBPort = UDPBPort
6✔
550
    this.enableDSRequest = enableDSRequest
6✔
551
    this.doLogging = doLogging
6✔
552

553
    if (this.m) {
6✔
554
      this.m.enableDSRequest = enableDSRequest
3✔
555
    }
556

557
    // check port, mavversion and baud are valid (if starting telem)
558
    if (!this.active) {
6✔
559
      this.activeDevice = { serial: null, baud: null, inputType: 'UART', mavversion: null, udpInputPort: 9000 }
3✔
560
      this.activeDevice.mavversion = mavversion
3✔
561

562
      if (inputType === 'UART') {
3!
563
        this.activeDevice.inputType = 'UART'
3✔
564
        for (let i = 0, len = this.serialDevices.length; i < len; i++) {
3✔
565
          if (this.serialDevices[i].value === device) {
3!
566
            this.activeDevice.serial = this.serialDevices[i].value
3✔
567
            break
3✔
568
          }
569
        }
570
        for (let i = 0, len = this.baudRates.length; i < len; i++) {
3✔
571
          if (this.baudRates[i].value === baud) {
18✔
572
            this.activeDevice.baud = this.baudRates[i].value
3✔
573
            break
3✔
574
          }
575
        }
576
        console.log('Selected device: ' + device + ' @ ' + baud)
3✔
577
        console.log(this.activeDevice)
3✔
578

579
        if (this.activeDevice.serial === null || this.activeDevice.baud === null || this.activeDevice.serial.value === null || this.activeDevice.mavversion === null || this.enableTCP === null) {
3!
580
          this.activeDevice = null
×
UNCOV
581
          this.active = false
×
UNCOV
582
          return callback(new Error('Bad serial device or baud'), false)
×
583
        }
584
      } else if (inputType === 'UDP') {
×
585
        // UDP input
UNCOV
586
        this.activeDevice.inputType = 'UDP'
×
587
        this.activeDevice.serial = null
×
UNCOV
588
        this.activeDevice.baud = null
×
UNCOV
589
        this.activeDevice.mavversion = mavversion
×
UNCOV
590
        this.activeDevice.udpInputPort = udpInputPort
×
591
      } else {
592
        // unknown input type
UNCOV
593
        this.activeDevice = null
×
UNCOV
594
        return callback(new Error('Unknown input type'), false)
×
595
      }
596

597
      // this.activeDevice = {inputType, udpInputPort, serial: device, baud: baud};
598
      this.startLink((err) => {
3✔
599
        if (err) {
3!
UNCOV
600
          console.log(err)
×
UNCOV
601
          this.activeDevice = null
×
602
        } else {
603
          // start timeout function for auto-reconnect
604
          this.startInterval()
3✔
605
          this.saveSerialSettings()
3✔
606
        }
607
        return callback(err, this.activeDevice !== null)
3✔
608
      })
609
    } else {
610
      // close link
611
      this.activeDevice = null
3✔
612
      this.closeLink(() => {
3✔
613
        this.saveSerialSettings()
3✔
614
        clearInterval(this.intervalObj)
3✔
615
        this.previousConnection = false
3✔
616
        this.m.close()
3✔
617
        this.m = null
3✔
618
        return callback(null, this.activeDevice !== null)
3✔
619
      })
620
    }
621
  }
622

623
  saveSerialSettings () {
624
    // Save the current settings to file
625
    try {
15✔
626
      this.settings.setValue('flightcontroller.activeDevice', this.activeDevice)
15✔
627
      this.settings.setValue('flightcontroller.outputs', this.UDPoutputs)
15✔
628
      this.settings.setValue('flightcontroller.enableHeartbeat', this.enableHeartbeat)
15✔
629
      this.settings.setValue('flightcontroller.enableTCP', this.enableTCP)
15✔
630
      this.settings.setValue('flightcontroller.enableUDPB', this.enableUDPB)
15✔
631
      this.settings.setValue('flightcontroller.UDPBPort', this.UDPBPort)
15✔
632
      this.settings.setValue('flightcontroller.enableDSRequest', this.enableDSRequest)
15✔
633
      this.settings.setValue('flightcontroller.doLogging', this.doLogging)
15✔
634
      this.settings.setValue('flightcontroller.active', this.active)
15✔
635
      console.log('Saved FC settings')
15✔
636
    } catch (e) {
UNCOV
637
      console.log(e)
×
638
    }
639
  }
640
}
641

642
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