Skip to content

Commit

Permalink
Video: Send VIDEO_STREAM_INFORMATION to GCS
Browse files Browse the repository at this point in the history
Addresses feature request/issue stephendade#169

Enables Rpanion to respond to send COMMAND_ACK and VIDEO_STREAM_INFORMATION messages via MAVLink in response to a MAV_CMD_REQUEST_MESSAGE.

Adds a Select dropdown to the Video page to select which IP will be transmitted as part of the URI that is sent in the MAVLink message.
  • Loading branch information
ddd999 authored and ddd999 committed Feb 29, 2024
1 parent c619331 commit 2e319f8
Show file tree
Hide file tree
Showing 7 changed files with 192 additions and 27 deletions.
26 changes: 25 additions & 1 deletion mavlink/mavManager.js
Original file line number Diff line number Diff line change
Expand Up @@ -100,8 +100,16 @@ class mavManager {

// send off initial messages
this.sendVersionRequest()

// Respond to MavLink commands that are targeted to the companion computer
} else if ( data.targetSystem === this.targetSystem &&
data.targetComponent == minimal.MavComponent.ONBOARD_COMPUTER &&
packet.header.msgid === common.CommandLong.MSG_ID
){
console.log("Received CommandLong addressed to onboard computer")

} else if (this.targetSystem !== packet.header.sysid) {
// don't use packets from other systems or components in Rpanion-server
//don't use packets from other systems or components in Rpanion-server
return
}

Expand Down Expand Up @@ -266,6 +274,22 @@ class mavManager {
this.sendData(heartbeatMessage, component)
}

sendCommandAck (commandReceived, commandResult = 0, targetSystem = 255, targetComponent = minimal.MavComponent.MISSION_PLANNER) {

// create a CommandAck packet
const commandAck = new common.CommandAck()

commandAck.command = commandReceived
// result = 0 for "accepted and executed"
commandAck.result = commandResult
// resultParam2 is for optional additional result information. Not currently used by rpanion.
commandAck.resultParam2 = 0;
commandAck.targetSystem = targetSystem
commandAck.targetComponent = targetComponent

this.sendData(commandAck)
}

sendReboot () {
// create a reboot packet
const command = new common.PreflightRebootShutdownCommand(this.targetSystem, this.targetComponent)
Expand Down
22 changes: 22 additions & 0 deletions mavlink/mavManager.test.js
Original file line number Diff line number Diff line change
Expand Up @@ -137,6 +137,28 @@ describe('MAVLink Functions', function () {
})
})

it('#commandAckSend()', function (done) {
const m = new mavManager(2, '127.0.0.1', 15000)
const udpStream = udp.createSocket('udp4')

m.eventEmitter.on('linkready', (info) => {
m.sendCommandAck()
})

udpStream.on('message', (msg, rinfo) => {
msg.should.eql(Buffer.from([253, 09, 00, 00, 00, 00, 191, 77, 00, 00, 00, 00, 00, 00, 00, 00, 00, 00, 255, 197, 27 ]))
m.close()
udpStream.close()
done()
})

udpStream.send(Buffer.from([0xfd, 0x06]), 15000, '127.0.0.1', (error) => {
if (error) {
console.error(error)
}
})
})

it('#perfTest()', function () {
// how fast can we process packets and send out over udp?
const m = new mavManager(2, '127.0.0.1', 15000)
Expand Down
79 changes: 65 additions & 14 deletions server/index.js
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@ const compression = require('compression')
const bodyParser = require('body-parser')
const pino = require('express-pino-logger')()
const process = require('process')
const { common } = require('node-mavlink')

const networkManager = require('./networkManager')
const aboutPage = require('./aboutInfo')
Expand Down Expand Up @@ -50,7 +51,7 @@ settings.init({

const vManager = new videoStream(settings, winston)
const fcManager = new fcManagerClass(settings, winston)
const logManager = new flightLogger(winston)
const logManager = new flightLogger(settings, winston)
const ntripClient = new ntrip(settings, winston)
const cloud = new cloudManager(settings)
const logConversion = new logConversionManager(settings)
Expand Down Expand Up @@ -80,20 +81,45 @@ ntripClient.eventEmitter.on('rtcmpacket', (msg, seq) => {
}
})

// Got a VIDEO_STREAM_INFORMATION message, send to flight controller
// to do: get target system and component from vManager
vManager.eventEmitter.on('videostreaminfo', (msg, senderSysId, senderCompId) => {
try {
if (fcManager.m) {
fcManager.m.sendCommandAck(common.VideoStreamInformation.MSG_ID, 0, senderSysId, senderCompId)
fcManager.m.sendData(msg)
}
} catch (err) {
console.log(err)
}
})

// Connecting the flight controller datastream to the logger
// and ntrip
// and ntrip and video
fcManager.eventEmitter.on('gotMessage', (packet, data) => {
try {
logManager.writetlog(packet, data)
ntripClient.onMavPacket(packet, data)
vManager.onMavPacket(packet, data)
} catch (err) {
console.log(err)
}
})

fcManager.eventEmitter.on('newLink', () => {
try {
logManager.newtlog()
} catch (err) {
console.log(err)
}
})

fcManager.eventEmitter.on('stopLink', () => {
try {
logManager.stoptlog()
} catch (err) {
console.log(err)
}
})

fcManager.eventEmitter.on('armed', () => {
Expand Down Expand Up @@ -357,9 +383,9 @@ app.use('/logdownload', express.static(path.join(__dirname, '..', '/flightlogs')
app.use('/rplogs', express.static(path.join(__dirname, '..', '/logs')))

app.get('/api/logfiles', (req, res) => {
logManager.getLogs((err, tlogs, binlogs, kmzlogs) => {
logManager.getLogs((err, tlogs, binlogs, kmzlogs, activeLogging) => {
res.setHeader('Content-Type', 'application/json')
res.send(JSON.stringify({ TlogFiles: tlogs, BinlogFiles: binlogs, KMZlogFiles: kmzlogs, url: req.protocol + '://' + req.headers.host }))
res.send(JSON.stringify({ enablelogging: activeLogging, TlogFiles: tlogs, BinlogFiles: binlogs, KMZlogFiles: kmzlogs, url: req.protocol + '://' + req.headers.host, logStatus: logManager.getStatus() }))
})
})

Expand All @@ -375,6 +401,31 @@ app.post('/api/deletelogfiles', [check('logtype').isIn(['tlog', 'binlog', 'kmzlo
res.send(JSON.stringify({}))
})

app.get('/api/newlogfile', (req, res) => {
logManager.newtlog()
// console.log(logConversion.tlogfilename)
res.setHeader('Content-Type', 'application/json')
res.send(JSON.stringify({}))
})

app.get('/api/tlogfilename', (req, res) => {
// console.log(logManager.activeFileTlog)
res.setHeader('Content-Type', 'application/json')
res.send(JSON.stringify({ tlogfilename: logManager.activeFileTlog }))
})

app.post('/api/logenable', [check('enable').isBoolean()], function (req, res) {
// User wants to enable/disable logging
const errors = validationResult(req)
if (!errors.isEmpty()) {
winston.error('Bad POST vars in /api/logenable', { message: JSON.stringify(errors.array()) })
return res.status(422).json({ error: JSON.stringify(errors.array()) })
}

res.setHeader('Content-Type', 'application/json')
res.send(JSON.stringify({ enablelogging: logManager.setLogging(req.body.enable) }))
})

app.get('/api/softwareinfo', (req, res) => {
aboutPage.getSoftwareInfo((OSV, NodeV, RpanionV, hostname, err) => {
if (!err) {
Expand All @@ -391,10 +442,11 @@ app.get('/api/softwareinfo', (req, res) => {

app.get('/api/videodevices', (req, res) => {
vManager.populateAddresses()
vManager.getVideoDevices((err, devices, active, seldevice, selRes, selRot, selbitrate, selfps, SeluseUDP, SeluseUDPIP, SeluseUDPPort, timestamp, fps, FPSMax, vidres) => {
vManager.getVideoDevices((err, devices, active, seldevice, selRes, selRot, selbitrate, selfps, SeluseUDP, SeluseUDPIP, SeluseUDPPort, timestamp, fps, FPSMax, vidres, selMavURI) => {
if (!err) {
res.setHeader('Content-Type', 'application/json')
res.send(JSON.stringify({
ifaces: vManager.ifaces,
dev: devices,
vidDeviceSelected: seldevice,
vidres: vidres,
Expand All @@ -410,7 +462,8 @@ app.get('/api/videodevices', (req, res) => {
timestamp,
error: null,
fps: fps,
FPSMax: FPSMax
FPSMax: FPSMax,
mavStreamSelected: vManager.selMavURI
}))
} else {
res.setHeader('Content-Type', 'application/json')
Expand Down Expand Up @@ -453,7 +506,7 @@ app.get('/api/FCOutputs', (req, res) => {

app.get('/api/FCDetails', (req, res) => {
res.setHeader('Content-Type', 'application/json')
fcManager.getSerialDevices((err, devices, bauds, seldevice, selbaud, mavers, selmav, active, enableHeartbeat, enableTCP, enableUDPB, UDPBPort, enableDSRequest, tlogging) => {
fcManager.getSerialDevices((err, devices, bauds, seldevice, selbaud, mavers, selmav, active, enableHeartbeat, enableTCP, enableUDPB, UDPBPort, enableDSRequest) => {
// hacky way to pass through the
if (!err) {
console.log('Sending')
Expand All @@ -470,8 +523,7 @@ app.get('/api/FCDetails', (req, res) => {
enableTCP,
enableUDPB,
UDPBPort,
enableDSRequest,
tlogging
enableDSRequest
}))
} else {
console.log(devices)
Expand All @@ -488,8 +540,7 @@ app.get('/api/FCDetails', (req, res) => {
enableTCP,
enableUDPB,
UDPBPort,
enableDSRequest,
tlogging
enableDSRequest
}))
winston.error('Error in /api/FCDetails ', { message: err })
}
Expand All @@ -506,15 +557,15 @@ app.post('/api/updatemaster', function (req, res) {
aboutPage.updateRS(io)
})

app.post('/api/FCModify', [check('device').isJSON(), check('baud').isJSON(), check('mavversion').isJSON(), check('enableHeartbeat').isBoolean(), check('enableTCP').isBoolean(), check('enableUDPB').isBoolean(), check('UDPBPort').isPort(), check('enableDSRequest').isBoolean(), check('tlogging').isBoolean()], function (req, res) {
app.post('/api/FCModify', [check('device').isJSON(), check('baud').isJSON(), check('mavversion').isJSON(), check('enableHeartbeat').isBoolean(), check('enableTCP').isBoolean(), check('enableUDPB').isBoolean(), check('UDPBPort').isPort(), check('enableDSRequest').isBoolean()], function (req, res) {
// User wants to start/stop FC telemetry
const errors = validationResult(req)
if (!errors.isEmpty()) {
winston.error('Bad POST vars in /api/FCModify', { message: JSON.stringify(errors.array()) })
return res.status(422).json({ error: JSON.stringify(errors.array()) })
}

fcManager.startStopTelemetry(JSON.parse(req.body.device), JSON.parse(req.body.baud), JSON.parse(req.body.mavversion), req.body.enableHeartbeat, req.body.enableTCP, req.body.enableUDPB, req.body.UDPBPort, req.body.enableDSRequest, req.body.tlogging, (err, isSuccess) => {
fcManager.startStopTelemetry(JSON.parse(req.body.device), JSON.parse(req.body.baud), JSON.parse(req.body.mavversion), req.body.enableHeartbeat, req.body.enableTCP, req.body.enableUDPB, req.body.UDPBPort, req.body.enableDSRequest, (err, isSuccess) => {
if (!err) {
res.setHeader('Content-Type', 'application/json')
// console.log(isSuccess);
Expand Down Expand Up @@ -671,7 +722,7 @@ app.post('/api/startstopvideo', [check('active').isBoolean(),
return res.status(422).json(ret)
}
// user wants to start/stop video streaming
vManager.startStopStreaming(req.body.active, req.body.device, req.body.height, req.body.width, req.body.format, req.body.rotation, req.body.bitrate, req.body.fps, req.body.useUDP, req.body.useUDPIP, req.body.useUDPPort, req.body.useTimestamp, (err, status, addresses) => {
vManager.startStopStreaming(req.body.active, req.body.device, req.body.height, req.body.width, req.body.format, req.body.rotation, req.body.bitrate, req.body.fps, req.body.useUDP, req.body.useUDPIP, req.body.useUDPPort, req.body.useTimestamp, req.body.mavStreamSelected, (err, status, addresses) => {
if (!err) {
res.setHeader('Content-Type', 'application/json')
const ret = { streamingStatus: status, streamAddresses: addresses }
Expand Down

0 comments on commit 2e319f8

Please sign in to comment.