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

stephendade / Rpanion-server / 25620187987

10 May 2026 04:52AM UTC coverage: 34.439% (-0.3%) from 34.724%
25620187987

push

github

stephendade
Video: Add local still image and video recording

- Enables local still image and video recording by re-organizing the camera subsystem into three distinct modes: streaming video (default), still photo capture, and video capture
- Adds Python helper scripts to detect and control cameras for local still/video capture
- Python script uses V4L2 if Picamera2 is not available
- Photo and Video modes are disabled if OpenCV is not available
- Now sends a VideoStreamInformation packet whenever video streaming is started
- Captures a photo or starts/stops video recording either when the button is pressed on the web UI, or when a MavLink MAV_CMD_DO_DIGICAM_CONTROL message is received
- Geotagging: Writes GPS position information (if available) to EXIF metadata of photos
- Refactor flight log browser page to include media file management, and the browser now recurses subdirectories and displays relative file paths in the file lists.

362 of 1424 branches covered (25.42%)

Branch coverage included in aggregate %.

211 of 556 new or added lines in 4 files covered. (37.95%)

6 existing lines in 3 files now uncovered.

1144 of 2949 relevant lines covered (38.79%)

3.48 hits per line

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

50.89
/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 { common } = require('node-mavlink')
3✔
7
const mavManager = require('../mavlink/mavManager.js')
3✔
8
const logpaths = require('./paths.js')
3✔
9
const { detectSerialDevices, isModemManagerInstalled, isPi, getSerialPathFromValue } = require('./serialDetection.js')
3✔
10

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

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

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

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

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

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

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

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

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

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

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

70
    this.doLogging = false
15✔
71

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

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

78
    // mavlink-routerd path
79
    this.mavlinkRouterPath = null
15✔
80
    
81
    // Store vehicle position received via mavlink
82
    this.vehiclePosition = {
15✔
83
            lat: 0,
84
            lon: 0,
85
            alt: 0,       // MSL in meters
86
            relAlt: 0,    // Relative to home/ground in meters
87
            hdg: 0        // Heading in degrees
88
    }
89

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

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

140
  validMavlinkRouter () {
141
    // check mavlink-router is installed and updates folder
142
    const ls = spawnSync('which', ['mavlink-routerd'])
3✔
143
    console.log(ls.stdout.toString())
3✔
144
    if (ls.stdout.toString().trim() == '') {
3!
145
      // also check the parent directory
146
      const parentDir = path.dirname(__dirname)
3✔
147
      const mavlinkRouterPath = path.join(parentDir, 'mavlink-routerd')
3✔
148
      if (fs.existsSync(mavlinkRouterPath)) {
3!
149
        console.log('Found mavlink-routerd in ' + parentDir)
3✔
150
        this.mavlinkRouterPath = parentDir + "/mavlink-routerd"
3✔
151
        return true
3✔
152
      }
153
      this.mavlinkRouterPath = null
×
154
      return false
×
155
    } else {
156
      console.log('Found mavlink-routerd in ' + ls.stdout.toString().trim())
×
157
      this.mavlinkRouterPath = ls.stdout.toString().trim()
×
158
      return true
×
159
    }
160
  }
161

162

163

164
  getUDPOutputs () {
165
    // get list of current UDP outputs
166
    const ret = []
33✔
167
    for (let i = 0, len = this.UDPoutputs.length; i < len; i++) {
33✔
168
      ret.push({ IPPort: this.UDPoutputs[i].IP + ':' + this.UDPoutputs[i].port })
36✔
169
    }
170
    return ret
33✔
171
  }
172

173
  addUDPOutput (newIP, newPort) {
174
    // add a new udp output, if not already in
175
    // check if this ip:port is already in the list
176
    for (let i = 0, len = this.UDPoutputs.length; i < len; i++) {
9✔
177
      if (this.UDPoutputs[i].IP === newIP && this.UDPoutputs[i].port === newPort) {
6✔
178
        return this.getUDPOutputs()
3✔
179
      }
180
    }
181

182
    // check that it's not the internal 127.0.0.1:14540
183
    if (newIP === '127.0.0.1' && newPort === 14540) {
6!
184
      return this.getUDPOutputs()
×
185
    }
186

187
    // add it in
188
    this.UDPoutputs.push({ IP: newIP, port: newPort })
6✔
189
    console.log('Added UDP Output ' + newIP + ':' + newPort)
6✔
190

191
    // restart mavlink-router, if link active
192
    if (this.m) {
6!
193
      this.closeLink(() => {
×
194
        this.startLink((err) => {
×
195
          if (err) {
×
196
            console.log(err)
×
197
          }
198
        })
199
      })
200
    }
201

202
    // try to save. Will be invalid if running under test runner
203
    try {
6✔
204
      this.saveSerialSettings()
6✔
205
    } catch (e) {
206
      console.log(e)
×
207
    }
208

209
    return this.getUDPOutputs()
6✔
210
  }
211

212
  removeUDPOutput (remIP, remPort) {
213
    // remove new udp output
214

215
    // check that it's not the internal 127.0.0.1:14540
216
    if (remIP === '127.0.0.1' && remPort === 14540) {
6!
217
      return this.getUDPOutputs()
×
218
    }
219

220
    // check if this ip:port is already in the list
221
    for (let i = 0, len = this.UDPoutputs.length; i < len; i++) {
6✔
222
      if (this.UDPoutputs[i].IP === remIP && this.UDPoutputs[i].port === remPort) {
9✔
223
        // and remove
224
        this.UDPoutputs.splice(i, 1)
3✔
225
        console.log('Removed UDP Output ' + remIP + ':' + remPort)
3✔
226

227
        // restart mavlink-router, if link active
228
        if (this.m) {
3!
229
          this.closeLink(() => {
×
230
            this.startLink((err) => {
×
231
              if (err) {
×
232
                console.log(err)
×
233
              }
234
            })
235
          })
236
        }
237

238
        // try to save. Will be invalid if running under test runner
239
        try {
3✔
240
          this.saveSerialSettings()
3✔
241
        } catch (e) {
242
          console.log(e)
×
243
        }
244

245
        return this.getUDPOutputs()
3✔
246
      }
247
    }
248

249
    return this.getUDPOutputs()
3✔
250
  }
251

252
  getSystemStatus () {
253
    // get the system status
254
    if (this.m !== null) {
3!
255
      return {
×
256
        numpackets: this.m.statusNumRxPackets,
257
        FW: this.m.autopilotFromID(),
258
        vehType: this.m.vehicleFromID(),
259
        conStatus: this.m.conStatusStr(),
260
        statusText: this.m.statusText,
261
        byteRate: this.m.statusBytesPerSec.avgBytesSec,
262
        fcVersion: this.m.fcVersion,
263
        vehiclePosition: this.vehiclePosition
264

265
      }
266
    } else {
267
      return {
3✔
268
        numpackets: 0,
269
        FW: '',
270
        vehType: '',
271
        conStatus: 'Not connected',
272
        statusText: '',
273
        byteRate: 0,
274
        fcVersion: '',
275
        vehiclePosition: { lat: 0, lon: 0, alt: 0, relAlt: 0, hdg: 0 }
276
      }
277
    }
278
  }
279

280
  rebootFC () {
281
    // command the flight controller to reboot
282
    if (this.m !== null) {
×
283
      console.log('Rebooting FC')
×
284
      this.m.sendReboot()
×
285
    }
286
  }
287

288
  startBinLogging () {
289
    // command the flight controller to start streaming bin log
290
    if (this.m !== null) {
×
291
      console.log('Bin log start request')
×
292
      this.m.sendBinStreamRequest()
×
293
    }
294
  }
295

296
  stopBinLogging () {
297
    // command the flight controller to stop streaming bin log
298
    if (this.m !== null) {
×
299
      console.log('Bin log stop request')
×
300
      this.m.sendBinStreamRequestStop()
×
301
    }
302
  }
303

304
  startDFLogger () {
305
    // Start the dataflash logger Python process
306
    if (this.dflogger !== null) {
×
307
      console.log('DFLogger already running')
×
308
      return
×
309
    }
310

311
    console.log('Starting DataFlash logger')
×
312
    const pythonPath = logpaths.getPythonPath()
×
313
    const dfloggerPath = path.join(__dirname, '..', 'python', 'dflogger.py')
×
314
    
315
    this.dflogger = spawn(pythonPath, [
×
316
      dfloggerPath,
317
      '--connection', 'udp:127.0.0.1:14541',
318
      '--logdir', logpaths.flightsLogsDir,
319
      '--rotate-on-disarm'
320
    ])
321

322
    this.dflogger.stdout.on('data', (data) => {
×
323
      console.log(`DFLogger: ${data}`)
×
324
    })
325

326
    this.dflogger.stderr.on('data', (data) => {
×
327
      console.error(`DFLogger stderr: ${data}`)
×
328
    })
329

330
    this.dflogger.on('close', (code) => {
×
331
      console.log(`DFLogger exited with code ${code}`)
×
332
      this.dflogger = null
×
333
    })
334
  }
335

336
  stopDFLogger () {
337
    // Stop the dataflash logger Python process
338
    if (this.dflogger === null) {
×
339
      console.log('DFLogger not running')
×
340
      return
×
341
    }
342

343
    console.log('Stopping DataFlash logger')
×
344
    this.dflogger.kill('SIGTERM')
×
345
    this.dflogger = null
×
346
  }
347

348
  getDFLoggerStatus () {
349
    // Get the current status of the dataflash logger
350
    return {
×
351
      running: this.dflogger !== null
352
    }
353
  }
354

355
  startLink (callback) {
356
    // start the serial link
357
    if (this.activeDevice.inputType === 'UDP') {
3!
358
      console.log('Opening UDP Link ' + '0.0.0.0:' + this.activeDevice.udpInputPort + ', MAV v' + this.activeDevice.mavversion)
×
359
    } else {
360
      console.log('Opening UART Link ' + this.activeDevice.serial + ' @ ' + this.activeDevice.baud + ', MAV v' + this.activeDevice.mavversion)
3✔
361
    }
362
    // this.outputs.push({ IP: newIP, port: newPort })
363

364
    // build up the commandline for mavlink-router
365
    const cmd = ['-e', '127.0.0.1:14540', '-e', '127.0.0.1:14541', '--tcp-port']
3✔
366
    if (this.enableTCP === true) {
3!
367
      cmd.push('5760')
3✔
368
    } else {
369
      cmd.push('0')
×
370
    }
371
    for (let i = 0, len = this.UDPoutputs.length; i < len; i++) {
3✔
372
      cmd.push('-e')
×
373
      cmd.push(this.UDPoutputs[i].IP + ':' + this.UDPoutputs[i].port)
×
374
    }
375
    //cmd.push('--log')
376
    //cmd.push(logpaths.flightsLogsDir)
377
    //if (this.doLogging === true) {
378
    //  cmd.push('--telemetry-log')
379
    //}
380
    if (this.enableUDPB === true) {
3!
381
      cmd.push('0.0.0.0:' + this.UDPBPort)
×
382
    }
383
    if (this.activeDevice.inputType === 'UART') {
3!
384
      const serialPath = getSerialPathFromValue(this.activeDevice.serial, this.serialDevices)
3✔
385
      cmd.push(serialPath + ':' + this.activeDevice.baud)
3✔
386
    } else if (this.activeDevice.inputType === 'UDP') {
×
387
      cmd.push('0.0.0.0:' + this.activeDevice.udpInputPort)
×
388
    }
389
    console.log(cmd)
3✔
390

391
    // check mavlink-router exists
392
    if (!this.validMavlinkRouter()) {
3!
393
      console.log('Could not find mavlink-routerd')
×
394
      this.active = false
×
395
      return callback('Could not find mavlink-routerd', false)
×
396
    }
397

398
    // start mavlink-router
399
    this.router = spawn(this.mavlinkRouterPath, cmd)
3✔
400
    this.router.stdout.on('data', (data) => {
3✔
401
      console.log(`stdout: ${data}`)
×
402
    })
403

404
    this.router.stderr.on('data', (data) => {
3✔
405
      console.error(`stderr: ${data}`)
3✔
406
      if (data.toString().includes('Logging target') && data.toString().includes('.bin')) {
3!
407
        // remove old log, if it exists and is >60kB
408
        try {
×
409
          if (this.binlog !== null) {
×
410
            const fileStat = fs.lstatSync(this.binlog)
×
411
            if (Math.round(fileStat.size / 1024) < 60) {
×
412
              fs.unlinkSync(this.binlog)
×
413
            }
414
          }
415
        } catch (err) {
416
          console.log(err)
×
417
        }
418
        const res = data.toString().split(' ')
×
419
        const curLog = (res[res.length - 1]).trim()
×
420
        this.binlog = path.join(logpaths.flightsLogsDir, curLog)
×
421
        console.log('Current log is: ' + this.binlog)
×
422
      }
423
    })
424

425
    this.router.on('close', (code) => {
3✔
426
      console.log(`child process exited with code ${code}`)
3✔
427
      console.log('Closed Router')
3✔
428
      this.eventEmitter.emit('stopLink')
3✔
429
    })
430

431
    console.log('Opened Router')
3✔
432

433
    // only restart the mavlink processor if it's a new link,
434
    // not a reconnect attempt
435
    if (this.m === null) {
3!
436
      this.m = new mavManager(this.activeDevice.mavversion, '127.0.0.1', 14540, this.enableDSRequest)
3✔
437
      this.m.eventEmitter.on('gotMessage', (packet, data) => {
3✔
438
        // got valid message - send on to attached classes
439
        this.previousConnection = true
×
NEW
440
        if (packet.header.msgid === common.GlobalPositionInt.MSG_ID) {
×
441
            // MAVLink sends lat/lon as int * 1E7, alt as mm, heading as cdeg
NEW
442
            if (this.vehiclePosition) {
×
NEW
443
                this.vehiclePosition.lat = data.lat / 10000000
×
NEW
444
                this.vehiclePosition.lon = data.lon / 10000000
×
NEW
445
                this.vehiclePosition.alt = data.alt / 1000
×
NEW
446
                this.vehiclePosition.relAlt = data.relativeAlt / 1000
×
NEW
447
                this.vehiclePosition.hdg = data.hdg / 100
×
448
            }
449
        }
UNCOV
450
        this.eventEmitter.emit('gotMessage', packet, data)
×
451
      })
452
    }
453

454
    // arming events - just pass them on
455
    this.m.eventEmitter.on('armed', () => {
3✔
456
      this.eventEmitter.emit('armed')
×
457
    })
458
    this.m.eventEmitter.on('disarmed', () => {
3✔
459
      this.eventEmitter.emit('disarmed')
×
460
    })
461
    this.eventEmitter.emit('newLink')
3✔
462

463
    // Start dataflash logger if logging enabled
464
    if (this.doLogging === true) {
3!
465
      this.startDFLogger()
×
466
    }
467

468
    this.active = true
3✔
469
    return callback(null, true)
3✔
470
  }
471

472
  closeLink (callback) {
473
    // stop the serial link
474
    this.active = false
3✔
475
    
476
    // Stop dataflash logger if running
477
    if (this.dflogger !== null) {
3!
478
      this.stopDFLogger()
×
479
    }
480
    
481
    if (this.router && this.router.exitCode === null) {
3!
482
      this.router.kill('SIGINT')
3✔
483
      console.log('Trying to close router')
3✔
484
      return callback(null)
3✔
485
    } else {
486
      console.log('Already Closed Router')
×
487
      this.eventEmitter.emit('stopLink')
×
488
      return callback(null)
×
489
    }
490
  }
491

492
  checkSerialPortIssues () {
493
    // Check if ModemManager is installed
494
    if (isModemManagerInstalled()) {
3!
495
      return new Error('The ModemManager package is installed. This must be uninstalled (via sudo apt remove modemmanager), due to conflicts with serial ports')
×
496
    }
497

498
    // Check if serial console is active on Raspberry Pi
499
    if (fs.existsSync('/boot/cmdline.txt') && isPi()) {
3!
500
      const data = fs.readFileSync('/boot/cmdline.txt', { encoding: 'utf8', flag: 'r' })
×
501
      if (data.includes('console=serial0')) {
×
502
        return new Error('Serial console is active on /dev/serial0. Use raspi-config to deactivate it')
×
503
      }
504
    }
505

506
    return null
3✔
507
  }
508

509
  async getDeviceSettings (callback) {
510
    // get all serial devices
511
    this.serialDevices = []
3✔
512
    let retError = null
3✔
513

514
    // Detect all serial devices using hardwareDetection module
515
    this.serialDevices = await detectSerialDevices()
3✔
516

517
    // Check for configuration issues
518
    retError = this.checkSerialPortIssues()
3✔
519

520
    // set the active device as selected
521
    if (this.active && this.activeDevice && this.activeDevice.inputType === 'UART') {
3!
522
      return callback(retError, this.serialDevices, this.baudRates, this.activeDevice.serial,
×
523
        this.activeDevice.baud, this.mavlinkVersions, this.activeDevice.mavversion,
524
        this.active, this.enableHeartbeat, this.enableTCP, this.enableUDPB, this.UDPBPort, this.enableDSRequest, this.doLogging, this.activeDevice.udpInputPort,
525
        this.inputTypes[0].value, this.inputTypes)
526
    } else if (this.active && this.activeDevice && this.activeDevice.inputType === 'UDP') {
3!
527
      return callback(retError, this.serialDevices, this.baudRates, this.serialDevices.length > 0 ? this.serialDevices[0].value : [], this.baudRates[3].value,
×
528
        this.mavlinkVersions, this.activeDevice.mavversion, this.active, this.enableHeartbeat,
529
        this.enableTCP, this.enableUDPB, this.UDPBPort, this.enableDSRequest, this.doLogging, this.activeDevice.udpInputPort,
530
        this.inputTypes[1].value, this.inputTypes)
531
    } else {
532
      // no connection
533
      return callback(retError, this.serialDevices, this.baudRates, this.serialDevices.length > 0 ? this.serialDevices[0].value : [],
3!
534
        this.baudRates[3].value, this.mavlinkVersions, this.mavlinkVersions[1].value, this.active, this.enableHeartbeat,
535
        this.enableTCP, this.enableUDPB, this.UDPBPort, this.enableDSRequest, this.doLogging, 9000, this.inputTypes[0].value, this.inputTypes)
536
    }
537
  }
538

539
  startInterval () {
540
    // start the 1-sec loop checking for disconnects
541
    this.intervalObj = setInterval(() => {
3✔
542
    
543
    // Send heartbeats, if they are enabled
544
    if(this.enableHeartbeat){
×
545
      this.m.sendHeartbeat()
×
546
    }
547
      // check for timeouts in serial link (ie disconnected cable or reboot)
548
      if (this.m && this.m.conStatusInt() === -1) {
×
549
        console.log('Trying to reconnect FC...')
×
550
        this.closeLink(() => {
×
551
          this.startLink((err) => {
×
552
            if (err) {
×
553
              console.log(err)
×
554
            } else {
555
              // DS request is in this.m.restart()
556
              this.m.restart()
×
557
            }
558
          })
559
        })
560
      }
561
    }, 1000)
562
  }
563

564
  startStopTelemetry (device, baud, mavversion, enableHeartbeat, enableTCP, enableUDPB, UDPBPort, enableDSRequest,
565
                      doLogging, inputType, udpInputPort, callback) {
566
    // user wants to start or stop telemetry
567
    // callback is (err, isSuccessful)
568

569
    this.enableHeartbeat = enableHeartbeat
6✔
570
    this.enableTCP = enableTCP
6✔
571
    this.enableUDPB = enableUDPB
6✔
572
    this.UDPBPort = UDPBPort
6✔
573
    this.enableDSRequest = enableDSRequest
6✔
574
    this.doLogging = doLogging
6✔
575

576
    if (this.m) {
6✔
577
      this.m.enableDSRequest = enableDSRequest
3✔
578
    }
579

580
    // check port, mavversion and baud are valid (if starting telem)
581
    if (!this.active) {
6✔
582
      this.activeDevice = { serial: null, baud: null, inputType: 'UART', mavversion: null, udpInputPort: 9000 }
3✔
583
      this.activeDevice.mavversion = mavversion
3✔
584

585
      if (inputType === 'UART') {
3!
586
        this.activeDevice.inputType = 'UART'
3✔
587
        for (let i = 0, len = this.serialDevices.length; i < len; i++) {
3✔
588
          if (this.serialDevices[i].value === device) {
3!
589
            this.activeDevice.serial = this.serialDevices[i].value
3✔
590
            break
3✔
591
          }
592
        }
593
        for (let i = 0, len = this.baudRates.length; i < len; i++) {
3✔
594
          if (this.baudRates[i].value === baud) {
18✔
595
            this.activeDevice.baud = this.baudRates[i].value
3✔
596
            break
3✔
597
          }
598
        }
599
        console.log('Selected device: ' + device + ' @ ' + baud)
3✔
600
        console.log(this.activeDevice)
3✔
601

602
        if (this.activeDevice.serial === null || this.activeDevice.baud === null || this.activeDevice.serial.value === null || this.activeDevice.mavversion === null || this.enableTCP === null) {
3!
603
          this.activeDevice = null
×
604
          this.active = false
×
605
          return callback(new Error('Bad serial device or baud'), false)
×
606
        }
607
      } else if (inputType === 'UDP') {
×
608
        // UDP input
609
        this.activeDevice.inputType = 'UDP'
×
610
        this.activeDevice.serial = null
×
611
        this.activeDevice.baud = null
×
612
        this.activeDevice.mavversion = mavversion
×
613
        this.activeDevice.udpInputPort = udpInputPort
×
614
      } else {
615
        // unknown input type
616
        this.activeDevice = null
×
617
        return callback(new Error('Unknown input type'), false)
×
618
      }
619

620
      // this.activeDevice = {inputType, udpInputPort, serial: device, baud: baud};
621
      this.startLink((err) => {
3✔
622
        if (err) {
3!
623
          console.log(err)
×
624
          this.activeDevice = null
×
625
        } else {
626
          // start timeout function for auto-reconnect
627
          this.startInterval()
3✔
628
          this.saveSerialSettings()
3✔
629
        }
630
        return callback(err, this.activeDevice !== null)
3✔
631
      })
632
    } else {
633
      // close link
634
      this.activeDevice = null
3✔
635
      this.closeLink(() => {
3✔
636
        this.saveSerialSettings()
3✔
637
        clearInterval(this.intervalObj)
3✔
638
        this.previousConnection = false
3✔
639
        this.m.close()
3✔
640
        this.m = null
3✔
641
        return callback(null, this.activeDevice !== null)
3✔
642
      })
643
    }
644
  }
645

646
  saveSerialSettings () {
647
    // Save the current settings to file
648
    try {
15✔
649
      this.settings.setValue('flightcontroller.activeDevice', this.activeDevice)
15✔
650
      this.settings.setValue('flightcontroller.outputs', this.UDPoutputs)
15✔
651
      this.settings.setValue('flightcontroller.enableHeartbeat', this.enableHeartbeat)
15✔
652
      this.settings.setValue('flightcontroller.enableTCP', this.enableTCP)
15✔
653
      this.settings.setValue('flightcontroller.enableUDPB', this.enableUDPB)
15✔
654
      this.settings.setValue('flightcontroller.UDPBPort', this.UDPBPort)
15✔
655
      this.settings.setValue('flightcontroller.enableDSRequest', this.enableDSRequest)
15✔
656
      this.settings.setValue('flightcontroller.doLogging', this.doLogging)
15✔
657
      this.settings.setValue('flightcontroller.active', this.active)
15✔
658
      console.log('Saved FC settings')
15✔
659
    } catch (e) {
660
      console.log(e)
×
661
    }
662
  }
663
}
664

665
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