diff --git a/.gitignore b/.gitignore new file mode 100644 index 0000000..1c8938c --- /dev/null +++ b/.gitignore @@ -0,0 +1,3 @@ +*.o +generated +web_server diff --git a/Makefile b/Makefile index 6764fbf..6c56a16 100644 --- a/Makefile +++ b/Makefile @@ -1,7 +1,7 @@ CC=gcc -CFLAGS=-Wall -g -Werror +CFLAGS=-Wall -g -Werror -std=gnu99 -SRC = $(wildcard *.c) $(wildcard lib/*.c) $(wildcard linux/*.c) +SRC = $(wildcard *.c) $(wildcard lib/*.c) $(wildcard linux/*.c) $(wildcard posix/*.c) OBJ = $(SRC:%.c=%.o) LIBS = -ltalloc -lpthread @@ -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 ../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/README.md b/README.md index a11caed..ff130cc 100644 --- a/README.md +++ b/README.md @@ -16,3 +16,8 @@ Some information on the JSON protocol used is here: https://docs.google.com/document/d/12IQFXDRIif06BiriHSCGdiJGZ6zsQ_phQsG_iI6_MAo/edit?usp=sharing + #### Build Notes + _Ubuntu 16.04_ + - libtalloc-dev is required to build this project. You can install the required package with the following command: `sudo apt-get install libtalloc-dev` + + diff --git a/cgi.c b/cgi.c index 32bd876..daf5652 100644 --- a/cgi.c +++ b/cgi.c @@ -21,6 +21,10 @@ #include "includes.h" #include +#ifdef _POSIX_VERSION +#include "posix/functions.h" +#endif + #define CONTENT_DISPOSITION "Content-Disposition:" #define CONTENT_TYPE "Content-Type:" #define MULTIPART_FORM_DATA "multipart/form-data" @@ -430,6 +434,7 @@ static const struct mime_type { {".txt", "text/plain", MIME_TYPE_TEXT_PLAIN}, {".html", "text/html;charset=UTF-8", MIME_TYPE_TEXT_HTML}, {".mp4", "video/mp4", MIME_TYPE_VIDEO_MP4}, + {".avi", "video/avi", MIME_TYPE_VIDEO_AVI}, {".bin", "data", MIME_TYPE_UNKNOWN}, {".svg", "image/svg+xml", MIME_TYPE_IMAGE_SVG}, {".js", "application/javascript", MIME_TYPE_JAVASCRIPT}, @@ -588,13 +593,11 @@ static void download(struct cgi_state *cgi, const char *path) mtype = get_mime_type(path); -#ifdef SYSTEM_FREERTOS if (strncmp(path, "fs/", 3) == 0) { download_filesystem(cgi, path); return; } -#endif - + size_t size = 0; const char *contents = get_embedded_file(path, &size); if (!contents) { @@ -649,6 +652,12 @@ static bool setup_standalone(struct cgi_state *cgi) cgi->content_length = atoi(&line[16]); } else if (strncasecmp(line,"Content-Type: ", 14)==0) { cgi->content_type = talloc_strdup(cgi, &line[14]); + } else if (strncasecmp(line,"Origin: ", 8)==0) { + cgi->origin = talloc_strdup(cgi, &line[8]); + if (cgi->check_origin != NULL && !cgi->check_origin(cgi->origin)) { + cgi->http_error(cgi, "400 Bad Origin", "", + "request with incorrect origin header"); + } } /* ignore all other requests! */ } diff --git a/cgi.h b/cgi.h index 72f991c..43793f3 100644 --- a/cgi.h +++ b/cgi.h @@ -41,10 +41,12 @@ struct cgi_state { const char *err, const char *header, const char *info); void (*download)(struct cgi_state *cgi, const char *path); void (*put)(struct cgi_state *cgi, const char *name, const char *value); + bool (*check_origin)(const char *origin); /* data */ struct cgi_var *variables; struct template_state *tmpl; + const char *origin; char *content_type; unsigned long content_length; int request_post; @@ -65,6 +67,7 @@ enum CGI_MIME_TYPE {MIME_TYPE_IMAGE_GIF, MIME_TYPE_TEXT_PLAIN, MIME_TYPE_TEXT_HTML, MIME_TYPE_VIDEO_MP4, + MIME_TYPE_VIDEO_AVI, MIME_TYPE_JAVASCRIPT, MIME_TYPE_JSON, MIME_TYPE_CSS, diff --git a/files/Makefile b/files/Makefile index 010bc34..1cdbd1e 100644 --- a/files/Makefile +++ b/files/Makefile @@ -1,6 +1,6 @@ all: @echo "Generating embedded.c" - @./embed.py *.html images/*.svg */*.js */*.json */*.css */*.jpg */*.png */*.mjpg data/*.xml + @./embed.py *.html images/*.svg */*.js */*.json */*.css */*.jpg */*.png */*.mjpg data/*.xml apsync/*.html @echo "Generating manifest" @./gen_manifest.sh @echo "Generating version.h" diff --git a/files/apsync/calibration.html b/files/apsync/calibration.html new file mode 100644 index 0000000..f1cf313 --- /dev/null +++ b/files/apsync/calibration.html @@ -0,0 +1,331 @@ + + + + ArduPilot + + + + + + + + + + + + + +

ArduPilot

+ +
+ + +
+ +
+ +
+

Six-Axis Accelerometer Calibration

+ +A six axis accelerometer calibration involves you placing your vehicle +in each of 6 orientations in turn, as you are guided by the prompts +below. This type of calibration is good if you will be doing 3D +flying, or if you find that you get poor results with a simple +accelerometer calibration. + +

After a six-axis calibration you will need to power cycle your vehicle + +

+ +
+


+

+


+ +


+ +

Sensor State

+ + + + + +
+ + + + + +
VariableValue
Roll
Pitch
+ + + + + + + + + + + + + + + + + + +
NameXYZ
Sensor
Offsets
Scaling
+ +
+ Accelerometers (X, Y, Z)
+

+

+
+ +
+ +

Magnetometer calibration

+ +To calibrate the magnetometer you will need to move to a location well +away from all metal. Then press the button below to start +calibration. Once started you will need to rotate the vehicle about +all axes. + +

A progress bar will display to show how far you are through the calibration. + +

After a magnetometer calibration you will need to power cycle your vehicle + +

+ +
+
+

Calibration progress:
+

+
+
+
+
+ +


+ +


+ +

Sensor State

+ + + + +
+ + + + + + +
VariableValue
Roll
Pitch
Yaw
+ + + + + + + + +
SensorXYZ
Magnetometer
+ +
+ Magnetometer (X, Y, Z)
+

+

+
+ + +
+

home + + + + + + diff --git a/files/apsync/status.html b/files/apsync/status.html new file mode 100644 index 0000000..0501bdf --- /dev/null +++ b/files/apsync/status.html @@ -0,0 +1,445 @@ + + + + ArduPilot + + + + + + + + + + + + + + +

ArduPilot

+ +
+ + + + + + + +
+ +
+ +Core system information

+ +

System Information

+ + + + + + +
VariableValue
Uptime
FC MAVLink count
FC MAVLink baudrate
+ +

Flight Board Status

+ + + + + +
Mode
Uptime
Voltage
+
+ +
+

Attitude

+ + + + + +
+ + + + + + +
VariableValue
Roll
Pitch
Yaw
+ +

IMU Status

+ + + + + + + + + + + + + + + + + + +
SensorXYZ
Accelerometer
Gyroscope
Magnetometer
+ +
+ Accelerometers (X, Y, Z)
+

+ Gyro (roll, pitch, yaw)
+

+ Magnetometer (X, Y, Z)
+

+

+
+ + +
+ + + + + +
+ + + + + +
VariableValue
Pressure Absolute
Pressure Relative
Temperature
+ +
+ Pressure
+

+ Temperature
+

+

+ +
+ +
+ + + + +
+ + + + + + + + +
VariableValue
FixType
Numsats
EKF Status
Latitude (GPS)
Longitude (GPS)
Altitude (AMSL)
+
+
+ +
+ + + + + + + + + + + +
VariableValue
Flags
Latitude
Longitude
Altitude
Velocity Variance
Position Variance (H)
Position Variance (V)
Compass Variance
+
+ +
+ + + + + +
+ + + + + + + + + + +
VariableValue
Channels
Chan1
Chan2
Chan3
Chan4
Chan5
Chan6
Chan7
+
+ Stick input (chan1, chan2, chan3, chan4)
+

+

+ +
+ +
+ snapshot +

+

+ JPG Frames + MJPG Stream
+
+ + + + +
+ +
+ +

Motor Testing

+ + +Select motor to test, along with test power level (as a percentage) +and test time in seconds. If you choose "All Motors" then all 4 motors +will come on in sequence, starting with the front-right motor and +proceeding clockwise from there. + +

+ + + + + + +

+ Test Power + + +
Test Time (s) + + +

+ +
+ +

Flight Controller Messages

+ + + +
+ + Refresh rate:  + + +
+

home + + + + + + diff --git a/files/apsync/system.html b/files/apsync/system.html new file mode 100644 index 0000000..05ccc12 --- /dev/null +++ b/files/apsync/system.html @@ -0,0 +1,95 @@ + + + + ArduPilot + + + + + + + + +

ArduPilot

+ +

System Control

+ +Control system setup of your vehicle +

+

+

+ +


+

WiFi Setup

+ +Configure your WiFi SSID, password, authentication type and +channel. + +

If using WEP you need to use a 5 character password. For WPA2 your +password needs to be at least 8 characters long. Using WPA2 is +recommended.

+ +

+ WiFi Configuration + WiFi SSID:
+
+WiFi Password:
+ +Show password
+Auth Type: + +WiFi Channel: + +
+
+ + + +
+

Reboot

+ +Reboot your companion computer or flight controller board

+ + + + +


+

home + + + + 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/calibration.html b/files/calibration.html index e89db1f..6fe1f2d 100644 --- a/files/calibration.html +++ b/files/calibration.html @@ -19,7 +19,7 @@
- +
@@ -50,7 +50,7 @@

Six-Axis Accelerometer Calibration

flying, or if you find that you get poor results with a simple accelerometer calibration. -

After a six-axis calibration you will need to power cycle your vehicle +

After a six-axis calibration you will need to power cycle your vehicle before you can fly.

@@ -111,7 +111,7 @@

Magnetometer calibration

A progress bar will display to show how far you are through the calibration. -

After a magnetometer calibration you will need to power cycle your vehicle +

After a magnetometer calibration you will need to power cycle your vehicle before you can fly.

@@ -146,12 +146,17 @@

Sensor State

+ Offsets +
+
+
+ Magnetometer (X, Y, Z)
-

+

@@ -189,12 +194,12 @@

Sensor State

} function simple_accel_cal_callback(result) { + var color = "red"; if (result == 0) { result = "calibration successful"; color = "green"; } else { result = "calibration failed: " + result; - color = "red"; } set_message_color("simple_accel_message", color, result); } @@ -215,6 +220,7 @@

Sensor State

function six_axis_accel_cal_callback(result) { six_axis_running = false; + var color = "red"; if (result == 0) { // wait for level six_axis_stage = 1; @@ -223,7 +229,6 @@

Sensor State

color = "blue"; } else { result = "calibration failed: " + result; - color = "red"; document.getElementById("continue_div").style.display = "none"; } set_message_color("six_axis_accel_message", color, result); @@ -238,6 +243,7 @@

Sensor State

} function mag_cal_callback(result) { + var color = "red"; if (result == 0) { // wait for level six_axis_stage = 1; @@ -247,7 +253,6 @@

Sensor State

mag_completion_pct = -1; } else { result = "calibration failed: " + result; - color = "red"; document.getElementById("mag_div").style.display = "none"; } set_message_color("mag_message", color, result); @@ -265,9 +270,15 @@

Sensor State

var name = plist[i].name; var value = plist[i].value; var element = document.getElementById(name); + params[name] = value; if (element != null) { - element.innerHTML = value; - params[name] = value; + element.innerHTML = value.toFixed(1); + } + var elements = document.getElementsByName(name); + if (elements != null) { + for (var j=0; jIndex of / -

Directory size: MByte
+

Directory size: MByte in files
Card Size:  GByte
Card Free:  GByte
Card Label:
-


+

+


home @@ -34,10 +35,44 @@

Index of /

diff --git a/files/index.html b/files/index.html index 968f313..1ccedb1 100644 --- a/files/index.html +++ b/files/index.html @@ -15,17 +15,16 @@

ArduPilot Web Server

-Welcome to the ArduPilot Streaming GPS Drone

+Welcome to the ArduPilot Web Interface!

diff --git a/files/js/charts.js b/files/js/charts.js index bd6057f..010adb0 100644 --- a/files/js/charts.js +++ b/files/js/charts.js @@ -15,9 +15,12 @@ function create_chart(canvass_name, variables) { yRangeFunction : chart_range }; charts[canvass_name] = new SmoothieChart(settings); for (var i=0; i' + message + ''; + } + mavlink_statustext(MAV_SEVERITY_INFO, message); +} + +/* + get utc time in seconds +*/ +function get_utc_sec() { + var d = new Date(); + var dsec = d.getTime() / 1000; + return dsec; +} + /* set the date on the sonix board */ function set_sonix_date() { var d = new Date(); - var dsec = d.getTime() / 1000; + var dsec = get_utc_sec(); var tz_offset = -d.getTimezoneOffset() * 60; d = (dsec+0.5).toFixed(0); - command_send("set_time_utc(" + d + "," + tz_offset + ")"); + var cmd = "set_time_utc(" + d + "," + tz_offset + ")"; + command_send(cmd); } -/* always set the date at connection time */ -set_sonix_date(); - +// set date every 20s +setInterval(set_sonix_date(), 20000); diff --git a/files/js/ublox.js b/files/js/ublox.js index 23fc148..433f6f4 100644 --- a/files/js/ublox.js +++ b/files/js/ublox.js @@ -15,7 +15,7 @@ function set_last_pos(pos) { handle downloaded MGA data */ function handle_mga_data(data) { - var utc_sec = new Date().getTime() / 1000; + var utc_sec = get_utc_sec(); var new_data = { timestamp : utc_sec, data : data }; db_store("mga_data", new_data); set_mga_data(new_data); @@ -34,8 +34,10 @@ function download_mga_data() { */ function set_mga_data(data) { console.log("mga_data length " + data.data.byteLength); - var utc_sec = new Date().getTime() / 1000; - if (data.timestamp > utc_sec + 60*60*24*7) { + var utc_sec = get_utc_sec(); + var age_days = (utc_sec - data.timestamp) / (60*60*24); + console.log("mga data age: " + age_days); + if (age_days > 2) { download_mga_data(); } var formData = new FormData(); @@ -50,9 +52,6 @@ function set_mga_data(data) { sent_last_pos = true; } - /* send the date again */ - set_sonix_date(); - var xhr = createCORSRequest("POST", drone_url + "/ajax/command.json"); xhr.send(formData); setTimeout(poll_ublox_status, mga_poll_period); @@ -67,7 +66,7 @@ function check_mga_status(json) { return; } page_fill_json_html(mga_status); - var utc_sec = new Date().getTime() / 1000; + var utc_sec = get_utc_sec(); if (mga_status.offline_cache_size > 0 && (last_pos == null || sent_last_pos)) { // its all up to date, don't send it the data diff --git a/files/nvram.html b/files/nvram.html index e2a594e..adfbf06 100644 --- a/files/nvram.html +++ b/files/nvram.html @@ -23,7 +23,7 @@

Video Parameters

-

+

diff --git a/files/parameters.html b/files/parameters.html index 88072a3..cee801c 100644 --- a/files/parameters.html +++ b/files/parameters.html @@ -60,7 +60,7 @@ option.innerHTML = category; category_select.appendChild(option); } - category_select.value = "Actions"; + category_select.value = "All"; var param_docs = {}; var plist; @@ -68,7 +68,6 @@ function fill_parameters(json) { var table = document.getElementById("param_table"); - var search = document.getElementById("search").value.toUpperCase(); // delete any existing rows var nrows = table.rows.length; @@ -105,10 +104,10 @@ var c2 = row.insertCell(2); var c3 = row.insertCell(3); var c4 = row.insertCell(4); - show_hide(row, search); byname[rowdata.name] = rowdata.value; } fill_param_docs(); + search_change(); } function refresh() { @@ -125,6 +124,26 @@ if (select != null) { select.value = value; } + set_bitoptions(name, value); + } + + function set_bitoptions(name, value) { + if (param_docs[name] == null || param_docs[name].bitoptions == null) { + return; + } + var bitoptions = param_docs[name].bitoptions; + var nbits = bitoptions.length; + for (var i=0; i' + opt.label + ''; + sel += selopt; + } + cell.innerHTML = sel; + set_bitoptions(name, value); + } + function fill_param_docs() { var table = document.getElementById("param_table"); var nrows = table.rows.length; @@ -186,9 +238,13 @@ if (pdoc) { tr.cells[3].innerHTML = pdoc.humanName; tr.cells[4].innerHTML = pdoc.documentation; + tr.cells[2].innerHTML = ''; if (pdoc.values != null) { fill_select_list(name, tr, pdoc.values); } + if (pdoc.bitoptions != null) { + fill_bitoptions(name, tr, pdoc.bitoptions); + } } } } @@ -219,9 +275,9 @@ nchildren = p.children.length; } for (var j=0; jTransmitter +
@@ -132,6 +133,7 @@

IMU Status

VariableValue FixType
Numsats
+ EKF Status
Latitude (GPS)
Longitude (GPS)
Altitude (AMSL)
@@ -177,6 +179,7 @@

IMU Status

+ @@ -285,17 +288,26 @@

Motor Testing

function motor_test(motornum) { var motorpower = document.getElementById("motor_power").value; var testtime = document.getElementById("test_time").value; - mavlink_command_long_send(MAV_CMD_DO_MOTOR_TEST, 0, motornum, 0, motorpower, testtime); + var motorcount = 0; + if (motornum == 0) { + motornum = 1; + motorcount = 4; + } + mavlink_command_long_send(MAV_CMD_DO_MOTOR_TEST, 0, motornum, 0, motorpower, testtime, motorcount); } -Select motor to test, along with test power level (as a percentage) and test time in seconds. +Select motor to test, along with test power level (as a percentage) +and test time in seconds. If you choose "All Motors" then all 4 motors +will come on in sequence, starting with the front-right motor and +proceeding clockwise from there.

+

Test Power @@ -326,14 +338,22 @@

Motor Testing

+ + +
+ +

Flight Controller Messages

+ + +
Refresh rate:  @@ -112,6 +112,9 @@

Factory Reset

your ArduPilot you should change your WiFi password immediately after rebooting.

+

NOTE! You must first power-cycle and then re-calibrate after a + reset or you will not be able to arm.

+


diff --git a/functions.c b/functions.c index 421faf9..5b54809 100644 --- a/functions.c +++ b/functions.c @@ -8,8 +8,32 @@ #include "mavlink_json.h" #include "mavlink_core.h" #include "cgi.h" +#include "rtsp_ipc.h" + +#ifdef _POSIX_VERSION +#include "posix/functions.h" +#endif +#ifdef __linux__ +#include "linux/functions.h" +#endif + +#ifdef _POSIX_VERSION +#include "posix/functions.h" +#endif #ifdef SYSTEM_FREERTOS +#include "../mavlink_wifi.h" +#include "video_main.h" +#include +#include +#include +#include "../tx_upload.h" +#include "../ublox.h" +#include "files/version.h" +#include +#include +#endif + /* get uptime in seconds */ @@ -21,6 +45,7 @@ static void uptime(struct template_state *tmpl, const char *name, const char *va /* get FC mavlink packet count */ +unsigned mavlink_fc_pkt_count(); static void fc_mavlink_count(struct template_state *tmpl, const char *name, const char *value, int argc, char **argv) { sock_printf(tmpl->sock, "%u", mavlink_fc_pkt_count()); @@ -29,9 +54,16 @@ static void fc_mavlink_count(struct template_state *tmpl, const char *name, cons /* get FC mavlink baudrate */ +int uart2_get_baudrate(); + static void fc_mavlink_baudrate(struct template_state *tmpl, const char *name, const char *value, int argc, char **argv) { - sock_printf(tmpl->sock, "%u", uart2_get_baudrate()); + int baudrate = uart2_get_baudrate(); + if (baudrate == -1) { + sock_printf(tmpl->sock, "\"Not in use\""); + } else { + sock_printf(tmpl->sock, "%u", baudrate); + } } /* @@ -42,7 +74,6 @@ static void mem_free(struct template_state *tmpl, const char *name, const char * int mem_type = argc>0?atoi(argv[0]):1; sock_printf(tmpl->sock, "%u", xPortGetFreeHeapSize(mem_type)); } -#endif /* get upload progress @@ -320,7 +351,11 @@ static void mavlink_message_send(struct template_state *tmpl, const char *name, static void reboot_companion(struct template_state *tmpl, const char *name, const char *value, int argc, char **argv) { console_printf("rebooting ...\n"); +#ifdef SYSTEM_FREERTOS reboot(); +#else + __reboot(); +#endif } extern void snx_nvram_bootup_upgrade(void); @@ -354,18 +389,16 @@ static void format_storage(struct template_state *tmpl, const char *name, const #endif } - -#ifdef SYSTEM_FREERTOS /* validate auth settings for wifi return error-string on error. Return NULL if OK */ -static const char *validate_ssid_password(const char *ssid, +const char *validate_ssid_password(const char *ssid, const char *password, - enc_auth_t auth_mode, + apweb_enc_auth_t auth_mode, int channel) { - if (channel < 1 || channel > 14) { + if (channel < 0 || channel > 14) { return "Invalid WiFi channel"; } switch (auth_mode) { @@ -391,6 +424,8 @@ static const char *validate_ssid_password(const char *ssid, return "Invalid auth mode"; } +#ifdef SYSTEM_FREERTOS + /* set ssid and password */ @@ -421,8 +456,8 @@ static void set_ssid(struct template_state *tmpl, const char *name, const char * snx_nvram_integer_set("WIFI_DEV", "AP_AUTH_MODE", auth_mode); snx_nvram_integer_set("WIFI_DEV", "AP_CHANNEL_INFO", ap_channel); - snx_nvram_string_set("WIFI_DEV", "AP_SSID_INFO", ssid); - snx_nvram_string_set("WIFI_DEV", "AP_KEY_INFO", password); + snx_nvram_string_set("WIFI_DEV", "AP_SSID_INFO", __DECONST(char *,ssid)); + snx_nvram_string_set("WIFI_DEV", "AP_KEY_INFO", __DECONST(char *,password)); sock_printf(tmpl->sock, "Set SSID and password"); } @@ -430,7 +465,7 @@ static void set_ssid(struct template_state *tmpl, const char *name, const char * /* get ssid and password */ -static void get_ssid(struct template_state *tmpl, const char *name, const char *value, int argc, char **argv) +static void get_ssid_info(struct template_state *tmpl, const char *name, const char *value, int argc, char **argv) { char ssid[50]="", pass[50]=""; int mode=0, channel=0; @@ -444,6 +479,18 @@ static void get_ssid(struct template_state *tmpl, const char *name, const char * ssid, pass, channel, mode); } +/* + get ssid + */ +static void get_ssid(struct template_state *tmpl, const char *name, const char *value, int argc, char **argv) +{ + char ssid[50]=""; + + snx_nvram_string_get("WIFI_DEV", "AP_SSID_INFO", ssid); + + sock_printf(tmpl->sock, "%s", ssid); +} + /* handle sonix fw update */ @@ -452,12 +499,15 @@ static void handle_sonix_upgrade(struct template_state *tmpl, const char *filena set_upload_message("checking firmware MD5"); set_upload_progress(1); if (check_fw_md5((const unsigned char *)filedata, size)) { - set_upload_message("Good MD5 on image - upgrading. Please reconnect WiFi in 30 seconds"); + set_upload_message("Good MD5 on image"); + mdelay(1000); set_upload_progress(100); // give time for UI to update + set_upload_message("starting upgrade"); mdelay(3000); fw_upgrade(__DECONST(char*,filedata), size); - set_upload_message("rebooting"); + set_upload_message("success - rebooting"); + mdelay(3000); } else { set_upload_message("Bad MD5 on image"); } @@ -508,6 +558,7 @@ static void handle_file_upload(struct template_state *tmpl, const char *filename } else { result = "file write failed"; } + f_sync(&fh); f_close(&fh); } else { result = "failed to open file"; @@ -709,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 */ @@ -842,21 +965,27 @@ static void nvram_pack_values(struct template_state *tmpl, const char *name, con while (cfg_cnt--) { nvram_cfg_name_data_info_t *cfg = &cfg_name_info[cfg_cnt]; + unsigned int data_len = 0; cfg_name = cfg->name; + if (snx_nvram_get_data_len(pack_name, cfg_name, &data_len) != NVRAM_SUCCESS || data_len == 0) { + continue; + } if (!first) { sock_printf(tmpl->sock, ", "); } first = false; - sock_printf(tmpl->sock, "{ \"name\" : \"%s\", \"size\" : %u, ", - cfg_name, cfg->data_info.data_len); + sock_printf(tmpl->sock, "{ \"name\" : \"%s\", \"size\" : %u, ", cfg_name, data_len); void *cfg_data = NULL; - cfg_data = talloc_zero_size(cfg_name_info, cfg->data_info.data_len); + cfg_data = talloc_zero_size(cfg_name_info, data_len); if (cfg_data == NULL) { continue; } cfg->data_info.data = cfg_data; snx_nvram_get_immediately(pack_name, cfg_name, &cfg->data_info); + if (cfg->data_info.data_type == NVRAM_DT_BIN_RAW) { + snx_nvram_binary_get(pack_name, cfg_name, cfg_data); + } switch (cfg->data_info.data_type) { case NVRAM_DT_STRING: @@ -887,6 +1016,7 @@ static void nvram_pack_values(struct template_state *tmpl, const char *name, con sock_printf(tmpl->sock, "\"type\" : \"unknown\" }"); break; } + talloc_free(cfg_data); cfg_data = NULL; } @@ -921,22 +1051,30 @@ static void nvram_set_value(struct template_state *tmpl, const char *name, const } uint32_t i; int dtype = -1; + nvram_cfg_name_data_info_t *cfg = NULL; + for (i=0; iname) == 0) { + break; + } + } - cfg_data = talloc_zero_size(cfg_name_info, cfg->data_info.data_len); - if (cfg_data == NULL) { - continue; - } - cfg->data_info.data = cfg_data; - snx_nvram_get_immediately(pack_name, cfg_name, &cfg->data_info); - dtype = cfg->data_info.data_type; + if (i == cfg_cnt) { + goto failed; } + void *cfg_data = talloc_zero_size(cfg_name_info, cfg->data_info.data_len); + if (cfg_data == NULL) { + goto failed; + } + cfg->data_info.data = cfg_data; + snx_nvram_get_immediately(pack_name, cfg_name, &cfg->data_info); + dtype = cfg->data_info.data_type; + switch (dtype) { case NVRAM_DT_STRING: - rc = snx_nvram_string_set(pack_name, cfg_name, svalue); + rc = snx_nvram_string_set(pack_name, cfg_name, __DECONST(char *,svalue)); break; case NVRAM_DT_INT: rc = snx_nvram_integer_set(pack_name, cfg_name, atoi(svalue)); @@ -957,12 +1095,10 @@ static void nvram_set_value(struct template_state *tmpl, const char *name, const void functions_init(struct template_state *tmpl) { #ifdef SYSTEM_FREERTOS - tmpl->put(tmpl, "uptime", "", uptime); - tmpl->put(tmpl, "mem_free", "", mem_free); tmpl->put(tmpl, "snapshot", "", snapshot); tmpl->put(tmpl, "mjpgvideo", "", mjpg_video); tmpl->put(tmpl, "take_picture", "", take_picture); - tmpl->put(tmpl, "get_ssid", "", get_ssid); + tmpl->put(tmpl, "get_ssid_info", "", get_ssid_info); tmpl->put(tmpl, "set_ssid", "", set_ssid); tmpl->put(tmpl, "sonix_version", "", sonix_version); tmpl->put(tmpl, "file_upload", "", file_upload); @@ -972,14 +1108,23 @@ void functions_init(struct template_state *tmpl) tmpl->put(tmpl, "file_listdir", "", file_listdir); tmpl->put(tmpl, "disk_info", "", disk_info); tmpl->put(tmpl, "set_time_utc", "", set_time_utc); - tmpl->put(tmpl, "fc_mavlink_count", "", fc_mavlink_count); - tmpl->put(tmpl, "fc_mavlink_baudrate", "", fc_mavlink_baudrate); tmpl->put(tmpl, "mga_status", "", mga_status); tmpl->put(tmpl, "mga_upload", "", mga_upload); tmpl->put(tmpl, "nvram_pack_list", "", nvram_pack_list); tmpl->put(tmpl, "nvram_pack_values", "", nvram_pack_values); tmpl->put(tmpl, "nvram_set_value", "", nvram_set_value); + tmpl->put(tmpl, "get_ssid", "", get_ssid); #endif // SYSTEM_FREERTOS +#ifdef _POSIX_VERSION + posix_functions_init(tmpl); +#endif +#ifdef __linux__ + linux_functions_init(tmpl); +#endif + tmpl->put(tmpl, "uptime", "", uptime); + tmpl->put(tmpl, "mem_free", "", mem_free); + tmpl->put(tmpl, "fc_mavlink_count", "", fc_mavlink_count); + tmpl->put(tmpl, "fc_mavlink_baudrate", "", fc_mavlink_baudrate); tmpl->put(tmpl, "format_storage", "", format_storage); tmpl->put(tmpl, "factory_reset", "", factory_reset); tmpl->put(tmpl, "reboot_companion", "", reboot_companion); @@ -993,5 +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/functions.h b/functions.h index c1c44bb..e6204b9 100644 --- a/functions.h +++ b/functions.h @@ -1,5 +1,18 @@ +#pragma once /* provide server side functions in C */ void functions_init(struct template_state *tmpl); + +typedef enum { + AUTH_NONE= 0, + AUTH_WEP = 1, + AUTH_WPA = 2, + AUTH_WPA2 = 3, +} apweb_enc_auth_t ; + +const char *validate_ssid_password(const char *ssid, + const char *password, + apweb_enc_auth_t auth_mode, + int channel); diff --git a/includes.h b/includes.h index 61f3705..2586e83 100644 --- a/includes.h +++ b/includes.h @@ -1,8 +1,30 @@ #pragma once +#ifdef SYSTEM_FREERTOS +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include "socket_ctrl.h" +#include +#include "../talloc.h" +#include "../dev_console.h" +#include "../util/print_vprintf.h" +#else #include "linux/includes.h" +#include "mavlink_core.h" +#endif #include "cgi.h" #include "template.h" #include "web_files.h" -#include "mavlink_core.h" + + diff --git a/linux/functions.c b/linux/functions.c new file mode 100644 index 0000000..721a862 --- /dev/null +++ b/linux/functions.c @@ -0,0 +1,180 @@ +#include "../includes.h" +#include "../template.h" +#include "functions.h" +#include "../functions.h" + +#include +#include +#include +#include +#include +#include +#include +#include + +void sock_send_ssid(struct sock_buf *sock, const char *ssid, const char *pass, const unsigned channel, const unsigned mode) +{ + sock_printf(sock, "{ " + "\"ssid\": \"%s\", " + "\"password\" : \"%s\", " + "\"channel\" : %d, " + "\"authmode\" : %d " + "}", + ssid, pass, channel, mode); +} + +static void nmcli_property_string_get(struct template_state *tmpl, const char *ifname, const char *setting_property, char *ret, unsigned retlen) +{ + char cmd[300]; + char tmpfile[] = "/tmp/nmcli.XXXXXX"; + int content_fd = mkstemp(tmpfile); + if (content_fd == -1) { + sock_printf(tmpl->sock, "mkstemp failed"); + return; + } + /* TODO: do we REALLY want to link with the dbus libraries?! */ + /* note that the -s argument to nmcli is not present on Raspbian/Jessie */ + /* .... and manlfunctions on TX1's Ubuntu 16.04 */ + snprintf(cmd, sizeof(cmd), "nmcli c s %s | grep \"%s:\" | perl -pe 's/^[^ ]*[ ]*(.*)\n/$1/' >%s", ifname, setting_property, tmpfile); + if (system(cmd) == -1) { + sock_printf(tmpl->sock, "system failed"); + return; + } + memset(ret, '\0', retlen); + if (read(content_fd, ret, retlen) == -1) { + sock_printf(tmpl->sock, "read failed"); + return; + } + close(content_fd); +} + +static void nmcli_property_integer_get(struct template_state *tmpl, const char *ifname, const char *setting_property, int *ret) +{ + char text[300]; + nmcli_property_string_get(tmpl, ifname, setting_property, text, sizeof(text)); + *ret = atoi(text); +} + + +static void nmcli_property_string_set(struct template_state *tmpl, const char *ifname, const char *setting_property, const char *value) +{ + char cmd[300]; + /* TODO: do we REALLY want to link with the dbus libraries?! */ + snprintf(cmd, sizeof(cmd), "nmcli c m %s %s %s", ifname, setting_property, value); + if (system(cmd) == -1) { + sock_printf(tmpl->sock, "system failed"); + return; + } +} + +static void nmcli_property_integer_set(struct template_state *tmpl, const char *ifname, const char *setting_property, int value) +{ + char text[300]; + snprintf(text, sizeof(text), "%d", value); + nmcli_property_string_set(tmpl, ifname, setting_property, text); +} + + +/* + * work around nmcli variation on different versions of Ubuntu by + * fetching secret directly from files. Yay abusing root access. + */ +int nm_fetch_wpa_psk_secret(const char *ifname, char *password, const uint8_t passwordlen) +{ + char cmd[300]; + char tmpfile[] = "/tmp/nmcli.XXXXXX"; + int content_fd = mkstemp(tmpfile); + if (content_fd == -1) { + return -1; + } + /* TODO: do we REALLY want to link with the dbus libraries?! */ + /* note that the -s argument to nmcli is not present on Raspbian/Jessie */ + /* .... and manlfunctions on TX1's Ubuntu 16.04 */ + snprintf(cmd, sizeof(cmd), "cat /etc/NetworkManager/system-connections/%s | grep '^psk=' | cut -f 2 -d '=' | perl -pe 's/\n//'g >%s", ifname, tmpfile); + if (system(cmd) == -1) { + return -1; + } + memset(password, '\0', passwordlen); + if (read(content_fd, password, passwordlen) == -1) { + return -1; + } + close(content_fd); + return 0; +} + +#define streq(a,b) (strcmp(a,b) == 0) + +static const char *ifname = "WiFiAP"; + +/* + get ssid and password + */ +static const char *prop_ssid = "802-11-wireless.ssid"; +static const char *prop_sectype = "802-11-wireless-security.key-mgmt"; +static const char *prop_channel = "802-11-wireless.channel"; +static const char *prop_key = "802-11-wireless-security.psk"; +static void get_ssid(struct template_state *tmpl, const char *name, const char *value, int argc, char **argv) +{ + char ssid[50]="", pass[50], security_type[50]=""; + int mode=0, channel=0; + + nmcli_property_string_get(tmpl, ifname, prop_ssid, ssid, sizeof(ssid)); + nmcli_property_string_get(tmpl, ifname, prop_sectype, security_type, sizeof(security_type)); + nmcli_property_integer_get(tmpl, ifname, prop_channel, &channel); + + if (streq(security_type, "wpa-psk")) { + // nmcli_property_string_get(tmpl, ifname, prop_key, pass, sizeof(pass)); + if (nm_fetch_wpa_psk_secret(ifname, pass, sizeof(pass)) == -1) { + pass[0] = '\0'; + } + mode = AUTH_WPA2; + } else { + mode = -1; + } + + sock_send_ssid(tmpl->sock, ssid, pass, channel, mode); +} + + +/* + set ssid and password + */ +static void set_ssid(struct template_state *tmpl, const char *name, const char *value, int argc, char **argv) +{ + if (argc < 4) { + sock_printf(tmpl->sock, "invalid call\n"); + return; + } + const char *ssid = argv[0]; + const char *password = argv[1]; + const char *authtype = argv[2]; + const char *channel = argv[3]; + if (!ssid || !password || !authtype || !channel) { + sock_printf(tmpl->sock, "invalid SSID or password\n"); + } + + int auth_mode = atoi(authtype); + int ap_channel = atoi(channel); + + const char *ret = validate_ssid_password(ssid, password, auth_mode, ap_channel); + if (ret) { + // invalid input + sock_printf(tmpl->sock, "%s", ret); + return; + } + + console_printf("Setting SSID='%s' password='%s' authtype=%s channel=%u\n", ssid, password, authtype, ap_channel); + + nmcli_property_integer_set(tmpl, ifname, prop_sectype, auth_mode); + nmcli_property_integer_set(tmpl, ifname, prop_channel, ap_channel); + nmcli_property_string_set(tmpl, ifname, prop_ssid, ssid); + nmcli_property_string_set(tmpl, ifname, prop_key, password); + + sock_printf(tmpl->sock, "Set SSID and password"); +} + +void linux_functions_init(struct template_state *tmpl) +{ + tmpl->put(tmpl, "get_ssid", "", get_ssid); + tmpl->put(tmpl, "set_ssid", "", set_ssid); +} diff --git a/linux/functions.h b/linux/functions.h new file mode 100644 index 0000000..9ebbafd --- /dev/null +++ b/linux/functions.h @@ -0,0 +1,4 @@ +#include "../template.h" +#include "../includes.h" + +void linux_functions_init(struct template_state *tmpl); diff --git a/linux/mavlink_linux.c b/linux/mavlink_linux.c index 217ef82..c9fabb8 100644 --- a/linux/mavlink_linux.c +++ b/linux/mavlink_linux.c @@ -3,6 +3,7 @@ */ #include "../includes.h" +#include /* list of packet types received @@ -297,6 +298,44 @@ void mavlink_message_list_json(struct sock_buf *sock) sock_printf(sock, "]"); } +enum TIME_SOURCE { + TIME_SOURCE_NONE=0, + TIME_SOURCE_FC, +}; +static uint8_t time_source = 0; + +bool mavlink_should_handle_system_time() +{ + if (time_source >= TIME_SOURCE_FC) { + return false; + } + return true; +} + +void set_system_time_utc_usec(const struct timespec *ts) +{ + if (clock_settime(CLOCK_REALTIME, ts) == -1) { + fprintf(stderr, "Failed to set time: %s\n", strerror(errno)); + } +} + + +void mavlink_handle_system_time(const mavlink_system_time_t *m) +{ +#define FC_MIN_DATE 1494314686 + if (m->time_unix_usec/1000000 > FC_MIN_DATE) { + struct timespec ts = { + m->time_unix_usec/1000000, + (m->time_unix_usec%1000000) * 1000 + }; + fprintf(stderr, "Setting system time to %u.%u (from fc)\n", + (uint32_t)ts.tv_sec, (uint32_t)ts.tv_nsec); + set_system_time_utc_usec(&ts); + time_source = TIME_SOURCE_FC; + } +} + + /* * handle an (as yet undecoded) mavlink message */ @@ -321,7 +360,16 @@ bool mavlink_handle_msg(const mavlink_message_t *msg) command_ack_save(&m); break; } - + + case MAVLINK_MSG_ID_SYSTEM_TIME: { + if (mavlink_should_handle_system_time()) { + mavlink_system_time_t m; + mavlink_msg_system_time_decode(msg, &m); + mavlink_handle_system_time(&m); + } + break; + } + default: break; } diff --git a/linux/util_linux.c b/linux/util_linux.c index 1f3bc87..e22f381 100644 --- a/linux/util_linux.c +++ b/linux/util_linux.c @@ -20,32 +20,20 @@ const char *get_upload_message(void) return ""; } -static struct { - bool initialised; - struct timeval tv; -} system_time; - // get number of seconds since boot long long get_sys_seconds_boot() { - if (!system_time.initialised) { - gettimeofday(&system_time.tv,NULL); - } - struct timeval tv; - gettimeofday(&tv,NULL); - return tv.tv_sec - system_time.tv.tv_sec; + return get_time_boot_ms()/1000; } // get number of milliseconds since boot uint32_t get_time_boot_ms() { - if (!system_time.initialised) { - gettimeofday(&system_time.tv,NULL); - system_time.initialised = true; - } - struct timeval tv; - gettimeofday(&tv,NULL); - return (tv.tv_sec - system_time.tv.tv_sec) * 1000U + (tv.tv_usec - system_time.tv.tv_usec) / 1000U; + struct timespec elapsed_from_boot; + + clock_gettime(CLOCK_BOOTTIME, &elapsed_from_boot); + + return elapsed_from_boot.tv_sec*1000 + elapsed_from_boot.tv_nsec/1000000; } void mdelay(uint32_t ms) @@ -65,9 +53,16 @@ bool toggle_recording(void) return false; } -void reboot(void) +void __reboot(void) { - printf("reboot not implemented\n"); + #if __APPLE__ + printf("reboot OSX implemented, but disabled for now.\n"); + //reboot(0); + #elif __linux__ + system("/sbin/shutdown -t now -r"); + #else + printf("reboot not implemented\n"); + #endif } @@ -92,3 +87,10 @@ void *print_printf(void *ctx, const char *fmt, ...) va_end(ap); return ret; } + + + +unsigned xPortGetFreeHeapSize() +{ + return 0; +} diff --git a/linux/util_linux.h b/linux/util_linux.h index ed656e6..90ec2fd 100644 --- a/linux/util_linux.h +++ b/linux/util_linux.h @@ -20,8 +20,13 @@ uint32_t get_time_boot_ms(); void mdelay(uint32_t ms); bool toggle_recording(void); -void reboot(void); +void __reboot(void); // __ so we don't call the os version of this by mistake. char *print_vprintf(void *ctx, const char *fmt, va_list ap); void *print_printf(void *ctx, const char *fmt, ...); + + + +unsigned mavlink_fc_pkt_count(); +unsigned xPortGetFreeHeapSize(); diff --git a/mavlink_core.h b/mavlink_core.h index 2a629e6..051d7a7 100644 --- a/mavlink_core.h +++ b/mavlink_core.h @@ -6,6 +6,9 @@ #define MAVLINK_SEPARATE_HELPERS #define MAVLINK_NO_CONVERSION_HELPERS +// arm processor does not handle misaligned accesses +#define MAVLINK_ALIGNED_FIELDS 0 + #define MAVLINK_SEND_UART_BYTES(chan, buf, len) comm_send_buffer(chan, buf, len) // allow two mavlink ports diff --git a/mavlink_json.c b/mavlink_json.c index 295c98a..006e99d 100644 --- a/mavlink_json.c +++ b/mavlink_json.c @@ -95,8 +95,8 @@ bool mavlink_json_message(struct sock_buf *sock, const mavlink_message_t *msg, u sock_printf(sock, "\"%s\" : { ", m->name); for (i=0; inum_fields; i++) { print_field(sock, msg, &f[i]); - sock_printf(sock, ","); - } + sock_printf(sock, ","); + } sock_printf(sock, "\"_seq\" : %u, ", msg->seq); sock_printf(sock, "\"_sysid\" : %u, ", msg->sysid); sock_printf(sock, "\"_compid\" : %u, ", msg->compid); @@ -159,46 +159,66 @@ bool mavlink_message_send_args(int argc, char **argv) } break; - case MAVLINK_TYPE_UINT8_T: - _mav_put_uint8_t(buf, f->wire_offset, strtoul(arg, NULL, 0)); + case MAVLINK_TYPE_UINT8_T: { + uint8_t b = simple_strtoul(arg, NULL, 0); + _mav_put_uint8_t(buf, f->wire_offset, b); break; + } - case MAVLINK_TYPE_UINT16_T: - _mav_put_uint16_t(buf, f->wire_offset, strtoul(arg, NULL, 0)); + case MAVLINK_TYPE_UINT16_T: { + uint16_t b = simple_strtoul(arg, NULL, 0); + _mav_put_uint16_t(buf, f->wire_offset, b); break; + } - case MAVLINK_TYPE_UINT32_T: - _mav_put_uint32_t(buf, f->wire_offset, strtoul(arg, NULL, 0)); + case MAVLINK_TYPE_UINT32_T: { + uint32_t b = simple_strtoul(arg, NULL, 0); + _mav_put_uint32_t(buf, f->wire_offset, b); break; + } - case MAVLINK_TYPE_UINT64_T: - _mav_put_uint64_t(buf, f->wire_offset, strtoull(arg, NULL, 0)); + case MAVLINK_TYPE_UINT64_T: { + uint64_t b = simple_strtoul(arg, NULL, 0); + _mav_put_uint64_t(buf, f->wire_offset, b); break; + } - case MAVLINK_TYPE_INT8_T: - _mav_put_int8_t(buf, f->wire_offset, strtol(arg, NULL, 0)); + case MAVLINK_TYPE_INT8_T: { + int8_t b = simple_strtol(arg, NULL, 0); + _mav_put_int8_t(buf, f->wire_offset, b); break; + } - case MAVLINK_TYPE_INT16_T: - _mav_put_int16_t(buf, f->wire_offset, strtol(arg, NULL, 0)); + case MAVLINK_TYPE_INT16_T: { + int16_t b = strtol(arg, NULL, 0); + _mav_put_int16_t(buf, f->wire_offset, b); break; + } - case MAVLINK_TYPE_INT32_T: - _mav_put_int32_t(buf, f->wire_offset, strtol(arg, NULL, 0)); + case MAVLINK_TYPE_INT32_T: { + int32_t b = strtol(arg, NULL, 0); + _mav_put_int32_t(buf, f->wire_offset, b); break; + } - case MAVLINK_TYPE_INT64_T: - _mav_put_int64_t(buf, f->wire_offset, strtoll(arg, NULL, 0)); + case MAVLINK_TYPE_INT64_T: { + int64_t b = strtol(arg, NULL, 0); + _mav_put_int64_t(buf, f->wire_offset, b); break; + } - case MAVLINK_TYPE_FLOAT: - _mav_put_float(buf, f->wire_offset, atof(arg)); + case MAVLINK_TYPE_FLOAT: { + float b = atof(arg); + _mav_put_float(buf, f->wire_offset, b); break; + } - case MAVLINK_TYPE_DOUBLE: - _mav_put_double(buf, f->wire_offset, atof(arg)); + case MAVLINK_TYPE_DOUBLE: { + double b = atof(arg); + _mav_put_double(buf, f->wire_offset, b); break; } + } } uint8_t msglen = 0; @@ -259,5 +279,3 @@ bool mavlink_message_send_args(int argc, char **argv) return true; } - - diff --git a/posix/config_variables.c b/posix/config_variables.c new file mode 100644 index 0000000..70951d0 --- /dev/null +++ b/posix/config_variables.c @@ -0,0 +1,262 @@ +#include "config_variables.h" + +#include +#include +#include +#include +#include +#include +#include + +char *config; +off_t config_size; +uint32_t config_file_modtime = 0; +const char *config_filename = "config.txt"; + +bool lock_initted; +static pthread_mutex_t lock; + +bool lock_config() +{ + if (!lock_initted) { + pthread_mutex_init(&lock, NULL); + lock_initted = 1; + } + return pthread_mutex_lock(&lock); +} + +bool unlock_config() +{ + return pthread_mutex_unlock(&lock); +} + +bool read_config_file() +{ + int fd = open(config_filename, O_RDONLY); + if (fd == -1) { + goto OUT_BAD; + } + struct stat _stat; + if (fstat(fd, &_stat) == -1) { + goto OUT_BAD_FD; + } + const uint32_t modtime = _stat.st_atime; + if (modtime == config_file_modtime) { + close(fd); + return true; + } + config_size = _stat.st_size; + char *new_config = realloc(config, config_size+1); + if (new_config == NULL) { + goto OUT_BAD_FD; + } + config = new_config; + memset(config, '\0', config_size+1); + off_t total_read = 0; + uint8_t max_loop_count = 10; + while (total_read != config_size && max_loop_count--) { + const off_t this_read = read(fd, &config[total_read], config_size-total_read); + if (this_read == -1) { + goto OUT_BAD_FD; + } + total_read += this_read; + } + if (total_read != config_size) { + goto OUT_BAD_FD; + } + config_file_modtime = modtime; + return true; +OUT_BAD_FD: + close(fd); +OUT_BAD: + free(config); + config_size = 0; + return false; +} + +bool config_string_get(const char *category, const char *name, char *ret, uint8_t retlen) +{ + char fullname[50]; + snprintf(fullname, 50, "%s.%s=", category, name); + lock_config(); + if (!read_config_file()) { + goto OUT_DO_RELEASE; + } + const char *namepos = strstr(config, fullname); + if (namepos == NULL) { + goto OUT_DO_RELEASE; + } + const char *terminator = strstr(namepos, "\n"); + if (terminator == NULL) { + goto OUT_DO_RELEASE; + } + const int16_t len = terminator - namepos - strlen(fullname); + const char *value = namepos+strlen(fullname); + memcpy(ret, value, (len <= retlen) ? len : retlen); +OUT_DO_RELEASE: + unlock_config(); + return true; +} + +bool config_integer_get(const char *category, const char *name, int *ret) +{ + char value[50] = {}; + if (!config_string_get(category, name, value, 50)) { + return false; + } + *ret = atoi(value); + fprintf(stderr, "value: (%s) (%d)\n", value, *ret); + return true; +} + +bool config_string_set(const char *category, const char *name, char *value) +{ + fprintf(stderr, "old config string: (%s) len=%lu\n", config, config_size); + char fullname[50]; + snprintf(fullname, 50, "%s.%s=", category, name); + lock_config(); + if (!read_config_file()) { + return false; + } + const char *namepos = strstr(config, fullname); + if (namepos == NULL) { + // append + const off_t new_config_size = config_size + strlen(fullname) + strlen(value) + 1; + char *new_config = realloc(config, new_config_size+1); + if (new_config == NULL) { + goto OUT_DO_RELEASE; + } + config = new_config; + config[new_config_size] = '\0'; + strcpy(&config[config_size], fullname); + strcpy(&config[config_size+strlen(fullname)], value); + config[config_size+strlen(fullname)+strlen(value)] = '\n'; + config_size = new_config_size; + } else { + // found existing entry + const char *terminator = strstr(namepos, "\n"); + if (terminator == NULL) { + goto OUT_DO_RELEASE; + } + const int name_offset = namepos-config; + const int value_offset = name_offset + strlen(fullname); + const off_t old_value_len = terminator - namepos - strlen(fullname); + const int delta = old_value_len - strlen(value); + const off_t new_config_size = config_size - old_value_len + strlen(value); + if (new_config_size > config_size) { + // make buffer bigger, move stuff to end of buffer using memmove + char *new_config = realloc(config, new_config_size+1); + if (new_config == NULL) { + goto OUT_DO_RELEASE; + } + config = new_config; + config[new_config_size] = '\0'; + memmove(&config[value_offset+strlen(value)], + &config[value_offset+old_value_len], + config_size-value_offset); + } else if (new_config_size < config_size) { + // move stuff to beginning of buffer using memmove, make + // buffer smaller + memmove(&config[value_offset], + &config[value_offset+delta], + config_size-value_offset-delta); + char *new_config = realloc(config, new_config_size+1); + if (new_config == NULL) { + goto OUT_DO_RELEASE; + } + config = new_config; + config[new_config_size] = '\0'; + } + memcpy(&config[name_offset+strlen(fullname)], value, strlen(value)); + config_size = new_config_size; + } + fprintf(stderr, "new config string: (%s) len=%lu\n", config, config_size); + unlock_config(); + return true; +OUT_DO_RELEASE: + unlock_config(); + return false; +} + +bool config_integer_set(const char *category, const char *name, int value) +{ + char value_string[50] = {}; + snprintf(value_string, 50, "%d", value); + return config_string_set(category, name, value_string); +} + + + +void test_config() +{ + int bob; + if (!config_integer_get("FOO", "BAR", &bob)) { + fprintf(stderr, "Failed to get FOO.BAR\n"); + abort(); + } + if (bob != 37) { + abort(); + } + fprintf(stderr, "Got %d\n", bob); + + if (!config_integer_set("FOO", "BAR", 5)) { + fprintf(stderr, "Failed to set FOO.BAR\n"); + abort(); + } + if (!config_integer_get("FOO", "BAR", &bob)) { + fprintf(stderr, "Failed to get FOO.BAR\n"); + abort(); + } + if (bob != 5) { + fprintf(stderr, "bob=%d\n", bob); + abort(); + } + + if (!config_integer_set("FOO", "BAR", 713)) { + fprintf(stderr, "Failed to set FOO.BAR\n"); + abort(); + } + if (!config_integer_get("FOO", "BAR", &bob)) { + fprintf(stderr, "Failed to get FOO.BAR\n"); + abort(); + } + if (bob != 713) { + fprintf(stderr, "bob=%d\n", bob); + abort(); + } + + if (!config_integer_set("FOO", "BAR", 123)) { + fprintf(stderr, "Failed to set FOO.BAR\n"); + abort(); + } + if (!config_integer_get("FOO", "BAR", &bob)) { + fprintf(stderr, "Failed to get FOO.BAR\n"); + abort(); + } + if (bob != 123) { + fprintf(stderr, "bob=%d\n", bob); + abort(); + } + + if (!config_integer_set("FOO", "BAZ", 54)) { + fprintf(stderr, "Failed to set FOO.BAR\n"); + abort(); + } + if (!config_integer_get("FOO", "BAZ", &bob)) { + fprintf(stderr, "Failed to get FOO.BAZ\n"); + abort(); + } + if (bob != 54) { + fprintf(stderr, "bob=%d\n", bob); + abort(); + } + if (!config_integer_get("FOO", "BAR", &bob)) { + fprintf(stderr, "Failed to get FOO.BAR\n"); + abort(); + } + if (bob != 123) { + fprintf(stderr, "bob=%d\n", bob); + abort(); + } +} + diff --git a/posix/config_variables.h b/posix/config_variables.h new file mode 100644 index 0000000..6e7a8c2 --- /dev/null +++ b/posix/config_variables.h @@ -0,0 +1,8 @@ +#pragma once + +#include +#include +#include + +bool config_integer_get(const char *category, const char *name, int * ret); +bool config_string_get(const char *category, const char *name, char *ret, uint8_t retlen); diff --git a/posix/functions.c b/posix/functions.c new file mode 100644 index 0000000..bb017b7 --- /dev/null +++ b/posix/functions.c @@ -0,0 +1,163 @@ +#include "../includes.h" +#include "../template.h" +#include "functions.h" +#include "../functions.h" + +#include +#include +#include +#include +#include +#include +#include +#include + + +static void sock_send_diskinfo(struct sock_buf *sock, const char *label, unsigned serial, unsigned total_clusters, unsigned free_clusters, unsigned cluster_size) +{ + sock_printf(sock, + "{" + "\"label\" : \"%s\", " + "\"serial\" : %u, " + "\"total_clusters\" : %u, " + "\"free_clusters\" : %u, " + "\"cluster_size\" : %u" + "}", + label, serial, total_clusters, free_clusters, cluster_size*512); +} + +static void disk_info(struct template_state *tmpl, const char *name, const char *value, int argc, char **argv) +{ + unsigned long free_clusters = 0, total_clusters = 0, cluster_size = 0; + const char label[] = "/"; + + /* Get volume information and free clusters of root filesystem */ + struct statvfs buf; + if (statvfs("/", &buf) != -1) { + total_clusters = buf.f_blocks; + free_clusters = buf.f_bfree; + cluster_size = buf.f_bsize / 512; + } + + const unsigned serial = 0; + + sock_send_diskinfo(tmpl->sock, label, serial, total_clusters, free_clusters, cluster_size); +} + + +static void sock_send_dirent(struct sock_buf *sock, bool first, int type, const char *name, unsigned year, unsigned month, unsigned day, unsigned hour, unsigned minute, unsigned second, unsigned size) +{ + if (!first) { + sock_printf(sock, "%s", ",\n"); + } + sock_printf(sock, "{" + "\"type\" : %u, " + "\"name\" : \"%s\", " + "\"date\" : \"%04u-%02u-%02u %02u:%02u:%02u\", " + "\"size\" : %u " + "}", + type, name, year, month, day, hour, minute, second, size); +} + +static void file_listdir(struct template_state *tmpl, const char *name, const char *value, int argc, char **argv) +{ + if (argc < 1) { + return; + } + const char *dirpath = argv[0]; + + DIR *dh = opendir(dirpath); + if (dh == NULL) { + console_printf("Failed to open directory %s\n", dirpath); + return; + } + + sock_printf(tmpl->sock, "[ "); + + bool first = true; + struct dirent *result; + while ((result = readdir(dh)) != NULL) { + if (strcmp(result->d_name, ".") == 0) { + continue; + } + + struct stat buf; + char filepath[PATH_MAX] = {}; + snprintf(filepath, sizeof(filepath), "%s/%s", dirpath, result->d_name); + if (stat(filepath, &buf) == -1) { + continue; + } + + struct tm t; + if (localtime_r(&buf.st_mtim.tv_sec, &t) == NULL) { + continue; + } + + sock_send_dirent(tmpl->sock, + first, + (result->d_type==DT_DIR) ? 1 :0, + result->d_name, + t.tm_year+1900, + t.tm_mon+1, + t.tm_mday, + t.tm_hour, + t.tm_min, + t.tm_sec, + buf.st_size); + first = false; + } + sock_printf(tmpl->sock, "]"); + closedir(dh); +} + +void download_filesystem(struct cgi_state *cgi, const char *fs_path) +{ + const char *path = fs_path+2; + + struct stat stats; + if (stat(path, &stats) == -1) { + cgi->http_error(cgi, "404 Bad File", "", "file not found"); + return; + } + + cgi->content_length = stats.st_size; + const int fd = open(path, O_RDONLY); + if(fd == -1) { + cgi->http_error(cgi, "500 Open failed", "", strerror(errno)); + return; + } + cgi->http_header(cgi, fs_path); + char buf[2048]; + do { + const ssize_t read_count = read(fd, buf, sizeof(buf)); + if (read_count == -1) { + console_printf("Read failure: %s", strerror(errno)); + return; + } + if (read_count == 0) { + // EOF + break; + } + ssize_t to_write = read_count; + while (to_write > 0) { + ssize_t write_count = sock_write(cgi->sock, buf, to_write); + if (write_count == 0) { + console_printf("EOF on write?!"); + return; + } + if (write_count == -1) { + console_printf("Error on write: %s", strerror(errno)); + return; + } + to_write -= write_count; + } + } while (1); + + close(fd); +} + +void posix_functions_init(struct template_state *tmpl) +{ + tmpl->put(tmpl, "file_listdir", "", file_listdir); + tmpl->put(tmpl, "disk_info", "", disk_info); +} diff --git a/posix/functions.h b/posix/functions.h new file mode 100644 index 0000000..38b4240 --- /dev/null +++ b/posix/functions.h @@ -0,0 +1,9 @@ +/* + provide server side functions in C + */ + +#include "../template.h" +#include "../includes.h" + +void posix_functions_init(struct template_state *tmpl); +void download_filesystem(struct cgi_state *cgi, const char *fs_path); 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 48e67a8..54a2568 100644 --- a/web_server.c +++ b/web_server.c @@ -8,13 +8,45 @@ #include "web_server.h" #include "includes.h" #include "web_files.h" - +#ifdef SYSTEM_FREERTOS +#include +#else +#include #include +#include +#include +#include +#endif +#ifndef SYSTEM_FREERTOS static pthread_mutex_t lock; +static int serial_port_fd = -1; +static int fc_udp_in_fd = -1; +static int udp_out_fd = -1; + +struct sockaddr_in fc_addr; +socklen_t fc_addrlen; + +struct sockaddr_in udp_out_addr; +socklen_t udp_out_addrlen; + +unsigned baudrate = 57600; + +struct { + uint64_t packet_count_from_fc; +} stats; + +#endif + static int num_sockets_open; static int debug_level; -static int mavlink_fd; + +// public web-site that will be allowed. Can be edited with NVRAM editor +static const char *public_origin = "fly.example.com"; + +#ifndef bool +#define bool int +#endif void web_server_set_debug(int level) { @@ -32,6 +64,15 @@ void web_debug(int level, const char *fmt, ...) va_end(ap); } +#ifdef SYSTEM_FREERTOS +static void lock_state(void) +{ +} + +static void unlock_state(void) +{ +} +#else static void lock_state(void) { pthread_mutex_lock(&lock); @@ -41,6 +82,7 @@ static void unlock_state(void) { pthread_mutex_unlock(&lock); } +#endif /* destroy socket buffer, writing any pending data @@ -69,8 +111,8 @@ static int sock_buf_destroy(struct sock_buf *sock) } lock_state(); + web_debug(3,"closing fd %d num_sockets_open=%d\n", sock->fd, num_sockets_open); num_sockets_open--; - web_debug(4,"closing fd %d num_sockets_open=%d\n", sock->fd, num_sockets_open); unlock_state(); close(sock->fd); @@ -118,12 +160,16 @@ void sock_printf(struct sock_buf *sock, const char *fmt, ...) va_list ap; va_start(ap, fmt); char *buf2 = print_vprintf(sock, fmt, ap); +#ifdef SYSTEM_FREERTOS + sock_write(sock, buf2, talloc_get_size(buf2)); +#else size_t size = talloc_get_size(buf2); if (buf2 && size > 0 && buf2[size-1] == 0) { // cope with differences in print_vprintf between platforms size--; } sock_write(sock, buf2, size); +#endif talloc_free(buf2); va_end(ap); } @@ -135,16 +181,28 @@ void sock_printf(struct sock_buf *sock, const char *fmt, ...) void connection_destroy(struct connection_state *c) { talloc_free(c); +#ifdef SYSTEM_FREERTOS + vTaskDelete(NULL); +#else pthread_exit(0); +#endif } +#ifndef SYSTEM_FREERTOS /* write some data to the flight controller */ void mavlink_fc_write(const uint8_t *buf, size_t size) { - write(mavlink_fd, buf, size); + if (serial_port_fd != -1) { + write(serial_port_fd, buf, size); + } + if (fc_udp_in_fd != -1) { + if (fc_addrlen != 0) { + sendto(fc_udp_in_fd, buf, size, 0, (struct sockaddr*)&fc_addr, fc_addrlen); + } + } } /* @@ -152,7 +210,14 @@ void mavlink_fc_write(const uint8_t *buf, size_t size) */ void mavlink_fc_send(mavlink_message_t *msg) { - _mavlink_resend_uart(MAVLINK_COMM_FC, msg); + if (serial_port_fd != -1) { + _mavlink_resend_uart(MAVLINK_COMM_FC, msg); + } + if (fc_udp_in_fd != -1) { + uint8_t buf[600]; + uint16_t len = mavlink_msg_to_send_buffer(buf, msg); + mavlink_fc_write(buf, len); + } } /* @@ -173,6 +238,22 @@ static void mavlink_broadcast(int fd, mavlink_message_t *msg) sendto(fd, buf, len, 0, (struct sockaddr*)&addr, sizeof(addr)); } } +#endif + +/* + send a mavlink msg over WiFi to a single target + */ +static void mavlink_send_udp_out(mavlink_message_t *msg) +{ + if (udp_out_fd == -1) { + return; + } + uint8_t buf[300]; + uint16_t len = mavlink_msg_to_send_buffer(buf, msg); + if (len > 0) { + sendto(udp_out_fd, buf, len, 0, (struct sockaddr*)&udp_out_addr, sizeof(udp_out_addr)); + } +} /* process input on a connection @@ -190,10 +271,128 @@ static void connection_process(struct connection_state *c) connection_destroy(c); } +/* + check origin header to prevent attacks by javascript in other web pages + */ +static bool check_origin(const char *origin) +{ + 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 + // could be a different local IP + char local_ip[16]; + get_local_ip(local_ip, sizeof(local_ip)); + if (strncmp(origin, "http://", 7) == 0 && + strcmp(origin+7, local_ip) == 0) { + return true; + } +#else + // TODO: check all IPs on all interfaces? +#endif + + // also allow file:// URLs which produce a 'null' origin + if (strcmp(origin, "null") == 0) { + return true; + } + char *allowed_origin; +#ifdef SYSTEM_FREERTOS + unsigned origin_length = 0; + if (snx_nvram_get_data_len("SkyViper", "AllowedOrigin", &origin_length) != NVRAM_SUCCESS) { + return false; + } + allowed_origin = talloc_zero_size(NULL, origin_length); + if (allowed_origin == NULL) { + return false; + } + if (snx_nvram_string_get("SkyViper", "AllowedOrigin", allowed_origin) != NVRAM_SUCCESS) { + talloc_free(allowed_origin); + return false; + } +#else + allowed_origin = talloc_zero_size(NULL, 1); +#endif + // check for wildcard allowed origin + if (strcmp(allowed_origin, "*") == 0) { + talloc_free(allowed_origin); + return true; + } + + // allow for http:// or https:// + if (strncmp(origin, "http://", 7) == 0) { + origin += 7; + } else if (strncmp(origin, "https://", 8) == 0) { + origin += 8; + } else { + console_printf("Denied origin protocol: [%s]\n", origin); + talloc_free(allowed_origin); + return false; + } + + if (strcmp(allowed_origin, origin) != 0) { + console_printf("Denied origin: [%s] allowed: [%s]\n", origin, allowed_origin); + talloc_free(allowed_origin); + return false; + } + talloc_free(allowed_origin); + return true; +} + +/* + setup AllowedOrigin if not set already + */ +static void setup_origin(const char *origin) +{ +#ifdef SYSTEM_FREERTOS + unsigned origin_length = 0; + if (snx_nvram_get_data_len("SkyViper", "AllowedOrigin", &origin_length) != NVRAM_SUCCESS || + origin_length == 0) { + snx_nvram_string_set("SkyViper", "AllowedOrigin", __DECONST(char *,origin)); + } +#endif +} + +void sig_pipe_handler(int signum) +{ + web_debug(3, "Caught signal SIGPIPE %d\n",signum); +} /* task for web_server */ +#ifdef SYSTEM_FREERTOS +static void web_server_connection_process(void *pvParameters) +{ + struct connection_state *c = pvParameters; + c->cgi = cgi_init(c, c->sock); + if (!c->cgi) { + connection_destroy(c); + return; + } + + c->cgi->check_origin = check_origin; + + connection_process(c); +} +#else static void *web_server_connection_process(void *arg) { int fd = (intptr_t)arg; @@ -217,33 +416,182 @@ static void *web_server_connection_process(void *arg) return NULL; } + c->cgi->check_origin = check_origin; + connection_process(c); return NULL; } +#endif + +#ifdef SYSTEM_FREERTOS +/* + task for web_server +*/ +void web_server_task_process(void *pvParameters) +{ + int listen_sock; + + struct sockaddr_in addr; + + // setup default allowed origin + setup_origin(public_origin); + + if ((listen_sock = socket(AF_INET, SOCK_STREAM, IPPROTO_TCP)) < 0) { + goto end; + } + + memset(&addr, 0x0, sizeof(addr)); + + addr.sin_family = AF_INET; + addr.sin_addr.s_addr = htonl(INADDR_ANY); + addr.sin_port = htons(WEB_SERVER_PORT); + + if (bind(listen_sock, (struct sockaddr*)&addr, sizeof(addr)) < 0) { + goto end; + } + + if (listen(listen_sock, 20) < 0) { + goto end; + } + + while (1) + { + fd_set fds; + struct timeval tv; + int numfd = listen_sock+1; + + FD_ZERO(&fds); + FD_SET(listen_sock, &fds); + + tv.tv_sec = 1; + tv.tv_usec = 0; + + int res = select(numfd, &fds, NULL, NULL, &tv); + if (res <= 0) { + continue; + } + + if (FD_ISSET(listen_sock, &fds)) { + // new connection + struct sockaddr_in addr; + int len = sizeof(struct sockaddr_in); + int fd = accept(listen_sock, (struct sockaddr *)&addr, (socklen_t *)&len); + if (fd != -1) { + struct connection_state *c = talloc_zero(NULL, struct connection_state); + if (c == NULL) { + close(fd); + continue; + } + c->sock = talloc_zero(c, struct sock_buf); + if (!c->sock) { + talloc_free(c); + close(fd); + continue; + } + c->sock->fd = fd; + num_sockets_open++; + talloc_set_destructor(c->sock, sock_buf_destroy); + xTaskCreate(web_server_connection_process, "http_connection", STACK_SIZE_4K, c, 10, &c->task); + } + } + } + +end: + vTaskDelete(NULL); +} +#else +void do_http_accept(const int sockfd) +{ + int fd = accept(sockfd, NULL,0); + if (fd == -1) { + console_printf("accept failed: %s\n", strerror(errno)); + goto BAD_ACCEPT; + }; + + // use a thread per connection. This allows for sending MAVLink messages + // via mavlink_fc_send() from connections + pthread_t thread_id; + pthread_attr_t thread_attr; + + int perrno; + if ((perrno = pthread_attr_init(&thread_attr)) != 0) { + console_printf("pthread_attr_init failed: %s\n", strerror(perrno)); + goto BAD_PTHREAD_INIT; + } + if ((perrno = pthread_attr_setdetachstate(&thread_attr, PTHREAD_CREATE_DETACHED)) != 0) { + console_printf("pthread_attr_setdetachstate failed: %s\n", strerror(perrno)); + goto BAD_PTHREAD_SETDETEACHSTATE; + } + if ((perrno = pthread_create(&thread_id, &thread_attr, web_server_connection_process, (void*)(intptr_t)fd)) != 0) { + console_printf("pthread_create failed: %s\n", strerror(perrno)); + goto BAD_PTHREAD_CREATE; + } + pthread_attr_destroy(&thread_attr); + return; + +BAD_PTHREAD_CREATE: +BAD_PTHREAD_SETDETEACHSTATE: + pthread_attr_destroy(&thread_attr); +BAD_PTHREAD_INIT: + close(fd); +BAD_ACCEPT: + return; +} + +int uart2_get_baudrate() +{ + return baudrate; +} + +unsigned mavlink_fc_pkt_count() +{ + return stats.packet_count_from_fc; +} /* main select loop */ -static void select_loop(int tcp_socket, int udp_socket, int mavlink_fd) +static void select_loop(int http_socket_fd, int udp_socket_fd) { while (1) { fd_set fds; struct timeval tv; - int numfd = tcp_socket+1; + int numfd = 0; FD_ZERO(&fds); - FD_SET(tcp_socket, &fds); - FD_SET(udp_socket, &fds); - FD_SET(mavlink_fd, &fds); + if (http_socket_fd != -1) { + FD_SET(http_socket_fd, &fds); + if (http_socket_fd >= numfd) { + numfd = http_socket_fd+1; + } + } + if (udp_socket_fd != -1) { + FD_SET(udp_socket_fd, &fds); + if (udp_socket_fd >= numfd) { + numfd = udp_socket_fd+1; + } + } + if (serial_port_fd != -1) { + FD_SET(serial_port_fd, &fds); + if (serial_port_fd >= numfd) { + numfd = serial_port_fd+1; + } + } - if (udp_socket >= numfd) { - numfd = udp_socket+1; + if (fc_udp_in_fd != -1) { + FD_SET(fc_udp_in_fd, &fds); + if (fc_udp_in_fd >= numfd) { + numfd = fc_udp_in_fd+1; + } } - if (mavlink_fd >= numfd) { - numfd = mavlink_fd+1; + + if (udp_out_fd != -1) { + FD_SET(udp_out_fd, &fds); + if (udp_out_fd >= numfd) { + numfd = udp_out_fd+1; + } } - - + tv.tv_sec = 1; tv.tv_usec = 0; @@ -253,48 +601,86 @@ static void select_loop(int tcp_socket, int udp_socket, int mavlink_fd) } // check for new incoming tcp connection - if (FD_ISSET(tcp_socket, &fds)) { - int fd = accept(tcp_socket, NULL,0); - if (fd == -1) continue; - - // use a thread per connection. This allows for sending MAVLink messages - // via mavlink_fc_send() from connections - pthread_t thread_id; - pthread_attr_t thread_attr; - - pthread_attr_init(&thread_attr); - pthread_attr_setdetachstate(&thread_attr, 0); - pthread_create(&thread_id, &thread_attr, web_server_connection_process, (void*)(intptr_t)fd); - pthread_attr_destroy(&thread_attr); + if (http_socket_fd != -1 && + FD_ISSET(http_socket_fd, &fds)) { + do_http_accept(http_socket_fd); } - // check for incoming UDP packet - if (FD_ISSET(udp_socket, &fds)) { + // check for incoming UDP packet (broadcast) + if (udp_socket_fd != -1 && + FD_ISSET(udp_socket_fd, &fds)) { // we have data pending uint8_t buf[300]; - ssize_t nread = read(udp_socket, buf, sizeof(buf)); + ssize_t nread = read(udp_socket_fd, buf, sizeof(buf)); if (nread > 0) { // send the data straight to the flight controller - write(mavlink_fd, buf, nread); + mavlink_fc_write(buf, nread); + } + } + + // check for incoming UDP packet from udp-out connection: + if (udp_out_fd != -1 && + FD_ISSET(udp_out_fd, &fds)) { + // we have data pending + uint8_t buf[1024]; + fc_addrlen = sizeof(fc_addr); + ssize_t nread = recvfrom(udp_out_fd, buf, sizeof(buf), MSG_DONTWAIT, (struct sockaddr*)&udp_out_addr, &udp_out_addrlen); + if (nread <= 0) { + /* printf("Read error from udp out connection\n"); */ + } else { + // send to flight controller + mavlink_fc_write(buf, nread); + } + } + + if (fc_udp_in_fd != -1 && + FD_ISSET(fc_udp_in_fd, &fds)) { + // we have data pending + uint8_t buf[3000]; + fc_addrlen = sizeof(fc_addr); + ssize_t nread = recvfrom(fc_udp_in_fd, buf, sizeof(buf), MSG_DONTWAIT, (struct sockaddr*)&fc_addr, &fc_addrlen); + if (nread > 0) { + mavlink_message_t msg; + mavlink_status_t status; + for (uint16_t i=0; i +#include +#include +#include "../dev_console.h" +#include "../mavlink_wifi.h" +#else #include #include #include @@ -27,6 +34,7 @@ #include #include #include +#endif struct connection_state; @@ -49,21 +57,36 @@ struct sock_buf { state of one connection */ struct connection_state { +#ifdef SYSTEM_FREERTOS + xTaskHandle task; +#endif struct sock_buf *sock; struct cgi_state *cgi; }; -#define FMT_PRINTF(a,b) __attribute__((format(printf, a, b))) - void web_server_task_process(void *pvParameters); void connection_destroy(struct connection_state *c); +#ifdef SYSTEM_FREERTOS +int32_t sock_write(struct sock_buf *sock, const char *s, size_t size); +#else ssize_t sock_write(struct sock_buf *sock, const char *s, size_t size); +#endif +#ifndef SYSTEM_FREERTOS +#define FMT_PRINTF(a,b) __attribute__((format(printf, a, b))) +#endif void sock_printf(struct sock_buf *sock, const char *fmt, ...) FMT_PRINTF(2,3); void web_server_set_debug(int debug); void web_debug(int level, const char *fmt, ...); void mavlink_fc_write(const uint8_t *buf, size_t len); +#ifdef SYSTEM_FREERTOS +void mavlink_rc_write(const uint8_t *buf, uint32_t len); +#endif +#ifndef SYSTEM_FREERTOS #define console_printf printf #define console_vprintf vprintf +#define simple_strtoul strtoul +#define simple_strtol strtol +#endif
VariableValue
Status
Channels
Chan1
Chan2