diff --git a/python/capture_still.py b/python/capture_still.py new file mode 100755 index 00000000..decedfe7 --- /dev/null +++ b/python/capture_still.py @@ -0,0 +1,47 @@ +#!/usr/bin/env python3 + +from picamera2 import Picamera2 +from argparse import ArgumentParser +import time, signal, os + +parser = ArgumentParser() +parser.add_argument("-f", "--filename", dest="filename", + help="Save captured image to FILE", metavar="FILE") +args = parser.parse_args() + +pid = os.getpid() +GOT_SIGNAL = 0 + +def receive_signal(signum, stack): + global GOT_SIGNAL + GOT_SIGNAL = 1 + +# Initialize the camera +picam2 = Picamera2() +config = picam2.create_still_configuration( + main={"size": picam2.sensor_resolution}, + buffer_count=2 +) +picam2.configure(config) +# Keep the camera active to make responses faster +picam2.start() + +print("Waiting 2 seconds for camera to stabilize...") +time.sleep(2) +print("Camera is ready") + +# Register the signal handler function +signal.signal(signal.SIGUSR1, receive_signal) +print("PID is : ", pid) + +# Wait for a signal to arrive +while True: + if GOT_SIGNAL == 1: + print("Received signal.SIGUSR1. Capturing photo.") + filename = time.strftime("RPN%Y%m%d_%H%M%S.jpg") + print(filename) + output_orig = picam2.capture_file(filename) + GOT_SIGNAL = 0 + #time.sleep(1) + # Wait for a signal + signal.pause() \ No newline at end of file diff --git a/server/index.js b/server/index.js index 788d66b3..c472553c 100644 --- a/server/index.js +++ b/server/index.js @@ -116,6 +116,33 @@ vManager.eventEmitter.on('videostreaminfo', (msg, senderSysId, senderCompId, tar } }) +// Got a CAMERA_SETTINGS event, send to flight controller +vManager.eventEmitter.on('camerasettings', (msg, senderSysId, senderCompId, targetComponent) => { + try { + if (fcManager.m) { + fcManager.m.sendCommandAck(common.CameraSettings.MSG_ID, 0, senderSysId, senderCompId, targetComponent) + fcManager.m.sendData(msg, senderCompId) + } + } catch (err) { + console.log(err) + } +}) + +// Got a DO_DIGICAM_CONTROL event, send to flight controller +//vManager.eventEmitter.on('digicamcontrol', (msg, senderSysId, senderCompId, targetComponent) => { +vManager.eventEmitter.on('digicamcontrol', (senderSysId, senderCompId, targetComponent) => { + console.log("index.js:digicamcontrol event received") + try { + if (fcManager.m) { + // 203 = MAV_CMD_DO_DIGICAM_CONTROL + fcManager.m.sendCommandAck(203, 0, senderSysId, senderCompId, targetComponent) + //fcManager.m.sendData(msg, senderCompId) + } + } catch (err) { + console.log(err) + } +}) + // Connecting the flight controller datastream to the logger // and ntrip and video fcManager.eventEmitter.on('gotMessage', (packet, data) => { @@ -428,7 +455,7 @@ 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, useCameraHeartbeat, selMavURI) => { + vManager.getVideoDevices((err, devices, active, seldevice, selRes, selRot, selbitrate, selfps, SeluseUDP, SelusePhotoMode, SeluseUDPIP, SeluseUDPPort, timestamp, fps, FPSMax, vidres, useCameraHeartbeat, useMavControl, selMavURI) => { if (!err) { res.setHeader('Content-Type', 'application/json') res.send(JSON.stringify({ @@ -443,6 +470,7 @@ app.get('/api/videodevices', (req, res) => { bitrate: selbitrate, fpsSelected: selfps, UDPChecked: SeluseUDP, + photoMode: SelusePhotoMode, useUDPIP: SeluseUDPIP, useUDPPort: SeluseUDPPort, timestamp, @@ -450,6 +478,7 @@ app.get('/api/videodevices', (req, res) => { fps: fps, FPSMax: FPSMax, enableCameraHeartbeat: useCameraHeartbeat, + enableMavControl: useMavControl, mavStreamSelected: selMavURI })) } else { @@ -697,8 +726,10 @@ app.post('/api/startstopvideo', [check('active').isBoolean(), check('height').if(check('active').isIn([true])).isInt({ min: 1 }), check('width').if(check('active').isIn([true])).isInt({ min: 1 }), check('useUDP').if(check('active').isIn([true])).isBoolean(), + check('usePhotoMode').if(check('active').isIn([true])).isBoolean(), check('useTimestamp').if(check('active').isIn([true])).isBoolean(), check('useCameraHeartbeat').if(check('active').isIn([true])).isBoolean(), + check('useMavControl').if(check('active').isIn([true])).isBoolean(), check('useUDPPort').if(check('active').isIn([true])).isPort(), check('useUDPIP').if(check('active').isIn([true])).isIP(), check('bitrate').if(check('active').isIn([true])).isInt({ min: 50, max: 50000 }), @@ -712,7 +743,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, req.body.useCameraHeartbeat, req.body.mavStreamSelected, (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.usePhotoMode, req.body.useUDPIP, req.body.useUDPPort, req.body.useTimestamp, req.body.useCameraHeartbeat, req.body.useMavControl, req.body.mavStreamSelected, (err, status, addresses) => { if (!err) { res.setHeader('Content-Type', 'application/json') const ret = { streamingStatus: status, streamAddresses: addresses } diff --git a/server/videostream.js b/server/videostream.js index 076dd847..620c87cb 100644 --- a/server/videostream.js +++ b/server/videostream.js @@ -29,12 +29,12 @@ class videoStream { // need to scan for video devices first though if (this.active) { this.active = false - this.getVideoDevices((error, devices, active, seldevice, selRes, selRot, selbitrate, selfps, selUDP, selUDPIP, selUDPPort, useTimestamp, useCameraHeartbeat, selMavURI) => { + this.getVideoDevices((error, devices, active, seldevice, selRes, selRot, selbitrate, selfps, selUDP, selPhotoMode, selUDPIP, selUDPPort, useTimestamp, useCameraHeartbeat, useMavControl, selMavURI) => { if (!error) { this.startStopStreaming(true, this.savedDevice.device, this.savedDevice.height, this.savedDevice.width, this.savedDevice.format, - this.savedDevice.rotation, this.savedDevice.bitrate, this.savedDevice.fps, this.savedDevice.useUDP, - this.savedDevice.useUDPIP, this.savedDevice.useUDPPort, this.savedDevice.useTimestamp, this.savedDevice.useCameraHeartbeat, this.savedDevice.mavStreamSelected, + this.savedDevice.rotation, this.savedDevice.bitrate, this.savedDevice.fps, this.savedDevice.useUDP, this.savedDevice.usePhotoMode, + this.savedDevice.useUDPIP, this.savedDevice.useUDPPort, this.savedDevice.useTimestamp, this.savedDevice.useCameraHeartbeat, this.savedDevice.useMavControl, this.savedDevice.mavStreamSelected, (err, status, addresses) => { if (err) { // failed setup, reset settings @@ -65,7 +65,7 @@ class videoStream { // video streaming getVideoDevices (callback) { // get all video device details - // callback is: err, devices, active, seldevice, selRes, selRot, selbitrate, selfps, SeluseUDP, SeluseUDPIP, SeluseUDPPort, timestamp, fps, FPSMax, vidres, cameraHeartbeat, selMavURI + // callback is: err, devices, active, seldevice, selRes, selRot, selbitrate, selfps, SeluseUDP, SelusePhotoMode, SeluseUDPIP, SeluseUDPPort, timestamp, fps, FPSMax, vidres, cameraHeartbeat, mavControl, selMavURI exec('python3 ./python/gstcaps.py', (error, stdout, stderr) => { const warnstrings = ['DeprecationWarning', 'gst_element_message_full_with_details', 'camera_manager.cpp', 'Unsupported V4L2 pixel format'] if (stderr && !warnstrings.some(wrn => stderr.includes(wrn))) { @@ -82,9 +82,9 @@ class videoStream { // and return current settings if (!this.active) { return callback(null, this.devices, this.active, this.devices[0], this.devices[0].caps[0], - { label: '0°', value: 0 }, 1100, fpsSelected, false, '127.0.0.1', 5400, false, + { label: '0°', value: 0 }, 1100, fpsSelected, false, false, '127.0.0.1', 5400, false, (this.devices[0].caps[0].fps !== undefined) ? this.devices[0].caps[0].fps : [], - this.devices[0].caps[0].fpsmax, this.devices[0].caps, false, { label: '127.0.0.1', value: 0 }) + this.devices[0].caps[0].fpsmax, this.devices[0].caps, false, false, { label: '127.0.0.1', value: 0 }) } else { // format saved settings const seldevice = this.devices.filter(it => it.value === this.savedDevice.device) @@ -94,9 +94,9 @@ class videoStream { this.winston.error('Bad video settings. Resetting ', { message: this.savedDevice }) this.resetVideo() return callback(null, this.devices, this.active, this.devices[0], this.devices[0].caps[0], - { label: '0°', value: 0 }, 1100, fpsSelected, false, '127.0.0.1', 5400, false, + { label: '0°', value: 0 }, 1100, fpsSelected, false, false, '127.0.0.1', 5400, false, (this.devices[0].caps[0].fps !== undefined) ? this.devices[0].caps[0].fps : [], - this.devices[0].caps[0].fpsmax, this.devices[0].caps, false, { label: '127.0.0.1', value: 0 }) + this.devices[0].caps[0].fpsmax, this.devices[0].caps, false, false, { label: '127.0.0.1', value: 0 }) } const selRes = seldevice[0].caps.filter(it => it.value === this.savedDevice.width.toString() + 'x' + this.savedDevice.height.toString() + 'x' + this.savedDevice.format.toString().split('/')[1]) let selFPS = this.savedDevice.fps @@ -108,18 +108,18 @@ class videoStream { console.log(seldevice[0]) return callback(null, this.devices, this.active, seldevice[0], selRes[0], { label: this.savedDevice.rotation.toString() + '°', value: this.savedDevice.rotation }, - this.savedDevice.bitrate, selFPS, this.savedDevice.useUDP, this.savedDevice.useUDPIP, + this.savedDevice.bitrate, selFPS, this.savedDevice.useUDP, this.savedDevice.usePhotoMode, this.savedDevice.useUDPIP, this.savedDevice.useUDPPort, this.savedDevice.useTimestamp, (selRes[0].fps !== undefined) ? selRes[0].fps : [], - selRes[0].fpsmax, seldevice[0].caps, this.savedDevice.useCameraHeartbeat, { label: this.savedDevice.mavStreamSelected.toString(), value: this.savedDevice.mavStreamSelected }) + selRes[0].fpsmax, seldevice[0].caps, this.savedDevice.useCameraHeartbeat, this.savedDevice.useMavControl, { label: this.savedDevice.mavStreamSelected.toString(), value: this.savedDevice.mavStreamSelected }) } else { // bad settings console.error('Bad video settings. Resetting' + seldevice + ', ' + selRes) this.winston.error('Bad video settings. Resetting ', { message: JSON.stringify(this.savedDevice) }) this.resetVideo() return callback(null, this.devices, this.active, this.devices[0], this.devices[0].caps[0], - { label: '0°', value: 0 }, 1100, fpsSelected, false, '127.0.0.1', 5400, false, + { label: '0°', value: 0 }, 1100, fpsSelected, false, false, '127.0.0.1', 5400, false, (this.devices[0].caps[0].fps !== undefined) ? this.devices[0].caps[0].fps : [], - this.devices[0].caps[0].fpsmax, this.devices[0].caps, false, { label: '127.0.0.1', value: 0 }) + this.devices[0].caps[0].fpsmax, this.devices[0].caps, false, false, { label: '127.0.0.1', value: 0 }) } } } @@ -164,7 +164,7 @@ class videoStream { return iface } - async startStopStreaming (active, device, height, width, format, rotation, bitrate, fps, useUDP, useUDPIP, useUDPPort, useTimestamp, useCameraHeartbeat, mavStreamSelected, callback) { + async startStopStreaming (active, device, height, width, format, rotation, bitrate, fps, useUDP, usePhotoMode, useUDPIP, useUDPPort, useTimestamp, useCameraHeartbeat, useMavControl, mavStreamSelected, callback) { // if current state same, don't do anything if (this.active === active) { console.log('Video current same') @@ -201,78 +201,88 @@ class videoStream { fps, rotation, useUDP, + usePhotoMode, useUDPIP, useUDPPort, useTimestamp, useCameraHeartbeat, + useMavControl, mavStreamSelected } - // note that video device URL's are the alphanumeric characters only. So /dev/video0 -> devvideo0 - this.populateAddresses(device.replace(/\W/g, '')) - - // rpi camera has different name under Ubuntu - if (await this.isUbuntu() && device === 'rpicam') { - device = '/dev/video0' - format = 'video/x-raw' + // Don't start a video stream if we are in photo mode + if (this.savedDevice.usePhotoMode){ + console.log("Started photo mode") } + else { + // note that video device URL's are the alphanumeric characters only. So /dev/video0 -> devvideo0 + this.populateAddresses(device.replace(/\W/g, '')) + + // rpi camera has different name under Ubuntu + if (await this.isUbuntu() && device === 'rpicam') { + device = '/dev/video0' + format = 'video/x-raw' + } - const args = ['./python/rtsp-server.py', - '--video=' + device, - '--height=' + height, - '--width=' + width, - '--format=' + format, - '--bitrate=' + bitrate, - '--rotation=' + rotation, - '--fps=' + fps, - '--udp=' + ((useUDP === false) ? '0' : useUDPIP + ':' + useUDPPort.toString()) - ] - - if (useTimestamp) { - args.push('--timestamp') - } + const args = ['./python/rtsp-server.py', + '--video=' + device, + '--height=' + height, + '--width=' + width, + '--format=' + format, + '--bitrate=' + bitrate, + '--rotation=' + rotation, + '--fps=' + fps, + '--udp=' + ((useUDP === false) ? '0' : useUDPIP + ':' + useUDPPort.toString()) + ] + + if (useTimestamp) { + args.push('--timestamp') + } - this.deviceStream = spawn('python3', args) + this.deviceStream = spawn('python3', args) - try { - if (this.deviceStream === null) { - this.settings.setValue('videostream.active', false) - console.log('Error spawning rtsp-server.py') - this.winston.info('Error spawning rtsp-server.py') - return callback(null, this.active, this.deviceAddresses) + try { + if (this.deviceStream === null) { + this.settings.setValue('videostream.active', false) + console.log('Error spawning rtsp-server.py') + this.winston.info('Error spawning rtsp-server.py') + return callback(null, this.active, this.deviceAddresses) + } + this.settings.setValue('videostream.active', this.active) + this.settings.setValue('videostream.savedDevice', this.savedDevice) + } catch (e) { + console.log(e) + this.winston.info(e) } - this.settings.setValue('videostream.active', this.active) - this.settings.setValue('videostream.savedDevice', this.savedDevice) - } catch (e) { - console.log(e) - this.winston.info(e) - } - this.deviceStream.stdout.on('data', (data) => { - this.winston.info('startStopStreaming() data ' + data) - console.log(`GST stdout: ${data}`) - }) + this.deviceStream.stdout.on('data', (data) => { + this.winston.info('startStopStreaming() data ' + data) + console.log(`GST stdout: ${data}`) + }) + + this.deviceStream.stderr.on('data', (data) => { + this.winston.error('startStopStreaming() err ', { message: data }) + console.error(`GST stderr: ${data}`) + }) + + this.deviceStream.on('close', (code) => { + console.log(`GST process exited with code ${code}`) + this.winston.info('startStopStreaming() close ' + code) + this.deviceStream.stdin.pause() + this.deviceStream.kill() + this.resetVideo() + }) - this.deviceStream.stderr.on('data', (data) => { - this.winston.error('startStopStreaming() err ', { message: data }) - console.error(`GST stderr: ${data}`) - }) + console.log('Started Video Streaming of ' + device) + this.winston.info('Started Video Streaming of ' + device) - this.deviceStream.on('close', (code) => { - console.log(`GST process exited with code ${code}`) - this.winston.info('startStopStreaming() close ' + code) - this.deviceStream.stdin.pause() - this.deviceStream.kill() - this.resetVideo() - }) + } + // If enabled, start the camera heartbeat in either photo or video mode if (this.savedDevice.useCameraHeartbeat) { this.startInterval() } - console.log('Started Video Streaming of ' + device) - this.winston.info('Started Video Streaming of ' + device) - return callback(null, this.active, this.deviceAddresses) } else { // stop streaming @@ -281,9 +291,15 @@ class videoStream { if (this.savedDevice.useCameraHeartbeat) { clearInterval(this.intervalObj) } - this.deviceStream.stdin.pause() - this.deviceStream.kill() - this.resetVideo() + + if(this.savedDevice.usePhotoMode) { + console.log("Stopped photo mode") + this.resetVideo() + } else { + this.deviceStream.stdin.pause() + this.deviceStream.kill() + this.resetVideo() + } } return callback(null, this.active, this.deviceAddresses) } @@ -344,7 +360,14 @@ class videoStream { msg.resolutionV = this.savedDevice.height msg.lensId = 0 // 256 = CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM (hard-coded for now until Rpanion gains more camera capabilities) - msg.flags = 256 + if(this.savedDevice.usePhotoMode){ + // 2 = CAMERA_CAP_FLAGS_CAPTURE_IMAGE + msg.flags = 2 + } else { + // 256 = CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM + msg.flags = 256 + } + msg.camDefinitionVersion = 0 msg.camDefinitionUri = '' msg.gimbalDeviceId = 0 @@ -352,7 +375,8 @@ class videoStream { } else if (data.targetComponent === minimal.MavComponent.CAMERA && packet.header.msgid === common.CommandLong.MSG_ID && - data._param1 === common.VideoStreamInformation.MSG_ID) { + data._param1 === common.VideoStreamInformation.MSG_ID && + !this.savedDevice.usePhotoMode) { console.log('Responding to MAVLink request for VideoStreamInformation') this.winston.info('Responding to MAVLink request for VideoStreamInformation') @@ -364,35 +388,75 @@ class videoStream { // build a VIDEO_STREAM_INFORMATION packet const msg = new common.VideoStreamInformation() - // rpanion only supports a single stream, so streamId and count will always be 1 - msg.streamId = 1 - msg.count = 1 - - // msg.type and msg.uri need to be different depending on whether RTP or RTSP is selected - if (this.savedDevice.useUDP) { - // msg.type = 0 = VIDEO_STREAM_TYPE_RTSP - // msg.type = 1 = VIDEO_STREAM_TYPE_RTPUDP - msg.type = 1 - // For RTP, just send the destination UDP port instead of a full URI - msg.uri = this.savedDevice.useUDPPort.toString() + + // rpanion only supports a single stream, so streamId and count will always be 1 + msg.streamId = 1 + msg.count = 1 + + // msg.type and msg.uri need to be different depending on whether RTP or RTSP is selected + if (this.savedDevice.useUDP) { + // msg.type = 0 = VIDEO_STREAM_TYPE_RTSP + // msg.type = 1 = VIDEO_STREAM_TYPE_RTPUDP + msg.type = 1 + // For RTP, just send the destination UDP port instead of a full URI + msg.uri = this.savedDevice.useUDPPort.toString() + } else { + msg.type = 0 + msg.uri = `rtsp://${this.savedDevice.mavStreamSelected}:8554/${this.savedDevice.device}` + } + + // 1 = VIDEO_STREAM_STATUS_FLAGS_RUNNING + // 2 = VIDEO_STREAM_STATUS_FLAGS_THERMAL + msg.flags = 1 + msg.framerate = this.savedDevice.fps + msg.resolutionH = this.savedDevice.width + msg.resolutionV = this.savedDevice.height + msg.bitrate = this.savedDevice.bitrate + msg.rotation = this.savedDevice.rotation + // Rpanion doesn't collect field of view values, so just set to zero + msg.hfov = 0 + msg.name = this.savedDevice.device + + this.eventEmitter.emit('videostreaminfo', msg, senderSysId, senderCompId, targetComponent) + + } else if (data.targetComponent === minimal.MavComponent.CAMERA && + packet.header.msgid === common.CommandLong.MSG_ID && + data._param1 === common.CameraSettings.MSG_ID) { + + console.log('Responding to MAVLink request for CameraSettings') + this.winston.info('Responding to MAVLink request for CameraSettings') + + const senderSysId = packet.header.sysid + const senderCompId = minimal.MavComponent.CAMERA + const targetComponent = packet.header.compid + + // build a CAMERA_SETTINGS packet + const msg = new common.CameraSettings() + + msg.timeBootMs = 0; + // Camera modes: 0 = IMAGE, 1 = VIDEO, 2 = IMAGE_SURVEY + if(this.savedDevice.usePhotoMode){ + msg.modeId = 0; } else { - msg.type = 0 - msg.uri = `rtsp://${this.savedDevice.mavStreamSelected}:8554/${this.savedDevice.device}` + msg.modeId = 1; } + msg.zoomLevel = null; + msg.focusLevel = null; - // 1 = VIDEO_STREAM_STATUS_FLAGS_RUNNING - // 2 = VIDEO_STREAM_STATUS_FLAGS_THERMAL - msg.flags = 1 - msg.framerate = this.savedDevice.fps - msg.resolutionH = this.savedDevice.width - msg.resolutionV = this.savedDevice.height - msg.bitrate = this.savedDevice.bitrate - msg.rotation = this.savedDevice.rotation - // Rpanion doesn't collect field of view values, so just set to zero - msg.hfov = 0 - msg.name = this.savedDevice.device + this.eventEmitter.emit('camerasettings', msg, senderSysId, senderCompId, targetComponent) - this.eventEmitter.emit('videostreaminfo', msg, senderSysId, senderCompId, targetComponent) + } else if (data.targetComponent === minimal.MavComponent.CAMERA && + packet.header.msgid === common.CommandLong.MSG_ID && + // 203 = MAV_CMD_DO_DIGICAM_CONTROL + data.command === 203) { + + console.log('Received DoDigicamControl command') + + const senderSysId = packet.header.sysid + const senderCompId = minimal.MavComponent.CAMERA + const targetComponent = packet.header.compid + + this.eventEmitter.emit('digicamcontrol', senderSysId, senderCompId, targetComponent) } } } diff --git a/src/video.js b/src/video.js index 8eb912e8..8afe79a1 100644 --- a/src/video.js +++ b/src/video.js @@ -13,6 +13,7 @@ class VideoPage extends basePage { super(props); this.state = { ifaces: [], + photoMode: false, dev: [], vidDeviceSelected: this.props.vidDeviceSelected, vidres: [], @@ -42,6 +43,10 @@ class VideoPage extends basePage { fetch(`/api/videodevices`).then(response => response.json()).then(state => { this.setState(state); this.isMulticastUpdateIP(state.useUDPIP); this.loadDone() }); } + handleUsePhotoModeChange = (event) => { + this.setState({ photoMode: event.target.value==="photo" }); + } + handleVideoChange = (value, action) => { //new video device this.setState({ vidDeviceSelected: value, vidres: value.caps }); @@ -122,11 +127,31 @@ class VideoPage extends basePage { this.setState({ enableCameraHeartbeat: !this.state.enableCameraHeartbeat }); } + handleMavControlChange = (event) => { + // Allow MAVLink-connected devices to control the camera + this.setState({ enableMavControl: !this.state.enableMavControl }); + } handleMavStreamChange = (value) => { //new value for selected stream IP this.setState({ mavStreamSelected: value }); } + handleCaptureStill = (event) => { + // user requested to capture a still + this.setState({ waiting: true }, () => { + fetch('/api/capturestill', { + method: 'POST', + headers: { + 'Accept': 'application/json', + 'Content-Type': 'application/json', + }, + body: JSON.stringify({ + // TODO: add camera/exposure settings here + }) + }).then(response => response.json()).then(state => { this.setState(state); this.setState({ waiting: false }) }); + }); + } + handleStreaming = (event) => { //user clicked start/stop streaming this.setState({ waiting: true }, () => { @@ -138,6 +163,7 @@ class VideoPage extends basePage { }, body: JSON.stringify({ active: !this.state.streamingStatus, + usePhotoMode: this.state.photoMode, device: this.state.vidDeviceSelected.value, height: this.state.vidResSelected.height, width: this.state.vidResSelected.width, @@ -151,6 +177,7 @@ class VideoPage extends basePage { useUDPPort: this.state.useUDPPort, useTimestamp: this.state.timestamp, useCameraHeartbeat: this.state.enableCameraHeartbeat, + useMavControl: this.state.enableMavControl, mavStreamSelected: this.state.mavStreamSelected.value, }) }).then(response => response.json()).then(state => { this.setState(state); this.setState({ waiting: false }) }); @@ -166,76 +193,102 @@ class VideoPage extends basePage {