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

stephendade / Rpanion-server / 19757474591

28 Nov 2025 07:49AM UTC coverage: 35.792% (+1.3%) from 34.54%
19757474591

Pull #344

github

web-flow
Merge f6fedd88d into 0fb9accdf
Pull Request #344: Finalsv12

330 of 1203 branches covered (27.43%)

Branch coverage included in aggregate %.

77 of 223 new or added lines in 6 files covered. (34.53%)

279 existing lines in 2 files now uncovered.

1058 of 2675 relevant lines covered (39.55%)

3.51 hits per line

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

55.26
/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.tlogging = false
15✔
70

71
    // Is the connection active?
72
    this.active = false
15✔
73

74
    // mavlink-routerd path
75
    this.mavlinkRouterPath = null
15✔
76

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

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

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

149

150

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

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

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

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

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

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

196
    return this.getUDPOutputs()
6✔
197
  }
198

199
  removeUDPOutput (remIP, remPort) {
200
    // remove new udp output
201

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

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

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

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

232
        return this.getUDPOutputs()
3✔
233
      }
234
    }
235

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

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

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

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

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

288
  startLink (callback) {
289
    // start the serial link
290
    if (this.activeDevice.inputType === 'UDP') {
3!
291
      console.log('Opening UDP Link ' + '0.0.0.0:' + this.activeDevice.udpInputPort + ', MAV v' + this.activeDevice.mavversion)
×
292
    } else {
293
      console.log('Opening UART Link ' + this.activeDevice.serial + ' @ ' + this.activeDevice.baud + ', MAV v' + this.activeDevice.mavversion)
3✔
294
    }
295
    // this.outputs.push({ IP: newIP, port: newPort })
296

297
    // build up the commandline for mavlink-router
298
    const cmd = ['-e', '127.0.0.1:14540', '--tcp-port']
3✔
299
    if (this.enableTCP === true) {
3!
300
      cmd.push('5760')
3✔
301
    } else {
302
      cmd.push('0')
×
303
    }
304
    for (let i = 0, len = this.UDPoutputs.length; i < len; i++) {
3✔
305
      cmd.push('-e')
×
306
      cmd.push(this.UDPoutputs[i].IP + ':' + this.UDPoutputs[i].port)
×
307
    }
308
    cmd.push('--log')
3✔
309
    cmd.push(logpaths.flightsLogsDir)
3✔
310
    if (this.tlogging === true) {
3!
311
      cmd.push('--telemetry-log')
×
312
    }
313
    if (this.enableUDPB === true) {
3!
314
      cmd.push('0.0.0.0:' + this.UDPBPort)
×
315
    }
316
    if (this.activeDevice.inputType === 'UART') {
3!
317
      const serialPath = getSerialPathFromValue(this.activeDevice.serial, this.serialDevices)
3✔
318
      cmd.push(serialPath + ':' + this.activeDevice.baud)
3✔
319
    } else if (this.activeDevice.inputType === 'UDP') {
×
320
      cmd.push('0.0.0.0:' + this.activeDevice.udpInputPort)
×
321
    }
322
    console.log(cmd)
3✔
323

324
    // check mavlink-router exists
325
    if (!this.validMavlinkRouter()) {
3!
326
      console.log('Could not find mavlink-routerd')
×
327
      this.active = false
×
328
      return callback('Could not find mavlink-routerd', false)
×
329
    }
330

331
    // start mavlink-router
332
    this.router = spawn(this.mavlinkRouterPath, cmd)
3✔
333
    this.router.stdout.on('data', (data) => {
3✔
334
      console.log(`stdout: ${data}`)
×
335
    })
336

337
    this.router.stderr.on('data', (data) => {
3✔
338
      console.error(`stderr: ${data}`)
3✔
339
      if (data.toString().includes('Logging target') && data.toString().includes('.bin')) {
3!
340
        // remove old log, if it exists and is >60kB
341
        try {
×
UNCOV
342
          if (this.binlog !== null) {
×
UNCOV
343
            const fileStat = fs.lstatSync(this.binlog)
×
UNCOV
344
            if (Math.round(fileStat.size / 1024) < 60) {
×
345
              fs.unlinkSync(this.binlog)
×
346
            }
347
          }
348
        } catch (err) {
UNCOV
349
          console.log(err)
×
350
        }
UNCOV
351
        const res = data.toString().split(' ')
×
352
        const curLog = (res[res.length - 1]).trim()
×
UNCOV
353
        this.binlog = path.join(logpaths.flightsLogsDir, curLog)
×
UNCOV
354
        console.log('Current log is: ' + this.binlog)
×
355
      }
356
    })
357

358
    this.router.on('close', (code) => {
3✔
359
      console.log(`child process exited with code ${code}`)
3✔
360
      console.log('Closed Router')
3✔
361
      this.eventEmitter.emit('stopLink')
3✔
362
    })
363

364
    console.log('Opened Router')
3✔
365

366
    // only restart the mavlink processor if it's a new link,
367
    // not a reconnect attempt
368
    if (this.m === null) {
3!
369
      this.m = new mavManager(this.activeDevice.mavversion, '127.0.0.1', 14540, this.enableDSRequest)
3✔
370
      this.m.eventEmitter.on('gotMessage', (packet, data) => {
3✔
371
        // got valid message - send on to attached classes
372
        this.previousConnection = true
×
373
        this.eventEmitter.emit('gotMessage', packet, data)
×
374
      })
375
    }
376

377
    // arming events - just pass them on
378
    this.m.eventEmitter.on('armed', () => {
3✔
UNCOV
379
      this.eventEmitter.emit('armed')
×
380
    })
381
    this.m.eventEmitter.on('disarmed', () => {
3✔
382
      this.eventEmitter.emit('disarmed')
×
383
    })
384
    this.eventEmitter.emit('newLink')
3✔
385

386
    this.active = true
3✔
387
    return callback(null, true)
3✔
388
  }
389

390
  closeLink (callback) {
391
    // stop the serial link
392
    this.active = false
3✔
393
    if (this.router && this.router.exitCode === null) {
3!
394
      this.router.kill('SIGINT')
3✔
395
      console.log('Trying to close router')
3✔
396
      return callback(null)
3✔
397
    } else {
398
      console.log('Already Closed Router')
×
399
      this.eventEmitter.emit('stopLink')
×
UNCOV
400
      return callback(null)
×
401
    }
402
  }
403

404
  checkSerialPortIssues () {
405
    // Check if ModemManager is installed
406
    if (isModemManagerInstalled()) {
3!
NEW
407
      return new Error('The ModemManager package is installed. This must be uninstalled (via sudo apt remove modemmanager), due to conflicts with serial ports')
×
408
    }
409

410
    // Check if serial console is active on Raspberry Pi
411
    if (fs.existsSync('/boot/cmdline.txt') && isPi()) {
3!
UNCOV
412
      const data = fs.readFileSync('/boot/cmdline.txt', { encoding: 'utf8', flag: 'r' })
×
UNCOV
413
      if (data.includes('console=serial0')) {
×
NEW
UNCOV
414
        return new Error('Serial console is active on /dev/serial0. Use raspi-config to deactivate it')
×
415
      }
416
    }
417

418
    return null
3✔
419
  }
420

421
  async getDeviceSettings (callback) {
422
    // get all serial devices
423
    this.serialDevices = []
3✔
424
    let retError = null
3✔
425

426
    // Detect all serial devices using hardwareDetection module
427
    this.serialDevices = await detectSerialDevices()
3✔
428

429
    // Check for configuration issues
430
    retError = this.checkSerialPortIssues()
3✔
431

432
    // set the active device as selected
433
    if (this.active && this.activeDevice && this.activeDevice.inputType === 'UART') {
3!
NEW
UNCOV
434
      return callback(retError, this.serialDevices, this.baudRates, this.activeDevice.serial,
×
435
        this.activeDevice.baud, this.mavlinkVersions, this.activeDevice.mavversion,
436
        this.active, this.enableHeartbeat, this.enableTCP, this.enableUDPB, this.UDPBPort, this.enableDSRequest, this.tlogging, this.activeDevice.udpInputPort,
437
        this.inputTypes[0].value, this.inputTypes)
438
    } else if (this.active && this.activeDevice && this.activeDevice.inputType === 'UDP') {
3!
UNCOV
439
      return callback(retError, this.serialDevices, this.baudRates, this.serialDevices.length > 0 ? this.serialDevices[0].value : [], this.baudRates[3].value,
×
440
        this.mavlinkVersions, this.activeDevice.mavversion, this.active, this.enableHeartbeat,
441
        this.enableTCP, this.enableUDPB, this.UDPBPort, this.enableDSRequest, this.tlogging, this.activeDevice.udpInputPort,
442
        this.inputTypes[1].value, this.inputTypes)
443
    } else {
444
      // no connection
445
      return callback(retError, this.serialDevices, this.baudRates, this.serialDevices.length > 0 ? this.serialDevices[0].value : [],
3!
446
        this.baudRates[3].value, this.mavlinkVersions, this.mavlinkVersions[1].value, this.active, this.enableHeartbeat,
447
        this.enableTCP, this.enableUDPB, this.UDPBPort, this.enableDSRequest, this.tlogging, 9000, this.inputTypes[0].value, this.inputTypes)
448
    }
449
  }
450

451
  startInterval () {
452
    // start the 1-sec loop checking for disconnects
453
    this.intervalObj = setInterval(() => {
3✔
454
    
455
    // Send heartbeats, if they are enabled
456
    if(this.enableHeartbeat){
×
457
      this.m.sendHeartbeat()
×
458
    }
459
      // check for timeouts in serial link (ie disconnected cable or reboot)
UNCOV
460
      if (this.m && this.m.conStatusInt() === -1) {
×
UNCOV
461
        console.log('Trying to reconnect FC...')
×
UNCOV
462
        this.closeLink(() => {
×
463
          this.startLink((err) => {
×
464
            if (err) {
×
465
              console.log(err)
×
466
            } else {
467
              // DS request is in this.m.restart()
UNCOV
468
              this.m.restart()
×
469
            }
470
          })
471
        })
472
      }
473
    }, 1000)
474
  }
475

476
  startStopTelemetry (device, baud, mavversion, enableHeartbeat, enableTCP, enableUDPB, UDPBPort, enableDSRequest,
477
                      tlogging, inputType, udpInputPort, callback) {
478
    // user wants to start or stop telemetry
479
    // callback is (err, isSuccessful)
480

481
    this.enableHeartbeat = enableHeartbeat
6✔
482
    this.enableTCP = enableTCP
6✔
483
    this.enableUDPB = enableUDPB
6✔
484
    this.UDPBPort = UDPBPort
6✔
485
    this.enableDSRequest = enableDSRequest
6✔
486
    this.tlogging = tlogging
6✔
487

488
    if (this.m) {
6✔
489
      this.m.enableDSRequest = enableDSRequest
3✔
490
    }
491

492
    // check port, mavversion and baud are valid (if starting telem)
493
    if (!this.active) {
6✔
494
      this.activeDevice = { serial: null, baud: null, inputType: 'UART', mavversion: null, udpInputPort: 9000 }
3✔
495
      this.activeDevice.mavversion = mavversion
3✔
496

497
      if (inputType === 'UART') {
3!
498
        this.activeDevice.inputType = 'UART'
3✔
499
        for (let i = 0, len = this.serialDevices.length; i < len; i++) {
3✔
500
          if (this.serialDevices[i].value === device) {
3!
501
            this.activeDevice.serial = this.serialDevices[i].value
3✔
502
            break
3✔
503
          }
504
        }
505
        for (let i = 0, len = this.baudRates.length; i < len; i++) {
3✔
506
          if (this.baudRates[i].value === baud) {
18✔
507
            this.activeDevice.baud = this.baudRates[i].value
3✔
508
            break
3✔
509
          }
510
        }
511
        console.log('Selected device: ' + device + ' @ ' + baud)
3✔
512
        console.log(this.activeDevice)
3✔
513

514
        if (this.activeDevice.serial === null || this.activeDevice.baud === null || this.activeDevice.serial.value === null || this.activeDevice.mavversion === null || this.enableTCP === null) {
3!
UNCOV
515
          this.activeDevice = null
×
UNCOV
516
          this.active = false
×
UNCOV
517
          return callback(new Error('Bad serial device or baud'), false)
×
518
        }
UNCOV
519
      } else if (inputType === 'UDP') {
×
520
        // UDP input
521
        this.activeDevice.inputType = 'UDP'
×
522
        this.activeDevice.serial = null
×
UNCOV
523
        this.activeDevice.baud = null
×
UNCOV
524
        this.activeDevice.mavversion = mavversion
×
525
        this.activeDevice.udpInputPort = udpInputPort
×
526
      } else {
527
        // unknown input type
528
        this.activeDevice = null
×
529
        return callback(new Error('Unknown input type'), false)
×
530
      }
531

532
      // this.activeDevice = {inputType, udpInputPort, serial: device, baud: baud};
533
      this.startLink((err) => {
3✔
534
        if (err) {
3!
UNCOV
535
          console.log(err)
×
UNCOV
536
          this.activeDevice = null
×
537
        } else {
538
          // start timeout function for auto-reconnect
539
          this.startInterval()
3✔
540
          this.saveSerialSettings()
3✔
541
        }
542
        return callback(err, this.activeDevice !== null)
3✔
543
      })
544
    } else {
545
      // close link
546
      this.activeDevice = null
3✔
547
      this.closeLink(() => {
3✔
548
        this.saveSerialSettings()
3✔
549
        clearInterval(this.intervalObj)
3✔
550
        this.previousConnection = false
3✔
551
        this.m.close()
3✔
552
        this.m = null
3✔
553
        return callback(null, this.activeDevice !== null)
3✔
554
      })
555
    }
556
  }
557

558
  saveSerialSettings () {
559
    // Save the current settings to file
560
    try {
15✔
561
      this.settings.setValue('flightcontroller.activeDevice', this.activeDevice)
15✔
562
      this.settings.setValue('flightcontroller.outputs', this.UDPoutputs)
15✔
563
      this.settings.setValue('flightcontroller.enableHeartbeat', this.enableHeartbeat)
15✔
564
      this.settings.setValue('flightcontroller.enableTCP', this.enableTCP)
15✔
565
      this.settings.setValue('flightcontroller.enableUDPB', this.enableUDPB)
15✔
566
      this.settings.setValue('flightcontroller.UDPBPort', this.UDPBPort)
15✔
567
      this.settings.setValue('flightcontroller.enableDSRequest', this.enableDSRequest)
15✔
568
      this.settings.setValue('flightcontroller.tlogging', this.tlogging)
15✔
569
      this.settings.setValue('flightcontroller.active', this.active)
15✔
570
      console.log('Saved FC settings')
15✔
571
    } catch (e) {
UNCOV
572
      console.log(e)
×
573
    }
574
  }
575
}
576

577
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