diff --git a/Makefile b/Makefile index 310be85..6c56a16 100644 --- a/Makefile +++ b/Makefile @@ -12,7 +12,7 @@ all: files/embedded.c mavlink web_server mavlink: generated/mavlink/ardupilotmega/mavlink.h generated/mavlink/ardupilotmega/mavlink.h: - mavgen.py --lang C modules/mavlink/message_definitions/v1.0/ardupilotmega.xml -o generated/mavlink --wire-protocol=2.0 + modules/mavlink/pymavlink/tools/mavgen.py --lang C modules/mavlink/message_definitions/v1.0/ardupilotmega.xml -o generated/mavlink --wire-protocol=2.0 web_server: $(OBJ) files/embedded.c $(CC) -o web_server $(OBJ) $(LIBS) diff --git a/files/apsync/video.html b/files/apsync/video.html new file mode 100644 index 0000000..6386f8e --- /dev/null +++ b/files/apsync/video.html @@ -0,0 +1,205 @@ + + + + ArduPilot + + + + + + + + +

ArduPilot

+

Video Streaming

+
+

Network Interface:

+
+
+ + +
DeviceCamera NameRTSP URLCopy URLQuality ⓘApply
+

+
+ + \ No newline at end of file diff --git a/files/index.html b/files/index.html index 6e9757d..1ccedb1 100644 --- a/files/index.html +++ b/files/index.html @@ -24,6 +24,7 @@

ArduPilot Web Server

  • System Status
  • Calibration
  • Flight Parameters
  • +
  • Video Streaming
  • diff --git a/files/js/config.js b/files/js/config.js index 2e50568..5fb8abd 100644 --- a/files/js/config.js +++ b/files/js/config.js @@ -1,4 +1,4 @@ -var drone_url = "http://192.168.99.1"; +var drone_url = "http://127.0.0.1"; /* URL for Ublox MGA data */ var mga_data_url = "http://gps.tridgell.net/data/mga-offline.ubx"; diff --git a/functions.c b/functions.c index ad2ec8e..5b54809 100644 --- a/functions.c +++ b/functions.c @@ -8,6 +8,7 @@ #include "mavlink_json.h" #include "mavlink_core.h" #include "cgi.h" +#include "rtsp_ipc.h" #ifdef _POSIX_VERSION #include "posix/functions.h" @@ -16,6 +17,10 @@ #include "linux/functions.h" #endif +#ifdef _POSIX_VERSION +#include "posix/functions.h" +#endif + #ifdef SYSTEM_FREERTOS #include "../mavlink_wifi.h" #include "video_main.h" @@ -755,6 +760,78 @@ static void get_param(struct template_state *tmpl, const char *name, const char } } +/* + gets the list of avaialble cameras from the RTSP stream server over a local socket + */ +static void get_camera_details(struct template_state *tmpl, const char *name, const char *value, int argc, char **argv) +{ + char msg[IPC_BUFFER_SIZE]; + char result[IPC_BUFFER_SIZE]; + msg[0] = '\0'; + get_server_response(GET_DEVICE_PROPS, msg, NULL); + if (strlen(msg)) { + process_server_response(msg, result); + sock_printf(tmpl->sock, "%s", result); + } else { + sock_printf(tmpl->sock, "%s", "ERROR"); + } +} + +/* + find the list of available network interfaces for starting the RTSP stream server + */ +static void get_interfaces(struct template_state *tmpl, const char *name, const char *value, int argc, char **argv) +{ + char interfaces_list[IPC_BUFFER_SIZE]; + get_interfaces_list(interfaces_list); + sock_printf(tmpl->sock, "%s", interfaces_list); +} + +/* + sets the properties of a camera through IPC with the RTSP stream server + */ +static void set_device_quality(struct template_state *tmpl, const char *name, const char *value, int argc, char **argv) +{ + if (argc) { + if (send_server_message(argv[0])) { + printf("Error in setting camera properties\n"); + } + } +} + +static pid_t stream_server_pid = -1; + +/* + forks to create a new process for the RTSP stream + */ +static void start_rtsp_server(struct template_state *tmpl, const char *name, const char *value, int argc, char **argv) +{ + if (stream_server_pid == -1) { + stream_server_pid = fork(); + if (stream_server_pid < 0) { + printf("Fork failed\n"); + } else if (stream_server_pid == 0) { + if (execlp("stream_server", "stream_server", argv[0], NULL)==-1) { + printf("Error in launching the stream server\n"); + } + } + } else { + printf("Stream server running with PID: %d\n", stream_server_pid); + } +} + +static void stop_rtsp_server(struct template_state *tmpl, const char *name, const char *value, int argc, char **argv) +{ + if (stream_server_pid != -1) { + if(!kill(stream_server_pid, SIGINT)) { + stream_server_pid = -1; + printf("Stream server successfully killed\n"); + } else { + printf("Could not kill the stream server\n"); + } + } +} + /* get parameter list */ @@ -1061,4 +1138,9 @@ void functions_init(struct template_state *tmpl) tmpl->put(tmpl, "process_content", "", process_content); tmpl->put(tmpl, "get_param", "", get_param); tmpl->put(tmpl, "get_param_list", "", get_param_list); + tmpl->put(tmpl, "get_camera_details", "", get_camera_details); + tmpl->put(tmpl, "set_device_quality", "", set_device_quality); + tmpl->put(tmpl, "start_rtsp_server", "", start_rtsp_server); + tmpl->put(tmpl, "stop_rtsp_server", "", stop_rtsp_server); + tmpl->put(tmpl, "get_interfaces", "", get_interfaces); } diff --git a/rtsp_ipc.c b/rtsp_ipc.c new file mode 100644 index 0000000..d3f568a --- /dev/null +++ b/rtsp_ipc.c @@ -0,0 +1,142 @@ +#include "includes.h" +#include "rtsp_ipc.h" +#include +#include +#include +#include +#include +#include +#include +#include + +const char SOCKET_PATH[80] = "/tmp/rtsp_server.sock"; + +const char* RTSP_MESSAGE_HEADER[] = { + "GDP", "SDP" +}; + +int send_server_message(char* msg) +{ + struct sockaddr_un addr; + int fd; + + if ((fd = socket(AF_UNIX, SOCK_STREAM, 0)) == -1) { + printf("Unable to create stream server socket\n"); + return -1; + } + + memset(&addr, 0, sizeof(addr)); + addr.sun_family = AF_UNIX; + strcpy(addr.sun_path, SOCKET_PATH); + + if (connect(fd, (struct sockaddr*)&addr, sizeof(addr)) == -1) { + printf("Unable to connect to the stream server\n"); + return -1; + } else { + write(fd, msg, strlen(msg)); + close(fd); + } + return 0; +} + +void get_server_response(RTSP_MESSAGE_TYPE type, char* reply, char* args) +{ + struct sockaddr_un addr; + int fd; + + if ((fd = socket(AF_UNIX, SOCK_STREAM, 0)) == -1) { + printf("Unable to create stream server socket\n"); + reply[0] = '\0'; + return; + } + + memset(&addr, 0, sizeof(addr)); + addr.sun_family = AF_UNIX; + strcpy(addr.sun_path, SOCKET_PATH); + + if (connect(fd, (struct sockaddr*)&addr, sizeof(addr)) == -1) { + reply[0] = '\0'; + printf("Unable to connect to the stream server\n"); + } else { + switch(type) { + case GET_DEVICE_PROPS: + write(fd, "GDP", 4); + break; + default: + printf("Malformed message from stream server\n"); + } + + char read_buffer[IPC_BUFFER_SIZE]; + read_buffer[0] = '\0'; + int bytes_read = recv(fd, read_buffer, sizeof(read_buffer), 0); + read_buffer[bytes_read] = '\0'; + if (bytes_read != -1) { + strcpy(reply, read_buffer); + } + } + close(fd); +} + +RTSP_MESSAGE_TYPE get_message_type(char* header) +{ + for (int i = 0; i < RTSP_MESSAGE_TYPE_COUNT; i++) { + if (!strcmp(header, RTSP_MESSAGE_HEADER[i])) { + return i; + } + } + return ERROR; +} + +void process_server_response(char* reply, char* result) +{ + char* p = strtok(reply, "$"); + + char* msg_header = strdup(p); + RTSP_MESSAGE_TYPE message_type; + message_type = get_message_type(msg_header); + + p = strtok(NULL, "$"); + result[0] = '\0'; + + switch (message_type) { + case GET_DEVICE_PROPS: + ; + if (result) { + strcpy(result, p); + } + break; + default: + printf("Malformed message from stream server\n"); + } +} + +// Gets list of available network interfaces for starting the RTSP stream server +void get_interfaces_list(char* interface_list) +{ + struct ifaddrs *ifaddr, *ifa; + char host[NI_MAXHOST]; + + if (getifaddrs(&ifaddr) == -1) { + printf("Could not get IPs"); + } + interface_list[0] = '\0'; + sprintf(interface_list, "{\"interfaces\": ["); + int i = 0; + for (ifa = ifaddr; ifa != NULL; ifa = ifa->ifa_next) { + if (ifa->ifa_addr == NULL) { + continue; + } + getnameinfo(ifa->ifa_addr,sizeof(struct sockaddr_in), host, NI_MAXHOST, + NULL, 0, NI_NUMERICHOST); + if (ifa->ifa_addr->sa_family==AF_INET) { + if (i == 0) { + sprintf(interface_list, "%s\"%s\"", interface_list, ifa->ifa_name); + } else { + sprintf(interface_list, "%s,\"%s\"", interface_list, ifa->ifa_name); + } + i++; + } + } + sprintf(interface_list, "%s]}", interface_list); + freeifaddrs(ifaddr); +} diff --git a/rtsp_ipc.h b/rtsp_ipc.h new file mode 100644 index 0000000..a87598c --- /dev/null +++ b/rtsp_ipc.h @@ -0,0 +1,18 @@ +#ifndef RTSP_IPC_H +#define RTSP_IPC_H + +static const unsigned int IPC_BUFFER_SIZE = 10000; + +typedef enum RTSP_MESSAGE_TYPE {GET_DEVICE_PROPS, + SET_DEVICE_PROPS, + ERROR, + RTSP_MESSAGE_TYPE_COUNT} + RTSP_MESSAGE_TYPE; + +void get_server_response(RTSP_MESSAGE_TYPE type, char* reply, char* args); +int send_server_message(char* msg); +void process_server_response(char* reply, char* result); +void get_interfaces_list(char* interface_list); +RTSP_MESSAGE_TYPE get_message_type(char* header); + +#endif diff --git a/web_server.c b/web_server.c index 78fa5c2..54a2568 100644 --- a/web_server.c +++ b/web_server.c @@ -13,6 +13,9 @@ #else #include #include +#include +#include +#include #endif #ifndef SYSTEM_FREERTOS @@ -273,9 +276,25 @@ static void connection_process(struct connection_state *c) */ static bool check_origin(const char *origin) { - if (strcmp(origin, "http://10.0.1.128") == 0) { - // always accept - return true; + struct ifaddrs *ifaddr, *ifa; + char host[NI_MAXHOST]; + + if (getifaddrs(&ifaddr) == -1) { + printf("Could not get IPs"); + } + + // check for matching IPs on all interfaces of the device + for (ifa = ifaddr; ifa != NULL; ifa = ifa->ifa_next) { + if (ifa->ifa_addr == NULL) { + continue; + } + getnameinfo(ifa->ifa_addr,sizeof(struct sockaddr_in), host, NI_MAXHOST, + NULL, 0, NI_NUMERICHOST); + if (ifa->ifa_addr->sa_family==AF_INET) { + if (strstr(origin, host) != NULL) { + return true; + } + } } #ifdef SYSTEM_FREERTOS @@ -848,9 +867,6 @@ int main(int argc, char *argv[]) // setup default allowed origin setup_origin(public_origin); - /* test_config(); */ - /* exit(1); */ - while ((opt=getopt(argc, argv, "p:s:b:hd:uf:O:")) != -1) { switch (opt) { case 'p': @@ -899,6 +915,14 @@ int main(int argc, char *argv[]) console_printf("Failed to ignore SIGPIPE: %m\n"); } + // summarily ignore SIGPIPE; without this, if a download is + // interrupted sock_write's write() call will kill the process + // with SIGPIPE + web_debug(4, "Ignoring sig pipe\n"); + if (signal(SIGPIPE, sig_pipe_handler) == SIG_ERR) { + console_printf("Failed to ignore SIGPIPE: %m\n"); + } + pthread_mutex_init(&lock, NULL); if (serial_port) {