Skip to content

Commit

Permalink
Video: Continue implementation of camera protocol
Browse files Browse the repository at this point in the history
This commit adds a heartbeat output for the camera device, and adds the ability to send CAMERA_INFORMATION messages when requested. Also includes improvements for better handling undefined parameters for sendCommandAck()

Completes the implementation of feature request issue stephendade#169.
  • Loading branch information
ddd999 committed Apr 10, 2024
1 parent b86e990 commit f9be4d9
Show file tree
Hide file tree
Showing 4 changed files with 28 additions and 27 deletions.
13 changes: 6 additions & 7 deletions mavlink/mavManager.js
Original file line number Diff line number Diff line change
Expand Up @@ -261,15 +261,15 @@ class mavManager {
sendHeartbeat (mavType, autopilot, component) {

// Set defaults if parameters are not provided
if (mavType === null || mavType === undefined) {
if (mavType === null || mavType === undefined) {
mavType = minimal.MavType.ONBOARD_CONTROLLER
}

if (autopilot === null || autopilot === undefined) {
if (autopilot === null || autopilot === undefined) {
autopilot = minimal.MavAutopilot.INVALID
}

if (component === null || component === undefined) {
if (component === null || component === undefined) {
component = minimal.MavComponent.ONBOARD_COMPUTER
}

Expand All @@ -288,17 +288,16 @@ class mavManager {
}

sendCommandAck (commandReceived, commandResult, senderSysId, senderCompId, targetComponent) {

// Set defaults if parameters are not provided
if (commandResult === null || commandResult === undefined) {
if (commandResult === null || commandResult === undefined) {
commandResult = 0
}

if (senderSysId === null || senderSysId === undefined) {
if (senderSysId === null || senderSysId === undefined) {
senderSysId = 255
}

if (senderCompId === null || senderCompId === undefined) {
if (senderCompId === null || senderCompId === undefined) {
senderCompId = minimal.MavComponent.MISSION_PLANNER
}

Expand Down
9 changes: 4 additions & 5 deletions server/index.js
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@ const compression = require('compression')
const bodyParser = require('body-parser')
const pino = require('express-pino-logger')()
const process = require('process')
const { minimal, common } = require('node-mavlink')
const { common } = require('node-mavlink')

const networkManager = require('./networkManager')
const aboutPage = require('./aboutInfo')
Expand Down Expand Up @@ -93,11 +93,11 @@ vManager.eventEmitter.on('cameraheartbeat', (mavType, autopilot, component) => {
})

// Got a CAMERA_INFORMATION event, send to flight controller
vManager.eventEmitter.on('camerainfo', (msg, senderSysId, senderCompId) => {
vManager.eventEmitter.on('camerainfo', (msg, senderSysId, senderCompId, targetComponent) => {
try {
if (fcManager.m) {
fcManager.m.sendCommandAck(common.CameraInformation.MSG_ID, 0, senderSysId, senderCompId)
fcManager.m.sendData(msg)
fcManager.m.sendCommandAck(common.CameraInformation.MSG_ID, 0, senderSysId, senderCompId, targetComponent)
fcManager.m.sendData(msg, senderCompId)
}
} catch (err) {
console.log(err)
Expand All @@ -107,7 +107,6 @@ vManager.eventEmitter.on('camerainfo', (msg, senderSysId, senderCompId) => {
// Got a VIDEO_STREAM_INFORMATION event, send to flight controller
vManager.eventEmitter.on('videostreaminfo', (msg, senderSysId, senderCompId, targetComponent) => {
try {
console.log("index.js: senderCompId:" + senderCompId)
if (fcManager.m) {
fcManager.m.sendCommandAck(common.VideoStreamInformation.MSG_ID, 0, senderSysId, senderCompId, targetComponent)
fcManager.m.sendData(msg, senderCompId)
Expand Down
29 changes: 16 additions & 13 deletions server/videostream.js
Original file line number Diff line number Diff line change
Expand Up @@ -266,8 +266,7 @@ class videoStream {
this.resetVideo()
})

// TODO: add check to see if MAVLink advertising was selected
if(1){
if (this.savedDevice.useCameraHeartbeat) {
this.startInterval()
}

Expand All @@ -278,8 +277,9 @@ class videoStream {
} else {
// stop streaming
// if mavlink advertising is on, clear the interval
// TODO: add the actual check in here!
if (1) {clearInterval(this.intervalObj)

if (this.savedDevice.useCameraHeartbeat) {
clearInterval(this.intervalObj)
}
this.deviceStream.stdin.pause()
this.deviceStream.kill()
Expand All @@ -305,12 +305,11 @@ class videoStream {
startInterval () {
// start the 1-sec loop to send heartbeat events
this.intervalObj = setInterval(() => {

const mavType = minimal.MavType.CAMERA
const autopilot = minimal.MavAutopilot.INVALID
const component = minimal.MavComponent.CAMERA

this.eventEmitter.emit('cameraheartbeat', mavType, autopilot, component)
this.eventEmitter.emit('cameraheartbeat', mavType, autopilot, component)
}, 1000)
}

Expand All @@ -320,12 +319,15 @@ class videoStream {
return
}

if (packet.header.msgid === common.CommandLong.MSG_ID & data._param1 === common.CameraInformation.MSG_ID) {
if (data.targetComponent === minimal.MavComponent.CAMERA &&
packet.header.msgid === common.CommandLong.MSG_ID &&
data._param1 === common.CameraInformation.MSG_ID) {
console.log('Responding to MAVLink request for CameraInformation')
this.winston.info('Responding to MAVLink request for CameraInformation')

const senderSysId = packet.header.sysid
const senderCompId = packet.header.compid
const senderCompId = minimal.MavComponent.CAMERA
const targetComponent = packet.header.compid

// build a CAMERA_INFORMATION packet
const msg = new common.CameraInformation()
Expand All @@ -341,16 +343,17 @@ class videoStream {
msg.resolution_h = this.savedDevice.width
msg.resolution_v = this.savedDevice.height
msg.lens_id = 0
msg.flags = CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM // Hard-coded for now until Rpanion gains more camera capabilities
// 256 = CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM (hard-coded for now until Rpanion gains more camera capabilities)
msg.flags = 256
msg.cam_definition_version = 0
msg.cam_definition_uri = ''
msg.gimbal_device_id = 0

this.eventEmitter.emit('camerainfo', msg, senderSysId, senderCompId)
this.eventEmitter.emit('camerainfo', msg, senderSysId, senderCompId, targetComponent)

} else if (data.targetComponent === minimal.MavComponent.CAMERA &&
packet.header.msgid === common.CommandLong.MSG_ID
&& data._param1 === common.VideoStreamInformation.MSG_ID) {
packet.header.msgid === common.CommandLong.MSG_ID &&
data._param1 === common.VideoStreamInformation.MSG_ID) {

console.log('Responding to MAVLink request for VideoStreamInformation')
this.winston.info('Responding to MAVLink request for VideoStreamInformation')

Expand Down
4 changes: 2 additions & 2 deletions server/videostream.test.js
Original file line number Diff line number Diff line change
Expand Up @@ -63,11 +63,11 @@ describe('Video Functions', function () {
settings.clear()
const vManager = new VideoStream(settings, winston)

vManager.startStopStreaming(true, 'testsrc', '1080', '1920', 'video/x-h264', '0', '1000', '5', false, false, false, true, '0', function (err, status, addresses) {
vManager.startStopStreaming(true, 'testsrc', '1080', '1920', 'video/x-h264', '0', '1000', '5', false, false, false, true, false, '0', function (err, status, addresses) {
assert.equal(err, null)
assert.equal(status, true)
assert.notEqual(vManager.deviceStream.pid, null)
vManager.startStopStreaming(false, 'testsrc', '1080', '1920', 'video/x-h264', '0', '1000', '5', false, false, false, true, '0', function (err, status, addresses) {
vManager.startStopStreaming(false, 'testsrc', '1080', '1920', 'video/x-h264', '0', '1000', '5', false, false, false, true, false, '0', function (err, status, addresses) {
assert.equal(err, null)
assert.equal(status, false)
done()
Expand Down

0 comments on commit f9be4d9

Please sign in to comment.