/* void draw_text_f (ESContext *esContext, float x1, float y1, float w, float h, char *file, char *text) { */ int tclcmd_draw_text_f (ClientData cdata, Tcl_Interp *interp, int objc, Tcl_Obj *const objv[]) { int len = 0; if (objc != 7) { Tcl_WrongNumArgs (interp, 1, objv, "{ESContext *esContext} { float x1} { float y1} { float w} { float h} { char *file} { char *text}"); return TCL_ERROR; } double arg_x1; if (Tcl_GetDoubleFromObj(interp, objv[1], (double *)&arg_x1) != TCL_OK) { return TCL_ERROR; } double arg_y1; if (Tcl_GetDoubleFromObj(interp, objv[2], (double *)&arg_y1) != TCL_OK) { return TCL_ERROR; } double arg_w; if (Tcl_GetDoubleFromObj(interp, objv[3], (double *)&arg_w) != TCL_OK) { return TCL_ERROR; } double arg_h; if (Tcl_GetDoubleFromObj(interp, objv[4], (double *)&arg_h) != TCL_OK) { return TCL_ERROR; } char arg_file[1024]; strncpy(arg_file, Tcl_GetStringFromObj(objv[5], &len), 1024); char arg_text[1024]; strncpy(arg_text, Tcl_GetStringFromObj(objv[6], &len), 1024); draw_text_f(GlobalesContext, (float)arg_x1, (float)arg_y1, (float)arg_w, (float)arg_h, arg_file, arg_text); return TCL_OK; }
void screen_system(ESContext *esContext) { #ifndef SDLGL ESMatrix modelview; UserData *userData = esContext->userData; #endif #ifndef WINDOWS FILE *cmd = NULL; #endif char buffer[1025]; static char ip[30]; static char bcast[30]; static char mask[30]; static char hostname[30]; static char dnsserver[30]; static char gateway[30]; uint32_t now_time = time(0); static uint32_t last_time = 0; #ifndef SDLGL esMatrixLoadIdentity(&modelview); esMatrixMultiply(&userData->mvpMatrix, &modelview, &userData->perspective); #endif draw_title(esContext, "System"); if (last_time != now_time) { strcpy(ip, "---.---.---.---"); strcpy(bcast, "---.---.---.---"); strcpy(mask, "---.---.---.---"); strcpy(dnsserver, "---.---.---.---"); strcpy(gateway, "---.---.---.---"); #ifndef WINDOWS #ifndef ANDROID #ifdef OSX if ((cmd = popen("LANG=C ifconfig en0 | grep \"inet \" | sed \"s|[a-zA-Z:]||g\"", "r")) != NULL) { while (!feof(cmd)) { if (fgets(buffer, 1024, cmd) != NULL) { sscanf(buffer, "%s %s %s", (char *)&ip, (char *)&bcast, (char *)&mask); // SDL_Log("## %s, %s, %s ##\n", ip, bcast, mask); } } pclose(cmd); } #else if ((cmd = popen("LANG=C ifconfig eth0 | grep \"inet addr:\" | sed \"s|[a-zA-Z:]||g\"", "r")) != NULL) { while (!feof(cmd)) { if (fgets(buffer, 1024, cmd) != NULL) { sscanf(buffer, "%s %s %s", (char *)&ip, (char *)&bcast, (char *)&mask); // SDL_Log("## %s, %s, %s ##\n", ip, bcast, mask); } } pclose(cmd); } if ((cmd = popen("grep \"^nameserver \" /etc/resolv.conf | cut -d\" \" -f2", "r")) != NULL) { while (!feof(cmd)) { if (fgets(dnsserver, 1024, cmd) != NULL) { } } } pclose(cmd); if ((cmd = popen("route -n | grep \" 0.0.0.0.*255.255.255.0 \" | cut -d\" \" -f1", "r")) != NULL) { while (!feof(cmd)) { if (fgets(gateway, 1024, cmd) != NULL) { } } } pclose(cmd); #endif if ((cmd = popen("hostname", "r")) != NULL) { while (!feof(cmd)) { if (fgets(hostname, 1024, cmd) != NULL) { } } } pclose(cmd); #endif #endif last_time = now_time; } sprintf(buffer, "Name : %s", hostname); draw_text_f(esContext, -0.5, -0.8 + 1 * 0.1, 0.06, 0.06, FONT_GREEN, buffer); sprintf(buffer, "IP : %s", ip); draw_text_f(esContext, -0.5, -0.8 + 3 * 0.1, 0.06, 0.06, FONT_GREEN, buffer); sprintf(buffer, "BCAST : %s", bcast); draw_text_f(esContext, -0.5, -0.8 + 4 * 0.1, 0.06, 0.06, FONT_GREEN, buffer); sprintf(buffer, "MASK : %s", mask); draw_text_f(esContext, -0.5, -0.8 + 5 * 0.1, 0.06, 0.06, FONT_GREEN, buffer); sprintf(buffer, "DNS : %s", dnsserver); draw_text_f(esContext, -0.5, -0.8 + 6 * 0.1, 0.06, 0.06, FONT_GREEN, buffer); sprintf(buffer, "GATE : %s", gateway); draw_text_f(esContext, -0.5, -0.8 + 7 * 0.1, 0.06, 0.06, FONT_GREEN, buffer); draw_text_button(esContext, "system_dhclient", VIEW_MODE_SYSTEM, "<GET IP OVER DHCP>", FONT_GREEN, 0.0, -0.8 + 9 * 0.1, 0.002, 0.06, ALIGN_CENTER, ALIGN_TOP, system_dhclient, 0.0); // draw_text_button(esContext, "system_gcs", VIEW_MODE_SYSTEM, "<UPDATE GCS>", FONT_GREEN, 0.0, -0.8 + 10 * 0.1, 0.002, 0.06, ALIGN_CENTER, ALIGN_TOP, system_update, 0.0); // Connections-Status char tmp_str[100]; uint8_t n = 0; if (ModelData[ModelActive].teletype == TELETYPE_AUTOQUAD || ModelData[ModelActive].teletype == TELETYPE_ARDUPILOT || ModelData[ModelActive].teletype == TELETYPE_MEGAPIRATE_NG) { if (mavlink_connection_status(ModelActive) != 0) { sprintf(tmp_str, "MAVLINK %s (%i / %i)", ModelData[ModelActive].telemetry_port, ModelData[ModelActive].telemetry_baud, (uint8_t)(time(0)) - mavlink_connection_status(ModelActive)); draw_text_button(esContext, "mavlink_connection_status", VIEW_MODE_SYSTEM, tmp_str, FONT_GREEN, -1.3, 0.2 + n++ * 0.065, 0.002, 0.04, ALIGN_LEFT, ALIGN_TOP, system_null, 0.0); } else { sprintf(tmp_str, "MAVLINK %s (%i)", ModelData[ModelActive].telemetry_port, ModelData[ModelActive].telemetry_baud); draw_text_button(esContext, "mavlink_connection_status", VIEW_MODE_SYSTEM, tmp_str, FONT_WHITE, -1.3, 0.2 + n++ * 0.065, 0.002, 0.04, ALIGN_LEFT, ALIGN_TOP, system_null, 0.0); } } else { draw_text_button(esContext, "mavlink_connection_status", VIEW_MODE_SYSTEM, "MAVLINK", FONT_TRANS, -1.3, 0.2 + n++ * 0.065, 0.002, 0.04, ALIGN_LEFT, ALIGN_TOP, system_null, 0.0); } if (ModelData[ModelActive].teletype == TELETYPE_MULTIWII_21 || ModelData[ModelActive].teletype == TELETYPE_BASEFLIGHT) { if (mwi21_connection_status(ModelActive) != 0) { sprintf(tmp_str, "MULTIWII21 %s (%i / %i)", ModelData[ModelActive].telemetry_port, ModelData[ModelActive].telemetry_baud, (uint8_t)(time(0)) - mwi21_connection_status(ModelActive)); draw_text_button(esContext, "mwi21_connection_status", VIEW_MODE_SYSTEM, tmp_str, FONT_GREEN, -1.3, 0.2 + n++ * 0.065, 0.002, 0.04, ALIGN_LEFT, ALIGN_TOP, system_null, 0.0); } else { sprintf(tmp_str, "MULTIWII21 %s (%i)", ModelData[ModelActive].telemetry_port, ModelData[ModelActive].telemetry_baud); draw_text_button(esContext, "mwi21_connection_status", VIEW_MODE_SYSTEM, tmp_str, FONT_WHITE, -1.3, 0.2 + n++ * 0.065, 0.002, 0.04, ALIGN_LEFT, ALIGN_TOP, system_null, 0.0); } } else { draw_text_button(esContext, "mwi21_connection_status", VIEW_MODE_SYSTEM, "MULTIWII21", FONT_TRANS, -1.3, 0.2 + n++ * 0.065, 0.002, 0.04, ALIGN_LEFT, ALIGN_TOP, system_null, 0.0); } if (ModelData[ModelActive].teletype == TELETYPE_BASEFLIGHT) { if (mwi21_connection_status(ModelActive) != 0) { sprintf(tmp_str, "BASEFLIGHT %s (%i / %i)", ModelData[ModelActive].telemetry_port, ModelData[ModelActive].telemetry_baud, (uint8_t)(time(0)) - mwi21_connection_status(ModelActive)); draw_text_button(esContext, "mwi21_connection_status", VIEW_MODE_SYSTEM, tmp_str, FONT_GREEN, -1.3, 0.2 + n++ * 0.065, 0.002, 0.04, ALIGN_LEFT, ALIGN_TOP, system_null, 0.0); } else { sprintf(tmp_str, "BASEFLIGHT %s (%i)", ModelData[ModelActive].telemetry_port, ModelData[ModelActive].telemetry_baud); draw_text_button(esContext, "mwi21_connection_status", VIEW_MODE_SYSTEM, tmp_str, FONT_WHITE, -1.3, 0.2 + n++ * 0.065, 0.002, 0.04, ALIGN_LEFT, ALIGN_TOP, system_null, 0.0); } } else { draw_text_button(esContext, "mwi21_connection_status", VIEW_MODE_SYSTEM, "BASEFLIGHT", FONT_TRANS, -1.3, 0.2 + n++ * 0.065, 0.002, 0.04, ALIGN_LEFT, ALIGN_TOP, system_null, 0.0); } if (ModelData[ModelActive].teletype == TELETYPE_OPENPILOT) { if (openpilot_connection_status(ModelActive) != 0) { sprintf(tmp_str, "OPENPILOT %s (%i / %i)", ModelData[ModelActive].telemetry_port, ModelData[ModelActive].telemetry_baud, (uint8_t)(time(0)) - openpilot_connection_status(ModelActive)); draw_text_button(esContext, "openpilot_connection_status", VIEW_MODE_SYSTEM, tmp_str, FONT_GREEN, -1.3, 0.2 + n++ * 0.065, 0.002, 0.04, ALIGN_LEFT, ALIGN_TOP, system_null, 0.0); } else { sprintf(tmp_str, "OPENPILOT %s (%i)", ModelData[ModelActive].telemetry_port, ModelData[ModelActive].telemetry_baud); draw_text_button(esContext, "openpilot_connection_status", VIEW_MODE_SYSTEM, tmp_str, FONT_WHITE, -1.3, 0.2 + n++ * 0.065, 0.002, 0.04, ALIGN_LEFT, ALIGN_TOP, system_null, 0.0); } } else { draw_text_button(esContext, "openpilot_connection_status", VIEW_MODE_SYSTEM, "OPENPILOT", FONT_TRANS, -1.3, 0.2 + n++ * 0.065, 0.002, 0.04, ALIGN_LEFT, ALIGN_TOP, system_null, 0.0); } if (ModelData[ModelActive].teletype == TELETYPE_GPS_NMEA) { if (gps_connection_status(ModelActive) != 0) { sprintf(tmp_str, "NMEA-GPS %s (%i / %i)", ModelData[ModelActive].telemetry_port, ModelData[ModelActive].telemetry_baud, (uint8_t)(time(0)) - gps_connection_status(ModelActive)); draw_text_button(esContext, "gps_connection_status", VIEW_MODE_SYSTEM, tmp_str, FONT_GREEN, -1.3, 0.2 + n++ * 0.065, 0.002, 0.04, ALIGN_LEFT, ALIGN_TOP, system_null, 0.0); } else { sprintf(tmp_str, "NMEA-GPS %s (%i)", ModelData[ModelActive].telemetry_port, ModelData[ModelActive].telemetry_baud); draw_text_button(esContext, "gps_connection_status", VIEW_MODE_SYSTEM, tmp_str, FONT_WHITE, -1.3, 0.2 + n++ * 0.065, 0.002, 0.04, ALIGN_LEFT, ALIGN_TOP, system_null, 0.0); } } else { draw_text_button(esContext, "gps_connection_status", VIEW_MODE_SYSTEM, "NMEA-GPS", FONT_TRANS, -1.3, 0.2 + n++ * 0.065, 0.002, 0.04, ALIGN_LEFT, ALIGN_TOP, system_null, 0.0); } if (frsky_connection_status() != 0) { sprintf(tmp_str, "FRSKY %s (%i / %i)", setup.frsky_port, setup.frsky_baud, (uint8_t)(time(0)) - frsky_connection_status()); draw_text_button(esContext, "frsky", VIEW_MODE_SYSTEM, tmp_str, FONT_GREEN, -1.3, 0.2 + n++ * 0.065, 0.002, 0.04, ALIGN_LEFT, ALIGN_TOP, system_device_change, 0.0); } else { sprintf(tmp_str, "FRSKY %s (%i)", setup.frsky_port, setup.frsky_baud); draw_text_button(esContext, "frsky", VIEW_MODE_SYSTEM, tmp_str, FONT_WHITE, -1.3, 0.2 + n++ * 0.065, 0.002, 0.04, ALIGN_LEFT, ALIGN_TOP, system_device_change, 0.0); } if (jeti_connection_status() != 0) { sprintf(tmp_str, "JETI %s (%i / %i)", setup.jeti_port, setup.jeti_baud, (uint8_t)(time(0)) - jeti_connection_status()); draw_text_button(esContext, "jeti", VIEW_MODE_SYSTEM, tmp_str, FONT_GREEN, -1.3, 0.2 + n++ * 0.065, 0.002, 0.04, ALIGN_LEFT, ALIGN_TOP, system_device_change, 0.0); } else { sprintf(tmp_str, "JETI %s (%i)", setup.jeti_port, setup.jeti_baud); draw_text_button(esContext, "jeti", VIEW_MODE_SYSTEM, tmp_str, FONT_WHITE, -1.3, 0.2 + n++ * 0.065, 0.002, 0.04, ALIGN_LEFT, ALIGN_TOP, system_device_change, 0.0); } if (gcsgps_connection_status() != 0) { sprintf(tmp_str, "GCS-GPS %s (%i / %i)", setup.gcs_gps_port, setup.gcs_gps_baud, (uint8_t)(time(0)) - gcsgps_connection_status()); draw_text_button(esContext, "gcs_gps", VIEW_MODE_SYSTEM, tmp_str, FONT_GREEN, -1.3, 0.2 + n++ * 0.065, 0.002, 0.04, ALIGN_LEFT, ALIGN_TOP, system_device_change, 0.0); } else { sprintf(tmp_str, "GCS-GPS %s (%i)", setup.gcs_gps_port, setup.gcs_gps_baud); draw_text_button(esContext, "gcs_gps", VIEW_MODE_SYSTEM, tmp_str, FONT_WHITE, -1.3, 0.2 + n++ * 0.065, 0.002, 0.04, ALIGN_LEFT, ALIGN_TOP, system_device_change, 0.0); } if (rcflow_connection_status() != 0) { sprintf(tmp_str, "RCFLOW %s (%i / %i)", setup.rcflow_port, setup.rcflow_baud, (uint8_t)(time(0)) - rcflow_connection_status()); draw_text_button(esContext, "rcflow", VIEW_MODE_SYSTEM, tmp_str, FONT_GREEN, -1.3, 0.2 + n++ * 0.065, 0.002, 0.04, ALIGN_LEFT, ALIGN_TOP, system_device_change, 0.0); } else { sprintf(tmp_str, "RCFLOW %s (%i)", setup.rcflow_port, setup.rcflow_baud); draw_text_button(esContext, "rcflow", VIEW_MODE_SYSTEM, tmp_str, FONT_WHITE, -1.3, 0.2 + n++ * 0.065, 0.002, 0.04, ALIGN_LEFT, ALIGN_TOP, system_device_change, 0.0); } if (tracker_connection_status() != 0) { sprintf(tmp_str, "TRACKER %s (%i / %i)", setup.tracker_port, setup.tracker_baud, (uint8_t)(time(0)) - tracker_connection_status()); draw_text_button(esContext, "tracker", VIEW_MODE_SYSTEM, tmp_str, FONT_GREEN, -1.3, 0.2 + n++ * 0.065, 0.002, 0.04, ALIGN_LEFT, ALIGN_TOP, system_device_change, 0.0); } else { sprintf(tmp_str, "TRACKER %s (%i)", setup.tracker_port, setup.tracker_baud); draw_text_button(esContext, "tracker", VIEW_MODE_SYSTEM, tmp_str, FONT_WHITE, -1.3, 0.2 + n++ * 0.065, 0.002, 0.04, ALIGN_LEFT, ALIGN_TOP, system_device_change, 0.0); } sprintf(tmp_str, "Font: %s (%i/%i)", fontnames[(int)setup.font], setup.font + 1, FONT_MAX); draw_text_button(esContext, "_font", VIEW_MODE_SYSTEM, tmp_str, FONT_GREEN, 0.55, 0.2, 0.002, 0.05, ALIGN_LEFT, ALIGN_TOP, system_set_font, 0.0); sprintf(tmp_str, "Resolution: %ix%i", esContext->width, esContext->height); draw_text_button(esContext, "_res", VIEW_MODE_SYSTEM, tmp_str, FONT_GREEN, 0.55, 0.3, 0.002, 0.05, ALIGN_LEFT, ALIGN_TOP, system_set_fps, 0.0); draw_text_button(esContext, "_border_x", VIEW_MODE_SYSTEM, "X-Border", FONT_GREEN, 0.55, 0.4, 0.002, 0.05, ALIGN_LEFT, ALIGN_TOP, system_set_border_x, 0.0); draw_text_button(esContext, "_border_x--", VIEW_MODE_SYSTEM, "[-]", FONT_GREEN, 0.85, 0.4, 0.002, 0.05, ALIGN_LEFT, ALIGN_TOP, system_set_border_x, -2.0); draw_text_button(esContext, "_border_x++", VIEW_MODE_SYSTEM, "[+]", FONT_GREEN, 0.95, 0.4, 0.002, 0.05, ALIGN_LEFT, ALIGN_TOP, system_set_border_x, 2.0); draw_text_button(esContext, "_border_y", VIEW_MODE_SYSTEM, "Y-Border", FONT_GREEN, 0.55, 0.5, 0.002, 0.05, ALIGN_LEFT, ALIGN_TOP, system_set_border_y, 0.0); draw_text_button(esContext, "_border_y--", VIEW_MODE_SYSTEM, "[-]", FONT_GREEN, 0.85, 0.5, 0.002, 0.05, ALIGN_LEFT, ALIGN_TOP, system_set_border_y, -2.0); draw_text_button(esContext, "_border_y++", VIEW_MODE_SYSTEM, "[+]", FONT_GREEN, 0.95, 0.5, 0.002, 0.05, ALIGN_LEFT, ALIGN_TOP, system_set_border_y, 2.0); sprintf(tmp_str, "Ratio(%0.1f)", setup.keep_ratio); draw_text_button(esContext, "ratio", VIEW_MODE_SYSTEM, tmp_str, FONT_GREEN, 0.55, 0.6, 0.002, 0.05, ALIGN_LEFT, ALIGN_TOP, system_set_ratio, 0.0); draw_text_button(esContext, "ratio--", VIEW_MODE_SYSTEM, "[-]", FONT_GREEN, 0.85, 0.6, 0.002, 0.05, ALIGN_LEFT, ALIGN_TOP, system_set_ratio, -0.1); draw_text_button(esContext, "ratio++", VIEW_MODE_SYSTEM, "[+]", FONT_GREEN, 0.95, 0.6, 0.002, 0.05, ALIGN_LEFT, ALIGN_TOP, system_set_ratio, 0.1); if (setup.side_by_side == 1) { draw_text_button(esContext, "side_by_side", VIEW_MODE_SYSTEM, "SideBySide", FONT_PINK, 0.55, 0.7, 0.002, 0.05, ALIGN_LEFT, ALIGN_TOP, system_set_side_by_side, 0.1); } else { draw_text_button(esContext, "side_by_side", VIEW_MODE_SYSTEM, "SideBySide", FONT_GREEN, 0.55, 0.7, 0.002, 0.05, ALIGN_LEFT, ALIGN_TOP, system_set_side_by_side, 0.1); } #ifndef ANDROID #ifdef SDL2 if (setup.fullscreen == 0) { draw_text_button(esContext, "fullscreen", VIEW_MODE_SYSTEM, "TOGGLE FULLSCREEN", FONT_WHITE, 0.55, 0.7, 0.002, 0.05, ALIGN_LEFT, ALIGN_TOP, system_set_fullscreen, 0.0); } else { draw_text_button(esContext, "fullscreen", VIEW_MODE_SYSTEM, "TOGGLE FULLSCREEN", FONT_GREEN, 0.55, 0.7, 0.002, 0.05, ALIGN_LEFT, ALIGN_TOP, system_set_fullscreen, 0.0); } #endif #endif if (setup.weather_enable == 1) { draw_text_button(esContext, "copyright", VIEW_MODE_SYSTEM, "Weather-Data copyright by http://www.openweathermap.org", FONT_PINK, 0.0, 0.88, 0.002, 0.04, ALIGN_CENTER, ALIGN_TOP, system_null, 0.0); } draw_text_button(esContext, "copyright", VIEW_MODE_SYSTEM, "Copyright by Oliver Dippel ([email protected])", FONT_PINK, 0.0, 0.93, 0.002, 0.04, ALIGN_CENTER, ALIGN_TOP, system_null, 0.0); screen_device(esContext); screen_baud(esContext); if (resize != 0) { resize = 0; #ifdef SDL2 glResize(esContext, setup.screen_w, setup.screen_h); #endif } }