Skip to content

Commit df93b31

Browse files
committed
Added support for Adaptive Video streaming
1 parent cf31727 commit df93b31

File tree

7 files changed

+465
-4
lines changed

7 files changed

+465
-4
lines changed

files/apsync/video.html

Lines changed: 205 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,205 @@
1+
<!DOCTYPE HTML>
2+
<html manifest="manifest.appcache">
3+
<head>
4+
<title>ArduPilot</title>
5+
<meta charset="UTF-8">
6+
<link rel="stylesheet" href="/css/styles.css">
7+
<script type="text/javascript" src="/js/config.js"></script>
8+
<script type="text/javascript" src="/js/cors.js"></script>
9+
<script type="text/javascript" src="/js/mavlink.js"></script>
10+
</head>
11+
<body>
12+
13+
<p><a href="/index.html"><img src="/images/main_logo.png" alt="ArduPilot"></a></p>
14+
<h1>Video Streaming</h1>
15+
<div id="serverStoppedDiv">
16+
<p>Network Interface: <select id="if_select_box"></select><button type="submit" style="padding:1px" value="set_if" onclick="start_server();">Start RTSP Server</button></p>
17+
</div>
18+
<div id="serverStartedDiv">
19+
<table id="rtsp_table" class="parameters">
20+
<tr><th>Device</th><th>Camera Name</th><th class="alnright">RTSP Mount Point</th><th onclick="alert('\'Auto\' quality adjusts the resolution and framerate according to the available bandwidth and packet loss estimates')">Quality ⓘ</th><th onclick="alert('Enabling \'Record\' starts the recording of the live-streamed video in the Companion Computer\'s home directory. The stream must be opened on the client for the recording to start. This does not work currently work for the \'Auto\' quality setting and for the Pi camera.')">Record ⓘ</th><th>Apply</th></tr>
21+
</table>
22+
<p><input type="submit" name="action" value="Stop RTSP Server" onclick="stop_server();"></p>
23+
</div>
24+
<script>
25+
var VideoPresetsEnum = {
26+
VIDEO_320x240x15: 0, VIDEO_640x480x15: 1, VIDEO_1280x720x15: 2,
27+
VIDEO_320x240x30: 3, VIDEO_640x480x30: 4, VIDEO_1280x720x30: 5,
28+
VIDEO_320x240x60: 6, VIDEO_640x480x60: 7, VIDEO_1280x720x60: 8
29+
};
30+
var VideoPresetsName = [
31+
"320x240 15fps", "640x480 15fps", "1280x720 15fps",
32+
"320x240 30fps", "640x480 30fps", "1280x720 30fps",
33+
"320x240 60fps", "640x480 60fps", "1280x720 60fps"
34+
];
35+
36+
var AUTO_PRESET = 1024;
37+
38+
window.onload = refresh;
39+
40+
function removeOptions(selectbox) {
41+
var i;
42+
for(i = selectbox.options.length - 1 ; i >= 0 ; i--) {
43+
selectbox.remove(i);
44+
}
45+
}
46+
47+
function start_server() {
48+
var select = document.getElementById("if_select_box");
49+
console.log(select.value);
50+
var interface = select.value;
51+
command_send("start_rtsp_server(" + interface + ")", {"onload" : late_refresh});
52+
}
53+
54+
function stop_server() {
55+
command_send("stop_rtsp_server()", {"onload" : refresh});
56+
}
57+
58+
function sleep(milliseconds) {
59+
var start = new Date().getTime();
60+
for (var i = 0; i < 1e7; i++) {
61+
if ((new Date().getTime() - start) > milliseconds){
62+
break;
63+
}
64+
}
65+
}
66+
67+
function late_refresh() {
68+
// The stream server needs some time to wake up
69+
timed_refresh(1000);
70+
}
71+
72+
function timed_refresh(millis) {
73+
sleep(millis);
74+
refresh();
75+
}
76+
77+
function fill_interface_list(interface_list) {
78+
console.log(interface_list);
79+
var select = document.getElementById("if_select_box");
80+
removeOptions(select);
81+
var iflist = JSON.parse(interface_list);
82+
var interfaces = iflist["interfaces"];
83+
for (var i = 0; i < interfaces.length; i++) {
84+
select.options[select.options.length] = new Option(interfaces[i], interfaces[i]);
85+
}
86+
}
87+
88+
function fill_rtsp_table(cam_data) {
89+
console.log(cam_data);
90+
var table = document.getElementById("rtsp_table");
91+
92+
// delete any existing rows
93+
var nrows = table.rows.length;
94+
for (var i=nrows-1; i>0; i--) {
95+
table.deleteRow(i);
96+
}
97+
98+
if (cam_data == "ERROR\n") {
99+
console.log("error str");
100+
document.getElementById("serverStartedDiv").style.display = 'none';
101+
document.getElementById("serverStoppedDiv").style.display = 'block';
102+
command_send("get_interfaces()", { "onload" : fill_interface_list });
103+
} else {
104+
document.getElementById("serverStartedDiv").style.display = 'block';
105+
document.getElementById("serverStoppedDiv").style.display = 'none';
106+
var plist;
107+
try {
108+
plist = JSON.parse(cam_data);
109+
plist.sort(function(a,b) {
110+
if (a.mount < b.mount) {
111+
return -1;
112+
}
113+
if (a.mount > b.mount) {
114+
return 1;
115+
}
116+
return 0;
117+
});
118+
} catch(e) {
119+
console.log(e);
120+
return;
121+
}
122+
123+
var n = plist.length;
124+
for (var i=0; i<n; i++) {
125+
var row = table.insertRow(table.rows.length);
126+
var rowdata = plist[i];
127+
var device_cell = row.insertCell(0);
128+
var ip = rowdata.ip;
129+
var port = rowdata.port;
130+
device_cell.innerHTML = rowdata.dev_mount;
131+
device_cell.id = "device" + i;
132+
row.insertCell(1).innerHTML = rowdata.name;
133+
var mount_url = "rtsp://" + ip + ":" + port + rowdata.mount;
134+
row.insertCell(2).innerHTML = mount_url;
135+
136+
var form_quality = "form_quality" + i;
137+
var quality_select_box = "quality_select_box"+i;
138+
var set_quality_button = "set_quality_button"+i;
139+
var record_video_checkbox = "record"+i;
140+
141+
var current_quality = rowdata.current_quality;
142+
var curr_recording = rowdata.recording;
143+
144+
// H.264 cams don't do file recording properly, so let's disable it for now
145+
if (rowdata.camtype != 1) {
146+
row.insertCell(3).innerHTML = '<select id="' + quality_select_box + '"></select>';
147+
} else {
148+
row.insertCell(3).innerHTML = '<select disabled id="' + quality_select_box + '"></select>';
149+
}
150+
if (rowdata.camtype != 2) {
151+
row.insertCell(4).innerHTML = '<input type="checkbox" id=' + record_video_checkbox + ' margin: auto; text-align:center; >';
152+
} else {
153+
row.insertCell(4).innerHTML = '<input disabled type="checkbox" id=' + record_video_checkbox + ' margin: auto; text-align:center; >';
154+
}
155+
row.insertCell(5).innerHTML = '<button type="submit" value="' + i.toString() + '" onclick="send_settings(this)">Set</button>';
156+
157+
var select = document.getElementById(quality_select_box);
158+
select.options[select.options.length] = new Option("Auto", AUTO_PRESET);
159+
for (var j = 0; j < Object.keys(VideoPresetsEnum).length; j++) {
160+
var test_value = 0;
161+
test_value = 1 << j;
162+
if (test_value & rowdata.frame_property_bitmask) {
163+
console.log("Supports " + VideoPresetsName[j]);
164+
select.options[select.options.length] = new Option(VideoPresetsName[j], j);
165+
}
166+
}
167+
document.getElementById(quality_select_box).value = current_quality;
168+
document.getElementById(record_video_checkbox).checked = curr_recording;
169+
}
170+
}
171+
}
172+
173+
function send_settings(button) {
174+
console.log("Reached this " + button.value);
175+
var table = document.getElementById("rtsp_table");
176+
var quality_select_box = document.getElementById("quality_select_box" + button.value);
177+
var record_video_checkbox = document.getElementById("record"+button.value);
178+
179+
var device_name = document.getElementById("device" + button.value).innerHTML;
180+
var qual_setting = quality_select_box.value;
181+
182+
var record_val;
183+
184+
if (record_video_checkbox.checked == true) {
185+
record_val = 1;
186+
} else {
187+
record_val = 0;
188+
}
189+
190+
var sdp_string = "SDP$" + device_name + " " + qual_setting + " " + record_val;
191+
command_send("set_device_quality(" + sdp_string + ")", {"onload" : after_sdp});
192+
console.log("QualValue - " + sdp_string);
193+
timed_refresh(100);
194+
}
195+
196+
function after_sdp() {
197+
console.log("SDP string sent");
198+
}
199+
200+
function refresh() {
201+
command_send("get_camera_details()", { "onload" : fill_rtsp_table });
202+
}
203+
204+
</script>
205+
</html>

files/index.html

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -24,6 +24,7 @@ <h2>ArduPilot Web Server</h2>
2424
<li><a href="apsync/status.html">System Status</a></li>
2525
<li><a href="apsync/calibration.html">Calibration</a></li>
2626
<li><a href="parameters.html">Flight Parameters</a></li>
27+
<li><a href="apsync/video.html">Video Streaming</a></li>
2728
</ul>
2829

2930

files/js/config.js

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
var drone_url = "http://192.168.99.1";
1+
var drone_url = "http://127.0.0.1";
22

33
/* URL for Ublox MGA data */
44
var mga_data_url = "http://gps.tridgell.net/data/mga-offline.ubx";

functions.c

Lines changed: 77 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -8,6 +8,7 @@
88
#include "mavlink_json.h"
99
#include "mavlink_core.h"
1010
#include "cgi.h"
11+
#include "rtsp_ipc.h"
1112

1213
#ifdef _POSIX_VERSION
1314
#include "posix/functions.h"
@@ -755,6 +756,77 @@ static void get_param(struct template_state *tmpl, const char *name, const char
755756
}
756757
}
757758

759+
/*
760+
gets the list of avaialble cameras from the RTSP stream server over a local socket
761+
*/
762+
static void get_camera_details(struct template_state *tmpl, const char *name, const char *value, int argc, char **argv)
763+
{
764+
char msg[IPC_BUFFER_SIZE];
765+
char result[IPC_BUFFER_SIZE];
766+
get_server_response(GET_DEVICE_PROPS, msg, NULL);
767+
if (strlen(msg)) {
768+
process_server_response(msg, result);
769+
sock_printf(tmpl->sock, "%s", result);
770+
} else {
771+
sock_printf(tmpl->sock, "%s", "ERROR");
772+
}
773+
}
774+
775+
/*
776+
find the list of available network interfaces for starting the RTSP stream server
777+
*/
778+
static void get_interfaces(struct template_state *tmpl, const char *name, const char *value, int argc, char **argv)
779+
{
780+
char interfaces_list[IPC_BUFFER_SIZE];
781+
get_interfaces_list(interfaces_list);
782+
sock_printf(tmpl->sock, "%s", interfaces_list);
783+
}
784+
785+
/*
786+
sets the properties of a camera through IPC with the RTSP stream server
787+
*/
788+
static void set_device_quality(struct template_state *tmpl, const char *name, const char *value, int argc, char **argv)
789+
{
790+
if (argc) {
791+
if (send_server_message(argv[0])) {
792+
printf("Error in setting camera properties\n");
793+
}
794+
}
795+
}
796+
797+
static pid_t stream_server_pid = -1;
798+
799+
/*
800+
forks to create a new process for the RTSP stream
801+
*/
802+
static void start_rtsp_server(struct template_state *tmpl, const char *name, const char *value, int argc, char **argv)
803+
{
804+
if (stream_server_pid == -1) {
805+
stream_server_pid = fork();
806+
if (stream_server_pid < 0) {
807+
printf("Fork failed\n");
808+
} else if (stream_server_pid == 0) {
809+
if (execlp("stream_server", "stream_server", argv[0], NULL)==-1) {
810+
printf("Error in launching the stream server\n");
811+
}
812+
}
813+
} else {
814+
printf("Stream server running with PID: %d\n", stream_server_pid);
815+
}
816+
}
817+
818+
static void stop_rtsp_server(struct template_state *tmpl, const char *name, const char *value, int argc, char **argv)
819+
{
820+
if (stream_server_pid != -1) {
821+
if(!kill(stream_server_pid, SIGTERM)) {
822+
stream_server_pid = -1;
823+
printf("Stream server successfully killed\n");
824+
} else {
825+
printf("Could not kill the stream server\n");
826+
}
827+
}
828+
}
829+
758830
/*
759831
get parameter list
760832
*/
@@ -1061,4 +1133,9 @@ void functions_init(struct template_state *tmpl)
10611133
tmpl->put(tmpl, "process_content", "", process_content);
10621134
tmpl->put(tmpl, "get_param", "", get_param);
10631135
tmpl->put(tmpl, "get_param_list", "", get_param_list);
1136+
tmpl->put(tmpl, "get_camera_details", "", get_camera_details);
1137+
tmpl->put(tmpl, "set_device_quality", "", set_device_quality);
1138+
tmpl->put(tmpl, "start_rtsp_server", "", start_rtsp_server);
1139+
tmpl->put(tmpl, "stop_rtsp_server", "", stop_rtsp_server);
1140+
tmpl->put(tmpl, "get_interfaces", "", get_interfaces);
10641141
}

0 commit comments

Comments
 (0)