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

stephendade / Rpanion-server / 16114004222

07 Jul 2025 10:05AM UTC coverage: 35.792% (+0.08%) from 35.71%
16114004222

Pull #307

github

web-flow
Merge 30ffe3647 into 71296a994
Pull Request #307: Include mavlink-routerd binary in package

279 of 1024 branches covered (27.25%)

Branch coverage included in aggregate %.

8 of 11 new or added lines in 1 file covered. (72.73%)

2 existing lines in 1 file now uncovered.

910 of 2298 relevant lines covered (39.6%)

2.6 hits per line

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

54.08
/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 { spawn, spawnSync } = require('child_process')
3✔
6
const si = require('systeminformation')
3✔
7

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

90
    this.tlogging = false
15✔
91

92
    // Is the connection active?
93
    this.active = false
15✔
94

95
    // mavlink-routerd path
96
    this.mavlinkRouterPath = null
15✔
97

98
    // load settings
99
    this.settings = settings
15✔
100
    this.activeDevice = this.settings.value('flightcontroller.activeDevice', null)
15✔
101
    this.UDPoutputs = this.settings.value('flightcontroller.outputs', [])
15✔
102
    this.enableHeartbeat = this.settings.value('flightcontroller.enableHeartbeat', false)
15✔
103
    this.enableTCP = this.settings.value('flightcontroller.enableTCP', false)
15✔
104
    this.enableUDPB = this.settings.value('flightcontroller.enableUDPB', true)
15✔
105
    this.UDPBPort = this.settings.value('flightcontroller.UDPBPort', 14550)
15✔
106
    this.enableDSRequest = this.settings.value('flightcontroller.enableDSRequest', false)
15✔
107
    this.tlogging = this.settings.value('flightcontroller.tlogging', false)
15✔
108
    this.active = this.settings.value('flightcontroller.active', false)
15✔
109

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

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

170
  isModemManagerInstalled () {
171
    // check ModemManager is installed
172
    const ls = spawnSync('which', ['ModemManager'])
3✔
173
    console.log(ls.stdout.toString())
3✔
174
    if (ls.stdout.toString().includes('ModemManager')) {
3!
175
      return true
×
176
    } else {
177
      return false
3✔
178
    }
179
  }
180

181
  getUDPOutputs () {
182
    // get list of current UDP outputs
183
    const ret = []
33✔
184
    for (let i = 0, len = this.UDPoutputs.length; i < len; i++) {
33✔
185
      ret.push({ IPPort: this.UDPoutputs[i].IP + ':' + this.UDPoutputs[i].port })
36✔
186
    }
187
    return ret
33✔
188
  }
189

190
  addUDPOutput (newIP, newPort) {
191
    // add a new udp output, if not already in
192
    // check if this ip:port is already in the list
193
    for (let i = 0, len = this.UDPoutputs.length; i < len; i++) {
9✔
194
      if (this.UDPoutputs[i].IP === newIP && this.UDPoutputs[i].port === newPort) {
6✔
195
        return this.getUDPOutputs()
3✔
196
      }
197
    }
198

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

204
    // add it in
205
    this.UDPoutputs.push({ IP: newIP, port: newPort })
6✔
206
    console.log('Added UDP Output ' + newIP + ':' + newPort)
6✔
207

208
    // restart mavlink-router, if link active
209
    if (this.m) {
6!
210
      this.closeLink(() => {
×
211
        this.startLink((err) => {
×
212
          if (err) {
×
213
            console.log(err)
×
214
          }
215
        })
216
      })
217
    }
218

219
    // try to save. Will be invalid if running under test runner
220
    try {
6✔
221
      this.saveSerialSettings()
6✔
222
    } catch (e) {
223
      console.log(e)
×
224
    }
225

226
    return this.getUDPOutputs()
6✔
227
  }
228

229
  removeUDPOutput (remIP, remPort) {
230
    // remove new udp output
231

232
    // check that it's not the internal 127.0.0.1:14540
233
    if (remIP === '127.0.0.1' && remPort === 14540) {
6!
234
      return this.getUDPOutputs()
×
235
    }
236

237
    // check if this ip:port is already in the list
238
    for (let i = 0, len = this.UDPoutputs.length; i < len; i++) {
6✔
239
      if (this.UDPoutputs[i].IP === remIP && this.UDPoutputs[i].port === remPort) {
9✔
240
        // and remove
241
        this.UDPoutputs.splice(i, 1)
3✔
242
        console.log('Removed UDP Output ' + remIP + ':' + remPort)
3✔
243

244
        // restart mavlink-router, if link active
245
        if (this.m) {
3!
246
          this.closeLink(() => {
×
247
            this.startLink((err) => {
×
248
              if (err) {
×
249
                console.log(err)
×
250
              }
251
            })
252
          })
253
        }
254

255
        // try to save. Will be invalid if running under test runner
256
        try {
3✔
257
          this.saveSerialSettings()
3✔
258
        } catch (e) {
259
          console.log(e)
×
260
        }
261

262
        return this.getUDPOutputs()
3✔
263
      }
264
    }
265

266
    return this.getUDPOutputs()
3✔
267
  }
268

269
  getSystemStatus () {
270
    // get the system status
271
    if (this.m !== null) {
3!
272
      return {
×
273
        numpackets: this.m.statusNumRxPackets,
274
        FW: this.m.autopilotFromID(),
275
        vehType: this.m.vehicleFromID(),
276
        conStatus: this.m.conStatusStr(),
277
        statusText: this.m.statusText,
278
        byteRate: this.m.statusBytesPerSec.avgBytesSec,
279
        fcVersion: this.m.fcVersion
280
      }
281
    } else {
282
      return {
3✔
283
        numpackets: 0,
284
        FW: '',
285
        vehType: '',
286
        conStatus: 'Not connected',
287
        statusText: '',
288
        byteRate: 0,
289
        fcVersion: ''
290
      }
291
    }
292
  }
293

294
  rebootFC () {
295
    // command the flight controller to reboot
296
    if (this.m !== null) {
×
297
      console.log('Rebooting FC')
×
298
      this.m.sendReboot()
×
299
    }
300
  }
301

302
  startBinLogging () {
303
    // command the flight controller to start streaming bin log
304
    if (this.m !== null) {
×
305
      console.log('Bin log start request')
×
306
      this.m.sendBinStreamRequest()
×
307
    }
308
  }
309

310
  stopBinLogging () {
311
    // command the flight controller to stop streaming bin log
312
    if (this.m !== null) {
×
313
      console.log('Bin log stop request')
×
314
      this.m.sendBinStreamRequestStop()
×
315
    }
316
  }
317

318
  startLink (callback) {
319
    // start the serial link
320
    if (this.activeDevice.inputType === 'UDP') {
3!
321
      console.log('Opening UDP Link ' + '0.0.0.0:' + this.activeDevice.udpInputPort + ', MAV v' + this.activeDevice.mavversion.value)
×
322
    } else {
323
      console.log('Opening UART Link ' + this.activeDevice.serial.value + ' @ ' + this.activeDevice.baud.value + ', MAV v' + this.activeDevice.mavversion.value)
3✔
324
    }
325
    // this.outputs.push({ IP: newIP, port: newPort })
326

327
    // build up the commandline for mavlink-router
328
    const cmd = ['-e', '127.0.0.1:14540', '--tcp-port']
3✔
329
    if (this.enableTCP === true) {
3!
330
      cmd.push('5760')
3✔
331
    } else {
332
      cmd.push('0')
×
333
    }
334
    for (let i = 0, len = this.UDPoutputs.length; i < len; i++) {
3✔
335
      cmd.push('-e')
×
336
      cmd.push(this.UDPoutputs[i].IP + ':' + this.UDPoutputs[i].port)
×
337
    }
338
    cmd.push('--log')
3✔
339
    cmd.push(logpaths.flightsLogsDir)
3✔
340
    if (this.tlogging === true) {
3!
341
      cmd.push('--telemetry-log')
×
342
    }
343
    if (this.enableUDPB === true) {
3!
344
      cmd.push('0.0.0.0:' + this.UDPBPort)
×
345
    }
346
    if (this.activeDevice.inputType === 'UART') {
3!
347
      cmd.push(this.activeDevice.serial.value + ':' + this.activeDevice.baud.value)
3✔
348
    } else if (this.activeDevice.inputType === 'UDP') {
×
349
      cmd.push('0.0.0.0:' + this.activeDevice.udpInputPort)
×
350
    }
351
    console.log(cmd)
3✔
352

353
    // check mavlink-router exists
354
    if (!this.validMavlinkRouter()) {
3!
355
      console.log('Could not find mavlink-routerd')
×
356
      this.active = false
×
357
      return callback('Could not find mavlink-routerd', false)
×
358
    }
359

360
    // start mavlink-router
361
    this.router = spawn(this.mavlinkRouterPath, cmd)
3✔
362
    this.router.stdout.on('data', (data) => {
3✔
363
      console.log(`stdout: ${data}`)
×
364
    })
365

366
    this.router.stderr.on('data', (data) => {
3✔
367
      console.error(`stderr: ${data}`)
3✔
368
      if (data.toString().includes('Logging target') && data.toString().includes('.bin')) {
3!
369
        // remove old log, if it exists and is >60kB
370
        try {
×
371
          if (this.binlog !== null) {
×
372
            const fileStat = fs.lstatSync(this.binlog)
×
373
            if (Math.round(fileStat.size / 1024) < 60) {
×
374
              fs.unlinkSync(this.binlog)
×
375
            }
376
          }
377
        } catch (err) {
378
          console.log(err)
×
379
        }
380
        const res = data.toString().split(' ')
×
381
        const curLog = (res[res.length - 1]).trim()
×
382
        this.binlog = path.join(logpaths.flightsLogsDir, curLog)
×
383
        console.log('Current log is: ' + this.binlog)
×
384
      }
385
    })
386

387
    this.router.on('close', (code) => {
3✔
388
      console.log(`child process exited with code ${code}`)
3✔
389
      console.log('Closed Router')
3✔
390
      this.eventEmitter.emit('stopLink')
3✔
391
    })
392

393
    console.log('Opened Router')
3✔
394

395
    // only restart the mavlink processor if it's a new link,
396
    // not a reconnect attempt
397
    if (this.m === null) {
3!
398
      this.m = new mavManager(this.activeDevice.mavversion.value, '127.0.0.1', 14540, this.enableDSRequest)
3✔
399
      this.m.eventEmitter.on('gotMessage', (packet, data) => {
3✔
400
        // got valid message - send on to attached classes
401
        this.previousConnection = true
×
402
        this.eventEmitter.emit('gotMessage', packet, data)
×
403
      })
404
    }
405

406
    // arming events - just pass them on
407
    this.m.eventEmitter.on('armed', () => {
3✔
408
      this.eventEmitter.emit('armed')
×
409
    })
410
    this.m.eventEmitter.on('disarmed', () => {
3✔
411
      this.eventEmitter.emit('disarmed')
×
412
    })
413
    this.eventEmitter.emit('newLink')
3✔
414

415
    this.active = true
3✔
416
    return callback(null, true)
3✔
417
  }
418

419
  closeLink (callback) {
420
    // stop the serial link
421
    this.active = false
3✔
422
    if (this.router && this.router.exitCode === null) {
3!
423
      this.router.kill('SIGINT')
3✔
424
      console.log('Trying to close router')
3✔
425
      return callback(null)
3✔
426
    } else {
427
      console.log('Already Closed Router')
×
428
      this.eventEmitter.emit('stopLink')
×
429
      return callback(null)
×
430
    }
431
  }
432

433
  async getDeviceSettings (callback) {
434
    // get all serial devices
435
    this.serialDevices = []
3✔
436
    let retError = null
3✔
437

438
    const Binding = autoDetect()
3✔
439
    const ports = await Binding.list()
3✔
440

441
    for (let i = 0, len = ports.length; i < len; i++) {
3✔
442
      if (ports[i].pnpId !== undefined) {
96!
443
        // usb-ArduPilot_Pixhawk1-1M_32002A000847323433353231-if00
444
        // console.log("Port: ", ports[i].pnpID);
445
        let namePorts = ''
×
446
        if (ports[i].pnpId.split('_').length > 2) {
×
447
          namePorts = ports[i].pnpId.split('_')[1] + ' (' + ports[i].path + ')'
×
448
        } else {
449
          namePorts = ports[i].manufacturer + ' (' + ports[i].path + ')'
×
450
        }
451
        // console.log("Port: ", ports[i].pnpID);
452
        this.serialDevices.push({ value: ports[i].path, label: namePorts, pnpId: ports[i].pnpId })
×
453
      } else if (ports[i].manufacturer !== undefined) {
96!
454
        // on recent RasPiOS, the pnpID is undefined :(
455
        const nameports = ports[i].manufacturer + ' (' + ports[i].path + ')'
×
456
        this.serialDevices.push({ value: ports[i].path, label: nameports, pnpId: nameports })
×
457
      }
458
    }
459
    // if the serial console or modemmanager are active on the Pi, return error
460
    if (this.isModemManagerInstalled()) {
3!
461
      retError = Error('The ModemManager package is installed. This must be uninstalled (via sudo apt remove modemmanager), due to conflicts with serial ports')
×
462
    }
463
    if (fs.existsSync('/boot/cmdline.txt') && isPi()) {
3!
464
      const data = fs.readFileSync('/boot/cmdline.txt', { encoding: 'utf8', flag: 'r' })
×
465
      if (data.includes('console=serial0')) {
×
466
        retError = Error('Serial console is active on /dev/serial0. Use raspi-config to deactivate it')
×
467
      }
468
    }
469
    // for the Ras Pi's inbuilt UART
470
    if (fs.existsSync('/dev/serial0') && isPi()) {
3!
471
      this.serialDevices.push({ value: '/dev/serial0', label: '/dev/serial0', pnpId: '/dev/serial0' })
×
472
    }
473
    if (fs.existsSync('/dev/ttyAMA0') && isPi()) {
3!
474
      //Pi5 uses a different UART name. See https://forums.raspberrypi.com/viewtopic.php?t=359132
475
      this.serialDevices.push({ value: '/dev/ttyAMA0', label: '/dev/ttyAMA0', pnpId: '/dev/ttyAMA0' })
×
476
    }
477
    if (fs.existsSync('/dev/ttyAMA1') && isPi()) {
3!
478
      this.serialDevices.push({ value: '/dev/ttyAMA1', label: '/dev/ttyAMA1', pnpId: '/dev/ttyAMA1' })
×
479
    }
480
    if (fs.existsSync('/dev/ttyAMA2') && isPi()) {
3!
481
      this.serialDevices.push({ value: '/dev/ttyAMA2', label: '/dev/ttyAMA2', pnpId: '/dev/ttyAMA2' })
×
482
    }
483
    if (fs.existsSync('/dev/ttyAMA3') && isPi()) {
3!
484
      this.serialDevices.push({ value: '/dev/ttyAMA3', label: '/dev/ttyAMA3', pnpId: '/dev/ttyAMA3' })
×
485
    }
486
    if (fs.existsSync('/dev/ttyAMA4') && isPi()) {
3!
487
      this.serialDevices.push({ value: '/dev/ttyAMA4', label: '/dev/ttyAMA4', pnpId: '/dev/ttyAMA4' })
×
488
    }
489
    // rpi uart has different name under Ubuntu
490
    const data = await si.osInfo()
3✔
491
    if (data.distro.toString().includes('Ubuntu') && fs.existsSync('/dev/ttyS0') && isPi()) {
3!
492
      // console.log("Running Ubuntu")
493
      this.serialDevices.push({ value: '/dev/ttyS0', label: '/dev/ttyS0', pnpId: '/dev/ttyS0' })
×
494
    }
495
    // jetson serial ports
496
    if (fs.existsSync('/dev/ttyTHS1')) {
3!
497
      this.serialDevices.push({ value: '/dev/ttyTHS1', label: '/dev/ttyTHS1', pnpId: '/dev/ttyTHS1' })
×
498
    }
499
    if (fs.existsSync('/dev/ttyTHS2')) {
3!
500
      this.serialDevices.push({ value: '/dev/ttyTHS2', label: '/dev/ttyTHS2', pnpId: '/dev/ttyTHS2' })
×
501
    }
502
    if (fs.existsSync('/dev/ttyTHS3')) {
3!
503
      this.serialDevices.push({ value: '/dev/ttyTHS3', label: '/dev/ttyTHS3', pnpId: '/dev/ttyTHS3' })
×
504
    }
505

506
    // set the active device as selected
507
    if (this.active && this.activeDevice && this.activeDevice.inputType === 'UART') {
3!
508
      return callback(retError, this.serialDevices, this.baudRates, this.activeDevice.serial,
×
509
        this.activeDevice.baud, this.mavlinkVersions, this.activeDevice.mavversion,
510
        this.active, this.enableHeartbeat, this.enableTCP, this.enableUDPB, this.UDPBPort, this.enableDSRequest, this.tlogging, this.activeDevice.udpInputPort,
511
        this.inputTypes[0], this.inputTypes)
512
    } else if (this.active && this.activeDevice && this.activeDevice.inputType === 'UDP') {
3!
513
      return callback(retError, this.serialDevices, this.baudRates, this.serialDevices.length > 0 ? this.serialDevices[0] : [], this.baudRates[3],
×
514
        this.mavlinkVersions, this.activeDevice.mavversion, this.active, this.enableHeartbeat,
515
        this.enableTCP, this.enableUDPB, this.UDPBPort, this.enableDSRequest, this.tlogging, this.activeDevice.udpInputPort,
516
        this.inputTypes[1], this.inputTypes)
517
    } else {
518
      // no connection
519
      return callback(retError, this.serialDevices, this.baudRates, this.serialDevices.length > 0 ? this.serialDevices[0] : [],
3!
520
        this.baudRates[3], this.mavlinkVersions, this.mavlinkVersions[1], this.active, this.enableHeartbeat,
521
        this.enableTCP, this.enableUDPB, this.UDPBPort, this.enableDSRequest, this.tlogging, 9000, this.inputTypes[0], this.inputTypes)
522
    }
523
  }
524

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

550
  startStopTelemetry (device, baud, mavversion, enableHeartbeat, enableTCP, enableUDPB, UDPBPort, enableDSRequest,
551
                      tlogging, inputType, udpInputPort, callback) {
552
    // user wants to start or stop telemetry
553
    // callback is (err, isSuccessful)
554

555
    this.enableHeartbeat = enableHeartbeat
6✔
556
    this.enableTCP = enableTCP
6✔
557
    this.enableUDPB = enableUDPB
6✔
558
    this.UDPBPort = UDPBPort
6✔
559
    this.enableDSRequest = enableDSRequest
6✔
560
    this.tlogging = tlogging
6✔
561

562
    if (this.m) {
6✔
563
      this.m.enableDSRequest = enableDSRequest
3✔
564
    }
565

566
    // check port, mavversion and baud are valid (if starting telem)
567
    if (!this.active) {
6✔
568
      this.activeDevice = { serial: null, baud: null, inputType: 'UART', mavversion: null, udpInputPort: 9000 }
3✔
569
      for (let i = 0, len = this.mavlinkVersions.length; i < len; i++) {
3✔
570
        if (this.mavlinkVersions[i].value === mavversion.value) {
6✔
571
          this.activeDevice.mavversion = this.mavlinkVersions[i]
3✔
572
          break
3✔
573
        }
574
      }
575

576
      if (inputType.value === 'UART') {
3!
577
        this.activeDevice.inputType = 'UART'
3✔
578
        for (let i = 0, len = this.serialDevices.length; i < len; i++) {
3✔
579
          if (this.serialDevices[i].pnpId === device.pnpId) {
3!
580
            this.activeDevice.serial = this.serialDevices[i]
3✔
581
            break
3✔
582
          }
583
        }
584
        for (let i = 0, len = this.baudRates.length; i < len; i++) {
3✔
585
          if (this.baudRates[i].value === baud.value) {
18✔
586
            this.activeDevice.baud = this.baudRates[i]
3✔
587
            break
3✔
588
          }
589
        }
590

591
        if (this.activeDevice.serial === null || this.activeDevice.baud.value === null || this.activeDevice.serial.value === null || this.activeDevice.mavversion.value === null || this.enableTCP === null) {
3!
592
          this.activeDevice = null
×
593
          this.active = false
×
594
          return callback(new Error('Bad serial device or baud'), false)
×
595
        }
596
      } else if (inputType.value === 'UDP') {
×
597
        // UDP input
598
        this.activeDevice.inputType = 'UDP'
×
599
        this.activeDevice.serial = null
×
600
        this.activeDevice.baud = null
×
601
        this.activeDevice.mavversion = { value: mavversion.value, label: mavversion.label }
×
602
        this.activeDevice.udpInputPort = udpInputPort
×
603
      } else {
604
        // unknown input type
605
        this.activeDevice = null
×
606
        return callback(new Error('Unknown input type'), false)
×
607
      }
608

609
      // this.activeDevice = {inputType, udpInputPort, serial: device, baud: baud};
610
      this.startLink((err) => {
3✔
611
        if (err) {
3!
612
          console.log("Can't open found FC " + this.activeDevice.serial.value + ', resetting link')
×
613
          this.activeDevice = null
×
614
        } else {
615
          // start timeout function for auto-reconnect
616
          this.startInterval()
3✔
617
          this.saveSerialSettings()
3✔
618
        }
619
        return callback(err, this.activeDevice !== null)
3✔
620
      })
621
    } else {
622
      // close link
623
      this.activeDevice = null
3✔
624
      this.closeLink(() => {
3✔
625
        this.saveSerialSettings()
3✔
626
        clearInterval(this.intervalObj)
3✔
627
        this.previousConnection = false
3✔
628
        this.m.close()
3✔
629
        this.m = null
3✔
630
        return callback(null, this.activeDevice !== null)
3✔
631
      })
632
    }
633
  }
634

635
  saveSerialSettings () {
636
    // Save the current settings to file
637
    try {
15✔
638
      this.settings.setValue('flightcontroller.activeDevice', this.activeDevice)
15✔
639
      this.settings.setValue('flightcontroller.outputs', this.UDPoutputs)
15✔
640
      this.settings.setValue('flightcontroller.enableHeartbeat', this.enableHeartbeat)
15✔
641
      this.settings.setValue('flightcontroller.enableTCP', this.enableTCP)
15✔
642
      this.settings.setValue('flightcontroller.enableUDPB', this.enableUDPB)
15✔
643
      this.settings.setValue('flightcontroller.UDPBPort', this.UDPBPort)
15✔
644
      this.settings.setValue('flightcontroller.enableDSRequest', this.enableDSRequest)
15✔
645
      this.settings.setValue('flightcontroller.tlogging', this.tlogging)
15✔
646
      this.settings.setValue('flightcontroller.active', this.active)
15✔
647
      console.log('Saved FC settings')
15✔
648
    } catch (e) {
649
      console.log(e)
×
650
    }
651
  }
652
}
653

654
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