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

stephendade / Rpanion-server / 19360612817

14 Nov 2025 09:43AM UTC coverage: 34.683% (+0.1%) from 34.547%
19360612817

Pull #343

github

web-flow
Merge ae5d17ea3 into 2164b81a9
Pull Request #343: Add Orange Pi Zero 3 support

328 of 1210 branches covered (27.11%)

Branch coverage included in aggregate %.

23 of 51 new or added lines in 5 files covered. (45.1%)

168 existing lines in 3 files now uncovered.

1008 of 2642 relevant lines covered (38.15%)

2.61 hits per line

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

54.16
/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
function isOrangePi () {
32
  let cpuInfo = ''
3✔
33
  try {
3✔
34
    cpuInfo = fs.readFileSync('/proc/device-tree/compatible', { encoding: 'utf8' })
3✔
35
  } catch (e) {
36
    // if this fails, this is probably not an Orange Pi
37
    return false
3✔
38
  }
39

NEW
40
  return cpuInfo.toLowerCase().includes('orangepi')
×
41
}
42

43
class FCDetails {
44
  constructor (settings) {
45
    // if the device was successfully opend and got packets
46
    this.previousConnection = false
15✔
47

48
    // all detected serial ports and baud rates
49
    this.serialDevices = []
15✔
50
    this.baudRates = [{ value: 9600, label: '9600' },
15✔
51
      { value: 19200, label: '19200' },
52
      { value: 38400, label: '38400' },
53
      { value: 57600, label: '57600' },
54
      { value: 111100, label: '111100' },
55
      { value: 115200, label: '115200' },
56
      { value: 230400, label: '230400' },
57
      { value: 256000, label: '256000' },
58
      { value: 460800, label: '460800' },
59
      { value: 500000, label: '500000' },
60
      { value: 921600, label: '921600' },
61
      { value: 1500000, label: '1500000' }]
62
    this.mavlinkVersions = [{ value: 1, label: '1.0' },
15✔
63
      { value: 2, label: '2.0' }]
64
    this.inputTypes = [{ value: 'UART', label: 'UART' },
15✔
65
      { value: 'UDP', label: 'UDP Server' }]
66
    // JSON of active device (input type, port and baud and mavversion). User selected
67
    // null if user selected no link (or no serial port of that name)
68
    this.activeDevice = null
15✔
69

70
    // mavlink-router process
71
    this.router = null
15✔
72

73
    // the mavlink manager object
74
    this.m = null
15✔
75

76
    // For sending events outside of object
77
    this.eventEmitter = new events.EventEmitter()
15✔
78

79
    // Interval to check connection status and re-connect
80
    // if required
81
    this.intervalObj = null
15✔
82

83
    // UDP Outputs
84
    this.UDPoutputs = []
15✔
85

86
    // Send out MAVLink heartbeat packets?
87
    this.enableHeartbeat = false
15✔
88
  
89
    // Use TCP output?
90
    this.enableTCP = false
15✔
91

92
    // Use UDP Broadcast?
93
    this.enableUDPB = true
15✔
94
    this.UDPBPort = 14550
15✔
95

96
    // Send datastream requests to flight controller?
97
    this.enableDSRequest = false
15✔
98

99
    // Current binlog via mavlink-router
100
    this.binlog = null
15✔
101

102
    this.tlogging = false
15✔
103

104
    // Is the connection active?
105
    this.active = false
15✔
106

107
    // mavlink-routerd path
108
    this.mavlinkRouterPath = null
15✔
109

110
    // load settings
111
    this.settings = settings
15✔
112
    this.activeDevice = this.settings.value('flightcontroller.activeDevice', null)
15✔
113
    this.UDPoutputs = this.settings.value('flightcontroller.outputs', [])
15✔
114
    this.enableHeartbeat = this.settings.value('flightcontroller.enableHeartbeat', false)
15✔
115
    this.enableTCP = this.settings.value('flightcontroller.enableTCP', false)
15✔
116
    this.enableUDPB = this.settings.value('flightcontroller.enableUDPB', true)
15✔
117
    this.UDPBPort = this.settings.value('flightcontroller.UDPBPort', 14550)
15✔
118
    this.enableDSRequest = this.settings.value('flightcontroller.enableDSRequest', false)
15✔
119
    this.tlogging = this.settings.value('flightcontroller.tlogging', false)
15✔
120
    this.active = this.settings.value('flightcontroller.active', false)
15✔
121

122
    if (this.active) {
15!
123
      // restart link if saved serial device is found
124
      this.getDeviceSettings((err, devices) => {
×
125
        if (this.activeDevice.inputType === 'UART') {
×
126
          let found = false
×
127
          for (let i = 0, len = devices.length; i < len; i++) {
×
128
            if (this.activeDevice.serial.value === devices[i].value) {
×
129
              found = true
×
130
              this.startLink((err) => {
×
131
                if (err) {
×
132
                  console.log("Can't open found FC " + this.activeDevice.serial.value + ', resetting link')
×
133
                  this.activeDevice = null
×
134
                  this.active = false
×
135
                }
136
                this.startInterval()
×
137
              })
138
              break
×
139
            }
140
          }
141
          if (!found) {
×
142
            console.log("Can't open saved connection, resetting")
×
143
            this.activeDevice = null
×
144
            this.active = false
×
145
          }
146
        } else if (this.activeDevice.inputType === 'UDP') {
×
147
          this.startLink((err) => {
×
148
            if (err) {
×
149
              console.log("Can't open UDP port " + this.activeDevice.udpInputPort + ', resetting link')
×
150
              this.activeDevice = null
×
151
              this.active = false
×
152
            }
153
            this.startInterval()
×
154
          })
155
        }
156
      })
157
    }
158
  }
159

160
  validMavlinkRouter () {
161
    // check mavlink-router is installed and updates folder
162
    const ls = spawnSync('which', ['mavlink-routerd'])
3✔
163
    console.log(ls.stdout.toString())
3✔
164
    if (ls.stdout.toString().trim() == '') {
3!
165
      // also check the parent directory
166
      const parentDir = path.dirname(__dirname)
3✔
167
      const mavlinkRouterPath = path.join(parentDir, 'mavlink-routerd')
3✔
168
      if (fs.existsSync(mavlinkRouterPath)) {
3!
169
        console.log('Found mavlink-routerd in ' + parentDir)
3✔
170
        this.mavlinkRouterPath = parentDir + "/mavlink-routerd"
3✔
171
        return true
3✔
172
      }
173
      this.mavlinkRouterPath = null
×
174
      return false
×
175
    } else {
176
      console.log('Found mavlink-routerd in ' + ls.stdout.toString().trim())
×
177
      this.mavlinkRouterPath = ls.stdout.toString().trim()
×
178
      return true
×
179
    }
180
  }
181

182
  isModemManagerInstalled () {
183
    // check ModemManager is installed
184
    const ls = spawnSync('which', ['ModemManager'])
3✔
185
    console.log(ls.stdout.toString())
3✔
186
    if (ls.stdout.toString().includes('ModemManager')) {
3!
187
      return true
×
188
    } else {
189
      return false
3✔
190
    }
191
  }
192

193
  getUDPOutputs () {
194
    // get list of current UDP outputs
195
    const ret = []
33✔
196
    for (let i = 0, len = this.UDPoutputs.length; i < len; i++) {
33✔
197
      ret.push({ IPPort: this.UDPoutputs[i].IP + ':' + this.UDPoutputs[i].port })
36✔
198
    }
199
    return ret
33✔
200
  }
201

202
  addUDPOutput (newIP, newPort) {
203
    // add a new udp output, if not already in
204
    // check if this ip:port is already in the list
205
    for (let i = 0, len = this.UDPoutputs.length; i < len; i++) {
9✔
206
      if (this.UDPoutputs[i].IP === newIP && this.UDPoutputs[i].port === newPort) {
6✔
207
        return this.getUDPOutputs()
3✔
208
      }
209
    }
210

211
    // check that it's not the internal 127.0.0.1:14540
212
    if (newIP === '127.0.0.1' && newPort === 14540) {
6!
213
      return this.getUDPOutputs()
×
214
    }
215

216
    // add it in
217
    this.UDPoutputs.push({ IP: newIP, port: newPort })
6✔
218
    console.log('Added UDP Output ' + newIP + ':' + newPort)
6✔
219

220
    // restart mavlink-router, if link active
221
    if (this.m) {
6!
222
      this.closeLink(() => {
×
223
        this.startLink((err) => {
×
224
          if (err) {
×
225
            console.log(err)
×
226
          }
227
        })
228
      })
229
    }
230

231
    // try to save. Will be invalid if running under test runner
232
    try {
6✔
233
      this.saveSerialSettings()
6✔
234
    } catch (e) {
235
      console.log(e)
×
236
    }
237

238
    return this.getUDPOutputs()
6✔
239
  }
240

241
  removeUDPOutput (remIP, remPort) {
242
    // remove new udp output
243

244
    // check that it's not the internal 127.0.0.1:14540
245
    if (remIP === '127.0.0.1' && remPort === 14540) {
6!
246
      return this.getUDPOutputs()
×
247
    }
248

249
    // check if this ip:port is already in the list
250
    for (let i = 0, len = this.UDPoutputs.length; i < len; i++) {
6✔
251
      if (this.UDPoutputs[i].IP === remIP && this.UDPoutputs[i].port === remPort) {
9✔
252
        // and remove
253
        this.UDPoutputs.splice(i, 1)
3✔
254
        console.log('Removed UDP Output ' + remIP + ':' + remPort)
3✔
255

256
        // restart mavlink-router, if link active
257
        if (this.m) {
3!
258
          this.closeLink(() => {
×
259
            this.startLink((err) => {
×
260
              if (err) {
×
261
                console.log(err)
×
262
              }
263
            })
264
          })
265
        }
266

267
        // try to save. Will be invalid if running under test runner
268
        try {
3✔
269
          this.saveSerialSettings()
3✔
270
        } catch (e) {
271
          console.log(e)
×
272
        }
273

274
        return this.getUDPOutputs()
3✔
275
      }
276
    }
277

278
    return this.getUDPOutputs()
3✔
279
  }
280

281
  getSystemStatus () {
282
    // get the system status
283
    if (this.m !== null) {
3!
284
      return {
×
285
        numpackets: this.m.statusNumRxPackets,
286
        FW: this.m.autopilotFromID(),
287
        vehType: this.m.vehicleFromID(),
288
        conStatus: this.m.conStatusStr(),
289
        statusText: this.m.statusText,
290
        byteRate: this.m.statusBytesPerSec.avgBytesSec,
291
        fcVersion: this.m.fcVersion
292
      }
293
    } else {
294
      return {
3✔
295
        numpackets: 0,
296
        FW: '',
297
        vehType: '',
298
        conStatus: 'Not connected',
299
        statusText: '',
300
        byteRate: 0,
301
        fcVersion: ''
302
      }
303
    }
304
  }
305

306
  rebootFC () {
307
    // command the flight controller to reboot
308
    if (this.m !== null) {
×
309
      console.log('Rebooting FC')
×
310
      this.m.sendReboot()
×
311
    }
312
  }
313

314
  startBinLogging () {
315
    // command the flight controller to start streaming bin log
316
    if (this.m !== null) {
×
317
      console.log('Bin log start request')
×
318
      this.m.sendBinStreamRequest()
×
319
    }
320
  }
321

322
  stopBinLogging () {
323
    // command the flight controller to stop streaming bin log
324
    if (this.m !== null) {
×
325
      console.log('Bin log stop request')
×
326
      this.m.sendBinStreamRequestStop()
×
327
    }
328
  }
329

330
  startLink (callback) {
331
    // start the serial link
332
    if (this.activeDevice.inputType === 'UDP') {
3!
333
      console.log('Opening UDP Link ' + '0.0.0.0:' + this.activeDevice.udpInputPort + ', MAV v' + this.activeDevice.mavversion)
×
334
    } else {
335
      console.log('Opening UART Link ' + this.activeDevice.serial.value + ' @ ' + this.activeDevice.baud + ', MAV v' + this.activeDevice.mavversion)
3✔
336
    }
337
    // this.outputs.push({ IP: newIP, port: newPort })
338

339
    // build up the commandline for mavlink-router
340
    const cmd = ['-e', '127.0.0.1:14540', '--tcp-port']
3✔
341
    if (this.enableTCP === true) {
3!
342
      cmd.push('5760')
3✔
343
    } else {
344
      cmd.push('0')
×
345
    }
346
    for (let i = 0, len = this.UDPoutputs.length; i < len; i++) {
3✔
347
      cmd.push('-e')
×
348
      cmd.push(this.UDPoutputs[i].IP + ':' + this.UDPoutputs[i].port)
×
349
    }
350
    cmd.push('--log')
3✔
351
    cmd.push(logpaths.flightsLogsDir)
3✔
352
    if (this.tlogging === true) {
3!
353
      cmd.push('--telemetry-log')
×
354
    }
355
    if (this.enableUDPB === true) {
3!
356
      cmd.push('0.0.0.0:' + this.UDPBPort)
×
357
    }
358
    if (this.activeDevice.inputType === 'UART') {
3!
359
      cmd.push(this.activeDevice.serial.value + ':' + this.activeDevice.baud)
3✔
360
    } else if (this.activeDevice.inputType === 'UDP') {
×
361
      cmd.push('0.0.0.0:' + this.activeDevice.udpInputPort)
×
362
    }
363
    console.log(cmd)
3✔
364

365
    // check mavlink-router exists
366
    if (!this.validMavlinkRouter()) {
3!
367
      console.log('Could not find mavlink-routerd')
×
368
      this.active = false
×
369
      return callback('Could not find mavlink-routerd', false)
×
370
    }
371

372
    // start mavlink-router
373
    this.router = spawn(this.mavlinkRouterPath, cmd)
3✔
374
    this.router.stdout.on('data', (data) => {
3✔
375
      console.log(`stdout: ${data}`)
×
376
    })
377

378
    this.router.stderr.on('data', (data) => {
3✔
379
      console.error(`stderr: ${data}`)
3✔
380
      if (data.toString().includes('Logging target') && data.toString().includes('.bin')) {
3!
381
        // remove old log, if it exists and is >60kB
382
        try {
×
383
          if (this.binlog !== null) {
×
384
            const fileStat = fs.lstatSync(this.binlog)
×
385
            if (Math.round(fileStat.size / 1024) < 60) {
×
386
              fs.unlinkSync(this.binlog)
×
387
            }
388
          }
389
        } catch (err) {
390
          console.log(err)
×
391
        }
392
        const res = data.toString().split(' ')
×
393
        const curLog = (res[res.length - 1]).trim()
×
394
        this.binlog = path.join(logpaths.flightsLogsDir, curLog)
×
395
        console.log('Current log is: ' + this.binlog)
×
396
      }
397
    })
398

399
    this.router.on('close', (code) => {
3✔
400
      console.log(`child process exited with code ${code}`)
3✔
401
      console.log('Closed Router')
3✔
402
      this.eventEmitter.emit('stopLink')
3✔
403
    })
404

405
    console.log('Opened Router')
3✔
406

407
    // only restart the mavlink processor if it's a new link,
408
    // not a reconnect attempt
409
    if (this.m === null) {
3!
410
      this.m = new mavManager(this.activeDevice.mavversion, '127.0.0.1', 14540, this.enableDSRequest)
3✔
411
      this.m.eventEmitter.on('gotMessage', (packet, data) => {
3✔
412
        // got valid message - send on to attached classes
413
        this.previousConnection = true
×
414
        this.eventEmitter.emit('gotMessage', packet, data)
×
415
      })
416
    }
417

418
    // arming events - just pass them on
419
    this.m.eventEmitter.on('armed', () => {
3✔
420
      this.eventEmitter.emit('armed')
×
421
    })
422
    this.m.eventEmitter.on('disarmed', () => {
3✔
423
      this.eventEmitter.emit('disarmed')
×
424
    })
425
    this.eventEmitter.emit('newLink')
3✔
426

427
    this.active = true
3✔
428
    return callback(null, true)
3✔
429
  }
430

431
  closeLink (callback) {
432
    // stop the serial link
433
    this.active = false
3✔
434
    if (this.router && this.router.exitCode === null) {
3!
435
      this.router.kill('SIGINT')
3✔
436
      console.log('Trying to close router')
3✔
437
      return callback(null)
3✔
438
    } else {
439
      console.log('Already Closed Router')
×
440
      this.eventEmitter.emit('stopLink')
×
441
      return callback(null)
×
442
    }
443
  }
444

445
  async getDeviceSettings (callback) {
446
    // get all serial devices
447
    this.serialDevices = []
3✔
448
    let retError = null
3✔
449

450
    const Binding = autoDetect()
3✔
451
    const ports = await Binding.list()
3✔
452

453
    for (let i = 0, len = ports.length; i < len; i++) {
3✔
454
      if (ports[i].pnpId !== undefined) {
96!
455
        // usb-ArduPilot_Pixhawk1-1M_32002A000847323433353231-if00
456
        // console.log("Port: ", ports[i].pnpID);
457
        let namePorts = ''
×
458
        if (ports[i].pnpId.split('_').length > 2) {
×
459
          namePorts = ports[i].pnpId.split('_')[1] + ' (' + ports[i].path + ')'
×
460
        } else {
461
          namePorts = ports[i].manufacturer + ' (' + ports[i].path + ')'
×
462
        }
463
        // console.log("Port: ", ports[i].pnpID);
464
        this.serialDevices.push({ value: ports[i].path, label: namePorts, pnpId: ports[i].pnpId })
×
465
      } else if (ports[i].manufacturer !== undefined) {
96!
466
        // on recent RasPiOS, the pnpID is undefined :(
467
        const nameports = ports[i].manufacturer + ' (' + ports[i].path + ')'
×
468
        this.serialDevices.push({ value: ports[i].path, label: nameports, pnpId: nameports })
×
469
      }
470
    }
471
    // if the serial console or modemmanager are active on the Pi, return error
472
    if (this.isModemManagerInstalled()) {
3!
473
      retError = Error('The ModemManager package is installed. This must be uninstalled (via sudo apt remove modemmanager), due to conflicts with serial ports')
×
474
    }
475
    if (fs.existsSync('/boot/cmdline.txt') && isPi()) {
3!
476
      const data = fs.readFileSync('/boot/cmdline.txt', { encoding: 'utf8', flag: 'r' })
×
477
      if (data.includes('console=serial0')) {
×
478
        retError = Error('Serial console is active on /dev/serial0. Use raspi-config to deactivate it')
×
479
      }
480
    }
481
    // for the Ras Pi's inbuilt UART
482
    if (fs.existsSync('/dev/serial0') && isPi()) {
3!
483
      this.serialDevices.push({ value: '/dev/serial0', label: '/dev/serial0', pnpId: '/dev/serial0' })
×
484
    }
485
    if (fs.existsSync('/dev/ttyAMA0') && isPi()) {
3!
486
      //Pi5 uses a different UART name. See https://forums.raspberrypi.com/viewtopic.php?t=359132
487
      this.serialDevices.push({ value: '/dev/ttyAMA0', label: '/dev/ttyAMA0', pnpId: '/dev/ttyAMA0' })
×
488
    }
489
    if (fs.existsSync('/dev/ttyAMA1') && isPi()) {
3!
490
      this.serialDevices.push({ value: '/dev/ttyAMA1', label: '/dev/ttyAMA1', pnpId: '/dev/ttyAMA1' })
×
491
    }
492
    if (fs.existsSync('/dev/ttyAMA2') && isPi()) {
3!
493
      this.serialDevices.push({ value: '/dev/ttyAMA2', label: '/dev/ttyAMA2', pnpId: '/dev/ttyAMA2' })
×
494
    }
495
    if (fs.existsSync('/dev/ttyAMA3') && isPi()) {
3!
496
      this.serialDevices.push({ value: '/dev/ttyAMA3', label: '/dev/ttyAMA3', pnpId: '/dev/ttyAMA3' })
×
497
    }
498
    if (fs.existsSync('/dev/ttyAMA4') && isPi()) {
3!
499
      this.serialDevices.push({ value: '/dev/ttyAMA4', label: '/dev/ttyAMA4', pnpId: '/dev/ttyAMA4' })
×
500
    }
501
    // rpi uart has different name under Ubuntu
502
    const data = await si.osInfo()
3✔
503
    if (data.distro.toString().includes('Ubuntu') && fs.existsSync('/dev/ttyS0') && isPi()) {
3!
504
      // console.log("Running Ubuntu")
505
      this.serialDevices.push({ value: '/dev/ttyS0', label: '/dev/ttyS0', pnpId: '/dev/ttyS0' })
×
506
    }
507
    // jetson serial ports
508
    if (fs.existsSync('/dev/ttyTHS1')) {
3!
509
      this.serialDevices.push({ value: '/dev/ttyTHS1', label: '/dev/ttyTHS1', pnpId: '/dev/ttyTHS1' })
×
510
    }
511
    if (fs.existsSync('/dev/ttyTHS2')) {
3!
512
      this.serialDevices.push({ value: '/dev/ttyTHS2', label: '/dev/ttyTHS2', pnpId: '/dev/ttyTHS2' })
×
513
    }
514
    if (fs.existsSync('/dev/ttyTHS3')) {
3!
515
      this.serialDevices.push({ value: '/dev/ttyTHS3', label: '/dev/ttyTHS3', pnpId: '/dev/ttyTHS3' })
×
516
    }
517
    // Orange Pi Zero3 serial ports
518
    if (fs.existsSync('/dev/ttyS5') && isOrangePi()) {
3!
NEW
519
      this.serialDevices.push({ value: '/dev/ttyS5', label: '/dev/ttyS5', pnpId: '/dev/ttyS5' })
×
520
    }
521
    if (fs.existsSync('/dev/ttyAS5') && isOrangePi()) {
3!
NEW
522
      this.serialDevices.push({ value: '/dev/ttyAS5', label: '/dev/ttyAS5', pnpId: '/dev/ttyAS5' })
×
523
    }
524
    // set the active device as selected
525
    if (this.active && this.activeDevice && this.activeDevice.inputType === 'UART') {
3!
526
      return callback(retError, this.serialDevices, this.baudRates, this.activeDevice.serial.value,
×
527
        this.activeDevice.baud, this.mavlinkVersions, this.activeDevice.mavversion,
528
        this.active, this.enableHeartbeat, this.enableTCP, this.enableUDPB, this.UDPBPort, this.enableDSRequest, this.tlogging, this.activeDevice.udpInputPort,
529
        this.inputTypes[0].value, this.inputTypes)
530
    } else if (this.active && this.activeDevice && this.activeDevice.inputType === 'UDP') {
3!
531
      return callback(retError, this.serialDevices, this.baudRates, this.serialDevices.length > 0 ? this.serialDevices[0].value : [], this.baudRates[3].value,
×
532
        this.mavlinkVersions, this.activeDevice.mavversion, this.active, this.enableHeartbeat,
533
        this.enableTCP, this.enableUDPB, this.UDPBPort, this.enableDSRequest, this.tlogging, this.activeDevice.udpInputPort,
534
        this.inputTypes[1].value, this.inputTypes)
535
    } else {
536
      // no connection
537
      return callback(retError, this.serialDevices, this.baudRates, this.serialDevices.length > 0 ? this.serialDevices[0].value : [],
3!
538
        this.baudRates[3].value, this.mavlinkVersions, this.mavlinkVersions[1].value, this.active, this.enableHeartbeat,
539
        this.enableTCP, this.enableUDPB, this.UDPBPort, this.enableDSRequest, this.tlogging, 9000, this.inputTypes[0].value, this.inputTypes)
540
    }
541
  }
542

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

568
  startStopTelemetry (device, baud, mavversion, enableHeartbeat, enableTCP, enableUDPB, UDPBPort, enableDSRequest,
569
                      tlogging, inputType, udpInputPort, callback) {
570
    // user wants to start or stop telemetry
571
    // callback is (err, isSuccessful)
572

573
    this.enableHeartbeat = enableHeartbeat
6✔
574
    this.enableTCP = enableTCP
6✔
575
    this.enableUDPB = enableUDPB
6✔
576
    this.UDPBPort = UDPBPort
6✔
577
    this.enableDSRequest = enableDSRequest
6✔
578
    this.tlogging = tlogging
6✔
579

580
    if (this.m) {
6✔
581
      this.m.enableDSRequest = enableDSRequest
3✔
582
    }
583

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

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

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

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

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

669
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