Skip to content

Commit 68af2ee

Browse files
ddd999ddd999
ddd999
authored andcommitted
Photo Mode Skeleton
The start of a Photo mode that allows full-resolution images to be captured locally on the device running Rpanion
1 parent f6dd036 commit 68af2ee

File tree

4 files changed

+358
-150
lines changed

4 files changed

+358
-150
lines changed

python/capture_still.py

+47
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,47 @@
1+
#!/usr/bin/env python3
2+
3+
from picamera2 import Picamera2
4+
from argparse import ArgumentParser
5+
import time, signal, os
6+
7+
parser = ArgumentParser()
8+
parser.add_argument("-f", "--filename", dest="filename",
9+
help="Save captured image to FILE", metavar="FILE")
10+
args = parser.parse_args()
11+
12+
pid = os.getpid()
13+
GOT_SIGNAL = 0
14+
15+
def receive_signal(signum, stack):
16+
global GOT_SIGNAL
17+
GOT_SIGNAL = 1
18+
19+
# Initialize the camera
20+
picam2 = Picamera2()
21+
config = picam2.create_still_configuration(
22+
main={"size": picam2.sensor_resolution},
23+
buffer_count=2
24+
)
25+
picam2.configure(config)
26+
# Keep the camera active to make responses faster
27+
picam2.start()
28+
29+
print("Waiting 2 seconds for camera to stabilize...")
30+
time.sleep(2)
31+
print("Camera is ready")
32+
33+
# Register the signal handler function
34+
signal.signal(signal.SIGUSR1, receive_signal)
35+
print("PID is : ", pid)
36+
37+
# Wait for a signal to arrive
38+
while True:
39+
if GOT_SIGNAL == 1:
40+
print("Received signal.SIGUSR1. Capturing photo.")
41+
filename = time.strftime("RPN%Y%m%d_%H%M%S.jpg")
42+
print(filename)
43+
output_orig = picam2.capture_file(filename)
44+
GOT_SIGNAL = 0
45+
#time.sleep(1)
46+
# Wait for a signal
47+
signal.pause()

server/index.js

+33-2
Original file line numberDiff line numberDiff line change
@@ -116,6 +116,33 @@ vManager.eventEmitter.on('videostreaminfo', (msg, senderSysId, senderCompId, tar
116116
}
117117
})
118118

119+
// Got a CAMERA_SETTINGS event, send to flight controller
120+
vManager.eventEmitter.on('camerasettings', (msg, senderSysId, senderCompId, targetComponent) => {
121+
try {
122+
if (fcManager.m) {
123+
fcManager.m.sendCommandAck(common.CameraSettings.MSG_ID, 0, senderSysId, senderCompId, targetComponent)
124+
fcManager.m.sendData(msg, senderCompId)
125+
}
126+
} catch (err) {
127+
console.log(err)
128+
}
129+
})
130+
131+
// Got a DO_DIGICAM_CONTROL event, send to flight controller
132+
//vManager.eventEmitter.on('digicamcontrol', (msg, senderSysId, senderCompId, targetComponent) => {
133+
vManager.eventEmitter.on('digicamcontrol', (senderSysId, senderCompId, targetComponent) => {
134+
console.log("index.js:digicamcontrol event received")
135+
try {
136+
if (fcManager.m) {
137+
// 203 = MAV_CMD_DO_DIGICAM_CONTROL
138+
fcManager.m.sendCommandAck(203, 0, senderSysId, senderCompId, targetComponent)
139+
//fcManager.m.sendData(msg, senderCompId)
140+
}
141+
} catch (err) {
142+
console.log(err)
143+
}
144+
})
145+
119146
// Connecting the flight controller datastream to the logger
120147
// and ntrip and video
121148
fcManager.eventEmitter.on('gotMessage', (packet, data) => {
@@ -428,7 +455,7 @@ app.get('/api/softwareinfo', (req, res) => {
428455

429456
app.get('/api/videodevices', (req, res) => {
430457
vManager.populateAddresses()
431-
vManager.getVideoDevices((err, devices, active, seldevice, selRes, selRot, selbitrate, selfps, SeluseUDP, SeluseUDPIP, SeluseUDPPort, timestamp, fps, FPSMax, vidres, useCameraHeartbeat, selMavURI) => {
458+
vManager.getVideoDevices((err, devices, active, seldevice, selRes, selRot, selbitrate, selfps, SeluseUDP, SelusePhotoMode, SeluseUDPIP, SeluseUDPPort, timestamp, fps, FPSMax, vidres, useCameraHeartbeat, useMavControl, selMavURI) => {
432459
if (!err) {
433460
res.setHeader('Content-Type', 'application/json')
434461
res.send(JSON.stringify({
@@ -443,13 +470,15 @@ app.get('/api/videodevices', (req, res) => {
443470
bitrate: selbitrate,
444471
fpsSelected: selfps,
445472
UDPChecked: SeluseUDP,
473+
photoMode: SelusePhotoMode,
446474
useUDPIP: SeluseUDPIP,
447475
useUDPPort: SeluseUDPPort,
448476
timestamp,
449477
error: null,
450478
fps: fps,
451479
FPSMax: FPSMax,
452480
enableCameraHeartbeat: useCameraHeartbeat,
481+
enableMavControl: useMavControl,
453482
mavStreamSelected: selMavURI
454483
}))
455484
} else {
@@ -697,8 +726,10 @@ app.post('/api/startstopvideo', [check('active').isBoolean(),
697726
check('height').if(check('active').isIn([true])).isInt({ min: 1 }),
698727
check('width').if(check('active').isIn([true])).isInt({ min: 1 }),
699728
check('useUDP').if(check('active').isIn([true])).isBoolean(),
729+
check('usePhotoMode').if(check('active').isIn([true])).isBoolean(),
700730
check('useTimestamp').if(check('active').isIn([true])).isBoolean(),
701731
check('useCameraHeartbeat').if(check('active').isIn([true])).isBoolean(),
732+
check('useMavControl').if(check('active').isIn([true])).isBoolean(),
702733
check('useUDPPort').if(check('active').isIn([true])).isPort(),
703734
check('useUDPIP').if(check('active').isIn([true])).isIP(),
704735
check('bitrate').if(check('active').isIn([true])).isInt({ min: 50, max: 50000 }),
@@ -712,7 +743,7 @@ app.post('/api/startstopvideo', [check('active').isBoolean(),
712743
return res.status(422).json(ret)
713744
}
714745
// user wants to start/stop video streaming
715-
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) => {
746+
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) => {
716747
if (!err) {
717748
res.setHeader('Content-Type', 'application/json')
718749
const ret = { streamingStatus: status, streamAddresses: addresses }

0 commit comments

Comments
 (0)