[clean] removing old tools, some of them where using pcre lib

This commit is contained in:
Gautier Hattenberger
2026-04-14 23:14:23 +02:00
parent 07b5404f4d
commit 5d31ccde87
19 changed files with 6 additions and 3552 deletions
+2 -6
View File
@@ -37,7 +37,7 @@ XLINKPKG = $(XPKG) -linkpkg -dllpath-pkg pprz.xlib,pprzlink,$(USE_LABELGTK)
SERVERCMO = server_globals.cmo aircraft_server.cmo wind.cmo airprox.cmo kml.cmo parse_messages_v1.ml intruder.cmo server.cmo
SERVERCMX = $(SERVERCMO:.cmo=.cmx)
all: link server ivy_tcp_aircraft ivy_tcp_controller ivy2udp ivy2serial app_server ivy2nmea gpsd2ivy gtk_tools
all: link server ivy_tcp_aircraft ivy_tcp_controller ivy2udp ivy2serial ivy2nmea gpsd2ivy gtk_tools
ifeq ($(USE_LABELGTK),lablgtk2)
gtk_tools: messages
@@ -46,7 +46,7 @@ endif
opt: server.opt
clean:
$(Q)rm -f link server messages *.bak *~ core *.o .depend *.opt *.out *.cm* ivy_tcp_aircraft ivy_tcp_controller ivy2udp ivy2serial ivy_serial_bridge app_server gpsd2ivy c_ivy_client_example_1 c_ivy_client_example_2 ivy2nmea
$(Q)rm -f link server messages *.bak *~ core *.o .depend *.opt *.out *.cm* ivy_tcp_aircraft ivy_tcp_controller ivy2udp ivy2serial ivy_serial_bridge gpsd2ivy c_ivy_client_example_1 c_ivy_client_example_2 ivy2nmea
messages : messages.cmo $(LIBPPRZCMA) $(LIBPPRZLINKCMA)
@echo OL $@
@@ -115,10 +115,6 @@ ifeq ("$(UNAME)","Darwin")
endif
app_server: app_server.c Makefile
@echo OL $@
$(Q)$(CC) $(shell pkg-config libxml-2.0 gio-2.0 ivy-glib --cflags) -o $@ $< -lm -lz $(shell pkg-config libxml-2.0 gio-2.0 ivy-glib --libs) $(PCRE_LDFLAGS)
gpsd2ivy: gpsd2ivy.c Makefile
ifeq (, $(shell which gpsd))
$(info GPSD not installed)
File diff suppressed because it is too large Load Diff
+4 -41
View File
@@ -35,14 +35,14 @@ ifeq ($(USE_LABELGTK),lablgtk2)
ifeq ($(LABLGTK2GLADE),)
XPKG = -package lablgtk2,pprz.xlib
XLINKPKG = $(XPKG) -linkpkg -dllpath-pkg pprz.xlib,pprzlink,$(USE_LABELGTK)
all : play plotter sd2log plotprofile openlog2tlm sdlogger_download
all : play plotter sd2log openlog2tlm sdlogger_download
else
XPKG = -package lablgtk2,pprz.xlib,lablgtk2.glade
XLINKPKG = $(XPKG) -linkpkg -dllpath-pkg pprz.xlib,pprzlink,$(USE_LABELGTK)
all : play plotter logplotter sd2log plotprofile openlog2tlm sdlogger_download
all : play plotter logplotter sd2log openlog2tlm sdlogger_download
endif
else # no gtk2
all: sd2log plotprofile openlog2tlm sdlogger_download
all: sd2log openlog2tlm sdlogger_download
endif
@@ -107,50 +107,13 @@ gtk_export.ml : export.glade
CC = gcc
CFLAGS=-g -O2 -Wall
PCRE_LDFLAGS= $(shell pcre2-config --libs8)
openlog2tlm: openlog2tlm.c
@echo CC $@
$(Q)$(CC) $(CFLAGS) -o $@ $^
DISP3D_CFLAGS = $(shell pkg-config --cflags ivy-glib gtk+-2.0 gtkgl-2.0)
DISP3D_LDFLAGS = $(shell pkg-config --libs ivy-glib gtk+-2.0 gtkgl-2.0) $(PCRE_LDFLAGS)
disp3d: disp3d.c
@echo CC $@
$(Q)$(CC) $(CFLAGS) $(DISP3D_CFLAGS) -o $@ $^ $(DISP3D_LDFLAGS)
IVY_C_LIBS = $(shell pkg-config --libs ivy-glib) $(PCRE_LDFLAGS)
GLIBIVY_CFLAGS = $(shell pkg-config --cflags ivy-glib)
#
# try to find include locations on OSX
#
UNAME = $(shell uname -s)
ifeq ("$(UNAME)","Darwin")
IVY_C_LIB_INC = $(shell if test -d /opt/paparazzi/lib; then echo "-L/opt/paparazzi/lib"; elif test -d /opt/local/lib; then echo "-L/opt/local/lib"; fi)
IVY_C_INCLUDES = $(shell if test -d /opt/paparazzi/include; then echo "-I/opt/paparazzi/include"; elif test -d /opt/local/include; then echo "-I/opt/local/include"; fi)
GLIBIVY_CFLAGS += $(IVY_C_LIB_INC) $(IVY_C_INCLUDES)
endif
plotprofile: plotprofile.c
@echo CC $@
$(Q)$(CC) $(CFLAGS) $(GLIBIVY_CFLAGS) -o $@ $^ $(IVY_C_LIBS)
ahrs2fg: ahrs2fg.c network.c flight_gear.c utils.c
$(CC) $(CFLAGS) $(GLIBIVY_CFLAGS) -o $@ $^ $(IVY_C_LIBS) -lm
tmclient: tmclient.c
$(CC) -g -O1 -Wall $(GLIBIVY_CFLAGS) -o $@ $^ $(IVY_C_LIBS)
ffjoystick: ffjoystick.c
$(CC) -g -O2 -Wall $(GLIBIVY_CFLAGS) -o $@ $^ $(IVY_C_LIBS) -lm
clean:
$(Q)rm -f *.opt *.out *~ core *.o *.bak .depend *.cm* play ahrs2fg logplotter plotter gtk_export.ml openlog2tlm disp3d plotprofile tmclient ffjoystick sd2log sdlogger_download
$(Q)rm -f *.opt *.out *~ core *.o *.bak .depend *.cm* play logplotter plotter gtk_export.ml openlog2tlm sd2log sdlogger_download
.PHONY: all clean
-193
View File
@@ -1,193 +0,0 @@
#include <glib.h>
#include <stdio.h>
#include <math.h>
#include <stdlib.h>
#include <string.h>
#include "flight_gear.h"
#include "network.h"
#include <Ivy/ivy.h>
#include <Ivy/ivyglibloop.h>
// Default Host
char default_fg_host[] = "127.0.0.1";
char* fg_host;
// Default TCP port
int fg_port = 5501;
#ifdef __APPLE__
char defaultIvyBus[] = "224.255.255.255:2010";
#else
char defaultIvyBus[] = "127.255.255.255:2010";
#endif
char* IvyBus;
int verbose = FALSE;
// quat int res
const float quat_int_res = (float)(1<<15);
// euler int res
const float euler_int_res = (float)(1<<12);
gfloat quat[4];
gfloat eulers[3];
gboolean timeout_callback(gpointer data) {
static double x = 0.;
static double y = 0.;
static double z = 10.;
const double earth_radius = 6372795.;
double lat = 0.656480 + asin(x/earth_radius);
double lon = -2.135537 + asin(y/earth_radius);
struct FGNetGUI gui;
net_gui_init(&gui);
gui.latitude = lat;
gui.longitude = lon;
gui.altitude = z;
if (verbose) {
printf("phi:%f, theta:%f, psi:%f\n", eulers[0], eulers[1], eulers[2]);
fflush(stdout);
}
gui.phi = eulers[0];
gui.theta = eulers[1];
gui.psi = eulers[2];
// net_gui_hton(&gui);
send_buf((struct FgNetChannel*)data, (char*)&gui, sizeof(gui));
return TRUE;
}
void quat_to_euler( gfloat* quat, gfloat* euler) {
// float q02 = quat[0] * quat[0];
float q12 = quat[1] * quat[1];
float q22 = quat[2] * quat[2];
float q32 = quat[3] * quat[3];
euler[0] = atan2( 2*(quat[2]*quat[3] + quat[0]*quat[1]),(1-2*(q12 + q22)) );
euler[1] = -asin(2*(quat[1]*quat[3] - quat[0]*quat[2]));
euler[2] = atan2( 2*(quat[1]*quat[2] + quat[0]*quat[3]),(1-2*(q22 + q32)) );
}
void on_ATTITUDE(IvyClientPtr app, void *user_data, int argc, char *argv[]){
float phi = atof(argv[0]);
float psi = atof(argv[1]);
float theta = atof(argv[2]);
eulers[0] = phi;
eulers[1] = theta;
eulers[2] = psi;
}
void on_AHRS_EULER_INT(IvyClientPtr app, void *user_data, int argc, char *argv[]){
float phi = atof(argv[3]);
float theta = atof(argv[4]);
float psi = atof(argv[5]);
eulers[0] = phi / euler_int_res;
eulers[1] = theta / euler_int_res;
eulers[2] = psi / euler_int_res;
}
void on_AHRS_QUAT_INT(IvyClientPtr app, void *user_data, int argc, char *argv[]){
float q0 = atof(argv[5]);
float q1 = atof(argv[6]);
float q2 = atof(argv[7]);
float q3 = atof(argv[8]);
quat[0] = q0 / quat_int_res;
quat[1] = q1 / quat_int_res;
quat[2] = q2 / quat_int_res;
quat[3] = q3 / quat_int_res;
quat_to_euler(quat, eulers);
}
void on_ROTORCRAFT_FP(IvyClientPtr app, void *user_data, int argc, char *argv[]){
float phi = atof(argv[6]);
float theta = atof(argv[7]);
float psi = atof(argv[8]);
eulers[0] = phi / euler_int_res;
eulers[1] = theta / euler_int_res;
eulers[2] = psi / euler_int_res;
}
// Print help message
void print_help() {
printf("Usage: ahrs2fg [options] <AC_ID>\n");
printf(" Options :\n");
printf(" -fg_host <host>\tFlight Gear host address (default: %s)\n", fg_host);
printf(" -fg_port <port>\tFlight Gear port (default: %d)\n", fg_port);
printf(" -b <Ivy bus>\tdefault is %s\n", defaultIvyBus);
printf(" -v\tverbose\n");
printf(" -h --help show this help\n");
}
int main ( int argc, char** argv) {
int ac_id = -1;
IvyBus = getenv("IVYBUS");
if (IvyBus == NULL) IvyBus = defaultIvyBus;
fg_host = default_fg_host;
if (argc < 1) {
print_help();
exit(0);
}
// Parse options
int i;
for (i = 1; i < argc; ++i) {
if (strcmp(argv[i], "--help") == 0 || strcmp(argv[i], "-h") == 0) {
print_help();
exit(0);
}
else if (strcmp(argv[i], "-fg_host") == 0) {
fg_host = argv[++i];
}
else if (strcmp(argv[i], "-fg_port") == 0) {
fg_port = atoi(argv[++i]);
}
else if (strcmp(argv[i], "-b") == 0) {
IvyBus = argv[++i];
}
else if (strcmp(argv[i], "-v") == 0) {
verbose = TRUE;
}
else {
ac_id = atoi(argv[i]);
}
}
if (ac_id == -1) {
print_help();
exit(0);
}
if (verbose) {
printf("FG options: %s:%d\n", fg_host, fg_port);
fflush(stdout);
}
struct FgNetChannel* chan = open_out_channel(fg_host, fg_port);
g_timeout_add(50, timeout_callback, chan);
GMainLoop *ml = g_main_loop_new(NULL, FALSE);
IvyInit ("ahrs2fg", "ahrs2fg READY", NULL, NULL, NULL, NULL);
IvyBindMsg(on_ATTITUDE, chan, "^%d ATTITUDE (\\S*) (\\S*) (\\S*)", ac_id);
IvyBindMsg(on_AHRS_EULER_INT, chan, "^%d AHRS_EULER_INT (\\S*) (\\S*) (\\S*) (\\S*) (\\S*) (\\S*) (\\S*)", ac_id);
IvyBindMsg(on_AHRS_QUAT_INT, chan, "^%d AHRS_QUAT_INT (\\S*) (\\S*) (\\S*) (\\S*) (\\S*) (\\S*) (\\S*) (\\S*) (\\S*) (\\S*)", ac_id);
IvyBindMsg(on_ROTORCRAFT_FP, chan, "^%d ROTORCRAFT_FP (\\S*) (\\S*) (\\S*) (\\S*) (\\S*) (\\S*) (\\S*) (\\S*) (\\S*) (\\S*) (\\S*) (\\S*) (\\S*) (\\S*) (\\S*)", ac_id);
if (verbose) {
printf("Ivy options: %s\n", IvyBus);
fflush(stdout);
}
IvyStart(IvyBus);
g_main_loop_run(ml);
return 0;
}
File diff suppressed because it is too large Load Diff
-167
View File
@@ -1,167 +0,0 @@
/*
* based on ffmvforce.c
*
*/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*
* You can contact the author by email at this address:
* Johann Deneux <deneux@ifrance.com>
*/
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <sys/stat.h>
#include <sys/ioctl.h>
#include <fcntl.h>
#include <unistd.h>
#include <math.h>
#include <linux/input.h>
#include <glib.h>
#include <Ivy/ivy.h>
#include <Ivy/ivyglibloop.h>
#define BIT(x) (1<<(x))
#define STR_LEN 64
#define PPRZ_MAX 9600
#define PPRZ_MIN (-PPRZ_MAX)
#define max(a,b) ((a)>(b)?(a):(b))
/* File descriptor of the force feedback /dev entry */
static int ff_fd;
static struct ff_effect effect;
static void welcome()
{
const char* txt[] = {
"ffjoystick: generate force feedback reaction from Paparazzi autopilot",
"Set COMMANDS message repeat rate low in telemetry and"
"use aircraft with rudder on channel 1 and elevator on 2",
"USE WITH CARE !!! HOLD STRONGLY YOUR WHEEL OR JOYSTICK TO PREVENT DAMAGES",
"To run this program, run it with at least one argument.",
"",
NULL };
const char** p = txt;
while (*p) {
printf("%s\n", *p);
p++;
}
}
static void generate_force(double nx, double ny)
{
static int first = 1;
double angle;
angle = atan2(nx, -ny);
//printf("n: %4.2f %4.2f angle: %4.2f\n", nx, ny, angle);
effect.type = FF_CONSTANT;
effect.u.constant.level = 0x7fff * max(fabs(nx), fabs(ny));
effect.direction = 0x8000 * (angle + M_PI)/M_PI;
//printf("level: %04x direction: %04x\n", (unsigned int)effect.u.constant.level, (unsigned int)effect.direction);
effect.u.constant.envelope.attack_length = 0;
effect.u.constant.envelope.attack_level = 0;
effect.u.constant.envelope.fade_length = 0;
effect.u.constant.envelope.fade_level = 0;
effect.trigger.button = 0;
effect.trigger.interval = 0;
effect.replay.length = 0xffff;
effect.replay.delay = 0;
if (first) {
effect.id = -1;
}
if (ioctl(ff_fd, EVIOCSFF, &effect) < 0) {
/* If updates are sent to frequently, they can be refused */
}
/* If first time, start to play the effect */
if (first) {
struct input_event play;
play.type = EV_FF;
play.code = effect.id;
play.value = 1;
if (write(ff_fd, (const void*) &play, sizeof(play)) == -1) {
perror("Play effect");
exit(1);
}
}
first = 0;
}
void on_commands(IvyClientPtr app, void *user_data, int argc, char *argv[]){
char* start = argv[0];
char* stop;
int x, y;
strtol(start, &stop, 10);
start=stop+1;
x = -strtol(start, &stop, 10);
start=stop+1;
y = strtol(start, &stop, 10);
if (x>PPRZ_MAX) x=PPRZ_MAX;
if (x<PPRZ_MIN) x=PPRZ_MIN;
if (y>PPRZ_MAX) y=PPRZ_MAX;
if (y<PPRZ_MIN) y=PPRZ_MIN;
generate_force((double)x/PPRZ_MAX, (double)y/PPRZ_MAX);
}
int main(int argc, char** argv)
{
char dev_name[STR_LEN];
int i;
GMainLoop *ml = g_main_loop_new(NULL, FALSE);
welcome();
if (argc <= 1) return 0;
/* Parse parameters */
strcpy(dev_name, "/dev/input/event0");
for (i=1; i<argc; ++i) {
if (strcmp(argv[i], "--help") == 0) {
printf("Usage: %s /dev/input/eventXX\n", argv[0]);
exit(1);
}
else {
strncpy(dev_name, argv[i], STR_LEN);
}
}
/* Open force feedback device */
ff_fd = open(dev_name, O_RDWR);
if (ff_fd == -1) {
perror("Open device file");
exit(1);
}
IvyInit ("IvyExample", "IvyExample READY", NULL, NULL, NULL, NULL);
IvyBindMsg(on_commands, NULL, "^\\S* COMMANDS (\\S*)");
IvyStart("127.255.255.255");
g_main_loop_run(ml);
return 0;
}
-416
View File
@@ -1,416 +0,0 @@
#include "flight_gear.h"
#include <stdio.h>
#include <netinet/in.h>
#include <string.h>
#include "utils.h"
void net_fdm_ntoh (struct FGNetFDM* fdm) {
fdm->version = ntohl(fdm->version);
htond(&fdm->latitude);
htond(&fdm->longitude);
htond(&fdm->altitude);
htonf(&fdm->agl);
htonf(&fdm->phi);
htonf(&fdm->theta);
htonf(&fdm->psi);
htonf(&fdm->alpha);
htonf(&fdm->beta);
htonf(&fdm->phidot);
htonf(&fdm->thetadot);
htonf(&fdm->psidot);
htonf(&fdm->vcas);
htonf(&fdm->climb_rate);
htonf(&fdm->v_north);
htonf(&fdm->v_east);
htonf(&fdm->v_down);
htonf(&fdm->v_wind_body_north);
htonf(&fdm->v_wind_body_east);
htonf(&fdm->v_wind_body_down);
htonf(&fdm->A_X_pilot);
htonf(&fdm->A_Y_pilot);
htonf(&fdm->A_Z_pilot);
htonf(&fdm->stall_warning);
htonf(&fdm->slip_deg);
fdm->num_engines = ntohl(fdm->num_engines);
int i;
for (i=0; i<FG_NET_FDM_MAX_ENGINES; i++) {
fdm->eng_state[i] = ntohl(fdm->eng_state[i]);
htonf(&fdm->rpm[i]);
htonf(&fdm->fuel_flow[i]);
htonf(&fdm->egt[i]);
htonf(&fdm->cht[i]);
htonf(&fdm->mp_osi[i]);
htonf(&fdm->tit[i]);
htonf(&fdm->oil_temp[i]);
htonf(&fdm->oil_px[i]);
}
fdm->num_tanks = ntohl(fdm->num_tanks);
for (i=0; i<FG_NET_FDM_MAX_TANKS; i++) {
htonf(&fdm->fuel_quantity[i]);
}
fdm->num_wheels = ntohl(fdm->num_wheels);
for (i=0; i<FG_NET_FDM_MAX_WHEELS; i++) {
fdm->wow[i] = ntohl(fdm->wow[i]);
htonf(&fdm->gear_pos[i]);
htonf(&fdm->gear_steer[i]);
htonf(&fdm->gear_compression[i]);
}
fdm->cur_time = ntohl(fdm->cur_time);
fdm->warp = ntohl(fdm->warp);
htonf(&fdm->visibility);
htonf(&fdm->elevator);
htonf(&fdm->elevator_trim_tab);
htonf(&fdm->left_flap);
htonf(&fdm->right_flap);
htonf(&fdm->left_aileron);
htonf(&fdm->right_aileron);
htonf(&fdm->rudder);
htonf(&fdm->nose_wheel);
htonf(&fdm->speedbrake);
htonf(&fdm->spoilers);
}
void net_fdm_dump (struct FGNetFDM* fdm) {
printf("net_fdm (version %d size %d)\n",fdm->version, sizeof( *fdm));
printf(" lat, lon, alt, agl\n [%f %f %f %f]\n",
fdm->latitude, fdm->longitude, fdm->altitude, fdm->agl);
printf(" phi, theta, psi, alpha, beta\n [%f %f %f %f %f]\n",
fdm->phi, fdm->theta, fdm->psi, fdm->alpha, fdm->beta);
printf(" phidot, thetadot, psidot, vcas, climb_rate\n [%f %f %f %f %f]\n",
fdm->phidot, fdm->thetadot, fdm->psidot, fdm->vcas, fdm->climb_rate);
printf(" v_north, v_east, v_down\n [%f %f %f]\n",
fdm->v_north, fdm->v_east, fdm->v_down);
printf(" v_wind_body_north, v_wind_body_east, v_wind_body_down\n [%f %f %f]\n",
fdm->v_wind_body_north, fdm->v_wind_body_east, fdm->v_wind_body_down);
/* [......] */
printf(" cur_time, warp\n [%u %u]\n", fdm->cur_time, fdm->warp);
printf(" visibility [%f]\n", fdm->visibility);
printf(" elevator, elevator_trim_tab\n [%f %f]\n",
fdm->elevator, fdm->elevator_trim_tab);
printf(" left_flap, right_flap\n [%f %f]\n",
fdm->left_flap, fdm->right_flap);
printf(" left_aileron, right_aileron\n [%f %f]\n",
fdm->left_aileron, fdm->right_aileron);
printf(" rudder, nose_wheel\n [%f %f]\n",
fdm->rudder, fdm->nose_wheel);
printf(" speedbrake, spoilers\n [%f %f]\n",
fdm->speedbrake, fdm->spoilers);
}
void net_fdm_init ( struct FGNetFDM* fdm ) {
fdm->version = FG_NET_FDM_VERSION;
fdm->latitude = 0.656480;
fdm->longitude = -2.135537;
fdm->altitude = 2.;
fdm->agl = 1.111652;
fdm->phi = 0.;
fdm->theta = 0.;
fdm->psi = 5.20;
fdm->alpha = 0.;
fdm->beta = 0.;
fdm->phidot = 0.;
fdm->thetadot = 0.;
fdm->psidot = 0.;
fdm->vcas = 0.;
fdm->climb_rate = 0.;
fdm->v_north = 0.;
fdm->v_east = 0.;
fdm->v_down = 0.;
fdm->v_wind_body_north = 0.;
fdm->v_wind_body_east = 0.;
fdm->v_wind_body_down = 0.;
fdm->A_X_pilot = 0.;
fdm->A_Y_pilot = 0.;
fdm->A_Z_pilot = 0.;
fdm->stall_warning = 0.;
fdm->slip_deg = 0.;
fdm->num_engines = 2;
fdm->eng_state[0] = 0;
fdm->eng_state[1] = 0;
fdm->rpm[0] = 0.;
fdm->rpm[1] = 0.;
fdm->fuel_flow[0] = 0.;
fdm->fuel_flow[1] = 0.;
fdm->egt[0] = 0.;
fdm->egt[1] = 0.;
fdm->egt[0] = 0.;
fdm->egt[1] = 0.;
fdm->cht[0] = 0.;
fdm->cht[1] = 0.;
fdm->mp_osi[0] = 0.;
fdm->mp_osi[1] = 0.;
fdm->tit[0] = 0.;
fdm->tit[1] = 0.;
fdm->oil_temp[0] = 0.;
fdm->oil_temp[1] = 0.;
fdm->oil_px[0] = 0.;
fdm->oil_px[1] = 0.;
fdm->num_tanks = 4;
fdm->fuel_quantity[0] = 0.;
fdm->fuel_quantity[1] = 0.;
fdm->fuel_quantity[2] = 0.;
fdm->fuel_quantity[3] = 0.;
fdm->num_wheels = 1;
fdm->wow[0] = 1;
fdm->gear_pos[0] = 0.;
fdm->gear_steer[0] = 0.;
fdm->gear_compression[0] = 0.;
fdm->cur_time = 3213082700ul;
fdm->warp = 0;
fdm->visibility = 1000.;
fdm->elevator = 0.;
fdm->elevator_trim_tab = 0.;
fdm->left_flap = 0.;
fdm->right_flap = 0.;
fdm->left_aileron = 0.;
fdm->right_aileron = 0.;
fdm->rudder = 0.;
fdm->nose_wheel = 0.;
fdm->speedbrake = 0.;
fdm->spoilers = 0.;
}
void net_gui_init (struct FGNetGUI* gui) {
gui->version = FG_NET_GUI_VERSION;
gui->latitude = 0.656480;
gui->longitude = -2.135537;
gui->altitude = 0.807609;
gui->agl = 1.111652;
gui->phi = 0.;
gui->theta = 0.;
gui->psi = 5.20;
gui->vcas = 0.;
gui->climb_rate = 0.;
gui->num_tanks = 1;
gui->fuel_quantity[0] = 0.;
gui->cur_time = 3198060679ul;
gui->warp = 1122474394ul;
gui->ground_elev = 0.;
gui->tuned_freq = 125.65;
gui->nav_radial = 90.;
gui->in_range = 1;
gui->dist_nm = 10.;
gui->course_deviation_deg = 0.;
gui->gs_deviation_deg = 0.;
}
void net_gui_hton (struct FGNetGUI* gui) {
gui->version = ntohl(gui->version);
htond(&gui->latitude);
htond(&gui->longitude);
htonf(&gui->altitude);
htonf(&gui->agl);
htonf(&gui->phi);
htonf(&gui->theta);
htonf(&gui->psi);
}
void net_gui_dump (struct FGNetGUI* gui) {
printf("net_gui (version %d size %d)\n",gui->version, sizeof( *gui));
printf(" lat, lon, alt, agl\n [%f %f %f %f]\n",
gui->latitude, gui->longitude, gui->altitude, gui->agl);
printf(" phi, theta, psi\n [%f %f %f]\n",
gui->phi, gui->theta, gui->psi);
printf(" vcas, climb_rate\n [%f %f]\n",
gui->vcas, gui->climb_rate);
printf(" num_tanks, fuel[0], fuel[1], fuel[2], fuel[3]\n [%u %f %f %f %f]\n",
gui->num_tanks, gui->fuel_quantity[0], gui->fuel_quantity[1],
gui->fuel_quantity[2], gui->fuel_quantity[3]);
printf(" cur_time, warp\n [%u %u]\n", gui->cur_time, gui->warp);
printf(" ground_elev\n [%f]\n",
gui->ground_elev);
printf(" tuned_freq, nav_radial, in_range\n [%f %f %u]\n",
gui->tuned_freq, gui->nav_radial, gui->in_range);
printf(" dist_nm, course_deviation_deg, gs_deviation_deg\n [%f %f %f]\n",
gui->dist_nm, gui->course_deviation_deg, gui->gs_deviation_deg);
}
void net_ctrls_init(struct FGNetCtrls* ctrls) {
ctrls->version = FG_NET_CTRLS_VERSION;
ctrls->aileron = 0.;
ctrls->elevator = 0.;
ctrls->rudder = 0.;
ctrls->aileron_trim = 0.;
ctrls->elevator_trim = 0.;
ctrls->rudder_trim = 0.;
ctrls->flaps = 0.;
ctrls->spoilers = 0.;
ctrls->speedbrake = 0.;
ctrls->flaps_power = 1;
ctrls->flap_motor_ok = 1;
ctrls->num_engines = 2;
int i;
for (i=0; i< 2; i++) {
ctrls->master_bat[i] = 1;
ctrls->master_alt[i] = 1;
ctrls->magnetos[i] = 1;
ctrls->starter_power[i] = 0;
ctrls->throttle[i] = 0.;
ctrls->mixture[i] = 0.;
ctrls->condition[i] = 0.;
ctrls->fuel_pump_power[i] = 1;
ctrls->prop_advance[i] = 1.;
ctrls->feed_tank_to[i] = 1;
ctrls->reverse[i] = 0;
ctrls->engine_ok[i] = 1;
ctrls->mag_left_ok[i] = 1;
ctrls->mag_right_ok[i] = 1;
ctrls->spark_plugs_ok[i] = 1;
ctrls->oil_press_status[i] = 0;
ctrls->fuel_pump_ok[i] = 1;
}
ctrls->num_tanks = 1;
ctrls->fuel_selector[0] = 1;
ctrls->xfer_pump[0] = 1;
ctrls->cross_feed = 0;
ctrls->brake_left = 0.;
ctrls->brake_right = 0.;
ctrls->copilot_brake_left = 0.;
ctrls->copilot_brake_right = 0.;
ctrls->brake_parking = 0.;
ctrls->gear_handle = 1;
ctrls->master_avionics = 0;
ctrls->comm_1 = 123.4;
ctrls->comm_2 = 123.4;
ctrls->nav_1 = 123.4;
ctrls->nav_2 = 123.4;
ctrls->wind_speed_kt = 0.;
ctrls->wind_dir_deg = 0.;
ctrls->turbulence_norm = 0.;
ctrls->temp_c = 25.;
ctrls->press_inhg = 25.;
ctrls->hground = 25.;
ctrls->magvar = 0.;
ctrls->speedup = 1;
}
void net_ctrls_ntoh(struct FGNetCtrls* ctrls) {
ctrls->version = ntohl(ctrls->version);
htond(&ctrls->aileron);
htond(&ctrls->elevator);
htond(&ctrls->rudder);
htond(&ctrls->aileron_trim);
htond(&ctrls->elevator_trim);
htond(&ctrls->rudder_trim);
htond(&ctrls->flaps);
}
void net_ctrls_dump(struct FGNetCtrls* ctrls) {
printf("net_ctrls (version %d size %d)\n",ctrls->version, sizeof( *ctrls));
printf(" aileron elevator rudder\n [%f %f %f]\n",
ctrls->aileron, ctrls->elevator, ctrls->rudder);
printf(" throttle\n [%f %f %f]\n",
ctrls->throttle[0], ctrls->throttle[1], ctrls->throttle[2]);
}
void mplay_msg_dump ( struct FGMplayMsg *msg ) {
printf("mplay_msg (size %d id %d)\n",msg->header.len, msg->header.id);
printf(" reply_addr %d\n", msg->header.reply_addr);
printf(" reply_port %d\n", msg->header.reply_port);
printf(" callsign ");
int i;
for (i=0; i < MP_MAX_CALLSIGN_LEN; i++) {
printf("%c", msg->header.callsign[i]);
}
printf("\n");
printf(" model %-96s (%d)\n", msg->pos.model, strlen(msg->pos.model));
printf(" time %f lag %f\n", msg->pos.time, msg->pos.lag);
printf(" position %f %f %f\n", msg->pos.position[0], msg->pos.position[1], msg->pos.position[2]);
printf(" orientation %f %f %f %f\n", msg->pos.orientation[0], msg->pos.orientation[1], msg->pos.orientation[2], msg->pos.orientation[3]);
printf(" linear_vel %f %f %f\n", msg->pos.linear_vel[0], msg->pos.linear_vel[1], msg->pos.linear_vel[2]);
printf(" angular_vel %f %f %f\n", msg->pos.angular_vel[0], msg->pos.angular_vel[1], msg->pos.angular_vel[2]);
printf(" linear_accel %f %f %f\n", msg->pos.linear_accel[0], msg->pos.linear_accel[1], msg->pos.linear_accel[2]);
printf(" angular_accel %f %f %f\n", msg->pos.angular_accel[0], msg->pos.angular_accel[1], msg->pos.angular_accel[2]);
printf("sizeof %d\n", sizeof(struct FGMplayMsg));
}
void mplay_msg_ntoh ( struct FGMplayMsg* msg) {
msg->header.magic = ntohl(msg->header.magic);
msg->header.version = ntohl(msg->header.version);
msg->header.id = ntohl(msg->header.id);
msg->header.len = ntohl(msg->header.len);
msg->header.reply_addr = ntohl(msg->header.reply_addr);
msg->header.reply_port = ntohl(msg->header.reply_port);
htond(&msg->pos.time);
htond(&msg->pos.lag);
htond(&msg->pos.position[0]);
htond(&msg->pos.position[1]);
htond(&msg->pos.position[2]);
htonf(&msg->pos.orientation[0]);
htonf(&msg->pos.orientation[1]);
htonf(&msg->pos.orientation[2]);
htonf(&msg->pos.orientation[3]);
htonf(&msg->pos.linear_vel[0]);
htonf(&msg->pos.linear_vel[1]);
htonf(&msg->pos.linear_vel[2]);
htonf(&msg->pos.angular_vel[0]);
htonf(&msg->pos.angular_vel[1]);
htonf(&msg->pos.angular_vel[2]);
htonf(&msg->pos.linear_accel[0]);
htonf(&msg->pos.linear_accel[1]);
htonf(&msg->pos.linear_accel[2]);
htonf(&msg->pos.angular_accel[0]);
htonf(&msg->pos.angular_accel[1]);
htonf(&msg->pos.angular_accel[2]);
}
void mplay_msg_init ( struct FGMplayMsg* msg) {
msg->header.magic = MP_MSG_MAGIC;
msg->header.version = MP_PROTO_VER;
msg->header.id = 7;
msg->header.len = 232;
}
-43
View File
@@ -1,43 +0,0 @@
#ifndef FLIGHT_GEAR_H
#define FLIGHT_GEAR_H
#include <stdint.h>
#include "../simulator/flight_gear.h"
#define MP_MAX_CALLSIGN_LEN 8
#define MP_MAX_MODEL_NAME_LEN 96
#define MP_MSG_MAGIC 0x46474653
#define MP_PROTO_VER 0x00010001
struct FGMplayHdr {
uint32_t magic;
uint32_t version;
uint32_t id;
uint32_t len;
uint32_t reply_addr;
uint32_t reply_port;
char callsign[MP_MAX_CALLSIGN_LEN];
};
struct FGMplayPosMsg {
char model[MP_MAX_MODEL_NAME_LEN];
double time;
double lag;
double position[3];
float orientation[4];
float linear_vel[3];
float angular_vel[3];
float linear_accel[3];
float angular_accel[3];
};
struct FGMplayMsg {
struct FGMplayHdr header;
struct FGMplayPosMsg pos;
};
extern void mplay_msg_dump ( struct FGMplayMsg *msg );
extern void mplay_msg_ntoh ( struct FGMplayMsg* msg );
extern void mplay_msg_init ( struct FGMplayMsg* msg );
#endif /* FLIGHT_GEAR_H */
-38
View File
@@ -1,38 +0,0 @@
#include "network.h"
#include <netdb.h>
#include <netinet/in.h>
#include <stdlib.h>
#include <stdio.h>
struct FgNetChannel* open_out_channel( char* host, uint16_t port) {
struct FgNetChannel* chan = malloc(sizeof (struct FgNetChannel));
int so_reuseaddr = 1;
struct protoent * pte = getprotobyname("UDP");
chan->socket = socket( PF_INET, SOCK_DGRAM, pte->p_proto);
setsockopt(chan->socket, SOL_SOCKET, SO_REUSEADDR,
&so_reuseaddr, sizeof(so_reuseaddr));
chan->addr.sin_family = PF_INET;
chan->addr.sin_port = htons(port);
chan->addr.sin_addr.s_addr = inet_addr(host);
return chan;
}
struct FgNetChannel* open_in_channel( char* host, uint16_t port) {
struct FgNetChannel* chan = open_out_channel(host, port);
int ret = bind(chan->socket, (struct sockaddr*)&chan->addr, sizeof(chan->addr));
if (ret)
perror("binding\n");
return chan;
}
void send_buf(struct FgNetChannel* chan, char* buf, int len) {
if (sendto(chan->socket, buf, len, 0,
(struct sockaddr*)&chan->addr, sizeof(chan->addr)) == -1)
printf("error sending\n");
}
-18
View File
@@ -1,18 +0,0 @@
#ifndef NETWORK_H
#define NETWORK_H
#include <inttypes.h>
#include <sys/socket.h>
#include <arpa/inet.h>
struct FgNetChannel {
int socket;
struct sockaddr_in addr;
};
extern struct FgNetChannel* open_out_channel( char* host, uint16_t port );
extern struct FgNetChannel* open_in_channel( char* host, uint16_t port );
extern void send_buf(struct FgNetChannel* chan, char* buf, int len);
#endif /* NETWORK_H */
-200
View File
@@ -1,200 +0,0 @@
/*
This is a quick hack - just to show how it might work. It gives a 3D view of
the GPS positions with an additional value (here: attitude phi) as colour.
Start this with your favorite .data telemetry file as argument and pipe it
to output.dat, then run gnuplot with:
#set terminal png nocrop enhanced size 800,600
#set output 'output.png'
set view 64, 8, 1, 1
set isosamples 50, 10
set hidden3d offset 1 trianglepattern 3 undefined 1 altdiagonal bentover
set palette
set xlabel "m"
set ylabel "m"
set zlabel "m"
splot "output.dat" using 1:2:3:4 title "roll" with linespoints palette
pause -1
*/
#include <stdio.h>
#include <stdlib.h>
#include <fcntl.h>
#include <stdarg.h>
#include <string.h>
#include <unistd.h>
#include <math.h>
#include <sys/time.h>
int main( int argc, char* argv[] )
{
/*
<message name="GPS" ID="8">
<field name="mode" type="uint8" unit="byte_mask"></field>
<field name="utm_east" type="int32" unit="cm"></field>
<field name="utm_north" type="int32" unit="cm"></field>
<field name="course" type="int16" unit="decideg"></field>
<field name="alt" type="int32" unit="cm"></field>
<field name="speed" type="uint16" unit="cm/s"></field>
<field name="climb" type="int16" unit="cm/s"></field>
<field name="itow" type="uint32" unit="ms"></field>
<field name="utm_zone" type="uint8"></field>
<field name="gps_nb_err" type="uint8"></field>
</message>
7.73 11 GPS 0 55577549 665183336 0 -4310 0 0 345957748 31 0
<message name="ATTITUDE" ID="6">
<field name="phi" type="int16" unit="deg"></field>
<field name="psi" type="int16" unit="deg"></field>
<field name="theta" type="int16" unit="deg"></field>
</message>
230.41 23 ATTITUDE -22 0 -4
<message name="NAVIGATION_REF" ID="0x09">
<field name="utm_east" type="int32" unit="m"></field>
<field name="utm_north" type="int32" unit="m"></field>
<field name="utm_zone" type="uint8"></field>
</message>
7.77 23 NAVIGATION_REF 567835 5790977 32
*/
char line_in[256];
float rtime;
char id_name[255];
unsigned int ac_id;
unsigned int byte_mask;
int utm_east;
int utm_north;
int course;
int alt;
int speed;
int climb;
unsigned int itow;
unsigned int utm_zone;
unsigned int gps_nb_err;
unsigned int phi;
unsigned int psi;
unsigned int theta;
unsigned int nr_utm_east;
unsigned int nr_utm_north;
unsigned int nr_utm_zone;
unsigned int humid;
unsigned int temp;
char got_navref = 0;
FILE *fd;
if (argc != 2)
{
printf("plot3dparse 'flight_file.data' > output.dat\n");
exit(0);
}
fd = fopen( argv[1], "r" );
if (!fd) exit(0);
while (!feof(fd))
{
fgets( line_in, 256, fd );
if (sscanf( line_in, "%e %i %s", &rtime, &ac_id, id_name ))
{
if (!strcmp( "NAVIGATION_REF", id_name))
{
sscanf( line_in, "%e %i %s %i %i %i\n",
&rtime,
&ac_id,
id_name,
&nr_utm_east,
&nr_utm_north,
&nr_utm_zone );
got_navref = 1;
}
#if 0
if (!strcmp( "DPICCO_STATUS", id_name))
{
#define DPICCO_HUMID_MAX 0x7FFF
#define DPICCO_HUMID_RANGE 100.0
#define DPICCO_TEMP_MAX 0x7FFF
#define DPICCO_TEMP_RANGE 165.0
#define DPICCO_TEMP_OFFS -40.0
float fhumid, ftemp;
sscanf( line_in, "%e %i %s %i %i %e %e\n",
&rtime,
&ac_id,
id_name,
&humid,
&temp );
fhumid = (dpicco_val[0] * DPICCO_HUMID_RANGE) / DPICCO_HUMID_MAX;
ftemp = ((dpicco_val[1] * DPICCO_TEMP_RANGE) / DPICCO_TEMP_MAX) + DPICCO_TEMP_OFFS;
if (temp != 0) printf("%f %f %f\n", rtime, fhumid, ftemp);
}
#endif
if (!strcmp( "GPS", id_name))
{
sscanf( line_in, "%e %i %s %i %i %i %i %i %i %i %i %i %i\n",
&rtime,
&ac_id,
id_name,
&byte_mask,
&utm_east,
&utm_north,
&course,
&alt,
&speed,
&climb,
&itow,
&utm_zone,
&gps_nb_err );
}
if (!strcmp( "ATTITUDE", id_name))
{
sscanf( line_in, "%e %i %s %i %i %i\n",
&rtime,
&ac_id,
id_name,
&phi,
&psi,
&theta );
if (got_navref) printf("%i %i %i %i\n\n",
utm_east/100 - nr_utm_east,
utm_north/100 - nr_utm_north,
alt / 100,
phi );
}
}
}
fclose( fd );
return(0);
}
-138
View File
@@ -1,138 +0,0 @@
/*
http://users.softlab.ntua.gr/~ttsiod/gnuplotStreaming.html
*/
#include <stdio.h>
#include <stdlib.h>
#include <fcntl.h>
#include <stdarg.h>
#include <string.h>
#include <unistd.h>
#include <math.h>
#include <inttypes.h>
#include <sys/time.h>
#include <glib.h>
#include <Ivy/ivy.h>
#include <Ivy/ivyglibloop.h>
#define HEIGHT_SPAN 20000
FILE *Gplt, *Gplh;
int32_t alt = 0;
int32_t temp[HEIGHT_SPAN] = {0};
int32_t humid[HEIGHT_SPAN] = {0};
void on_GPS(IvyClientPtr app, void *user_data, int argc, char *argv[]){
/*
<message name="GPS" id="8">
<field name="mode" type="uint8" unit="byte_mask"/>
<field name="utm_east" type="int32" unit="cm" alt_unit="m"/>
<field name="utm_north" type="int32" unit="cm" alt_unit="m"/>
<field name="course" type="int16" unit="decideg" alt_unit="deg"/>
<field name="alt" type="int32" unit="cm" alt_unit="m"/>
<field name="speed" type="uint16" unit="cm/s" alt_unit="m/s"/>
<field name="climb" type="int16" unit="cm/s" alt_unit="m/s"/>
<field name="week" type="uint16" unit="weeks"></field>
<field name="itow" type="uint32" unit="ms"/>
<field name="utm_zone" type="uint8"/>
<field name="gps_nb_err" type="uint8"/>
</message>
7.73 11 GPS 0 55577549 665183336 0 -4310 0 0 1642 345957748 31 0
*/
int32_t _alt;
_alt = atoi(argv[5]);
alt = _alt / 100;
// if ((_alt/100) < HEIGHT_SPAN) alt = _alt;
// printf("alt %f\n", (float) _alt/100.);
}
void on_TMP_STATUS(IvyClientPtr app, void *user_data, int argc, char *argv[]){
/*
<message name="TMP_STATUS" id="86">
<field name="itemp" type="uint16"/>
<field name="temp" type="float" unit="deg_celsius" format="%.2f"/>
</message>
*/
float _temp;
int i;
_temp = atof(argv[2]);
if (alt < HEIGHT_SPAN) temp[alt] = _temp * 100;
// printf("temp %f\n", _temp);
fprintf(Gplt, "plot '-' w points pt 0 title \"Temp\"\n");
for (i = 0; i < HEIGHT_SPAN; i++){
if (temp[i] != 0) fprintf(Gplt, "%f %d\n", temp[i]/100., i);
}
fprintf(Gplt,"e\n");
}
void on_SHT_STATUS(IvyClientPtr app, void *user_data, int argc, char *argv[]){
/*
<message name="SHT_STATUS" id="89">
<field name="ihumid" type="uint16"/>
<field name="itemp" type="uint16"/>
<field name="humid" type="float" unit="rel_hum" format="%.2f"/>
<field name="temp" type="float" unit="deg_celsius" format="%.2f"/>
</message>
*/
float _humid;
int i;
_humid = atof(argv[3]);
if (alt < HEIGHT_SPAN) humid[alt] = _humid * 100;
// printf("humid %f\n", _humid);
fprintf(Gplh, "plot '-' w points pt 0 title \"Humid\"\n");
for (i = 0; i < HEIGHT_SPAN; i++){
if (humid[i] != 0) fprintf(Gplh, "%f %d\n", humid[i]/100., i);
}
fprintf(Gplh,"e\n");
}
int main( int argc, char* argv[] )
{
double xmint, xmaxt, xminh, xmaxh, ymin, ymax;
GMainLoop *ml;
ml = g_main_loop_new(NULL, FALSE);
IvyInit ("IvyPlotProfile", "IvyPlotProfile READY", NULL, NULL, NULL, NULL);
IvyBindMsg(on_GPS, NULL, "^(\\S*) GPS (\\S*) (\\S*) (\\S*) (\\S*) (\\S*) (\\S*) (\\S*) (\\S*) (\\S*) (\\S*) (\\S*)");
IvyBindMsg(on_TMP_STATUS, NULL, "^(\\S*) TMP_STATUS (\\S*) (\\S*)");
IvyBindMsg(on_SHT_STATUS, NULL, "^(\\S*) SHT_STATUS (\\S*) (\\S*) (\\S*) (\\S*)");
// IvyBindMsg(on_SHT_STATUS, NULL, "^(\\S*) DPICCO_STATUS (\\S*) (\\S*) (\\S*) (\\S*)");
IvyStart("127.255.255.255");
xmint = 5;
xmaxt = 35;
xminh = 0;
xmaxh = 100;
ymin = 500;
ymax = 2300;
Gplt = popen("gnuplot -geometry 300x300 -noraise","w");
setlinebuf(Gplt);
fprintf(Gplt, "set xrange[%f:%f]\n", xmint, xmaxt);
fprintf(Gplt, "set yrange[%f:%f]\n", ymin, ymax);
Gplh = popen("gnuplot -geometry 300x300 -noraise","w");
setlinebuf(Gplh);
fprintf(Gplh, "set xrange[%f:%f]\n", xminh, xmaxh);
fprintf(Gplh, "set yrange[%f:%f]\n", ymin, ymax);
g_main_loop_run(ml);
fclose(Gplt);
fclose(Gplh);
return 0;
}
-83
View File
@@ -1,83 +0,0 @@
#include <gtkdatabox.h>
#include <gtkdatabox_points.h>
#include <gtkdatabox_lines.h>
#include <gtkdatabox_bars.h>
#include <gtkdatabox_grid.h>
#include <gtkdatabox_cross_simple.h>
#include <gtkdatabox_markers.h>
#include <string.h>
#define NB_POINTS 2000
#define NB_POINTS_BY_STEP 1
//500
const GdkColor colors[] = {{65535, 0, 0}, {0, 65535, 0}, {0, 0, 65535}, {0, 0, 0}};
#define NB_COLORS 4
#define REFRESH_RATE 166 /* ms */
static gboolean timeout_callback(gpointer data);
GtkWidget* sliding_plot_new(guint nb_plot) {
GtkWidget* databox = gtk_databox_new ();
g_object_set_data(G_OBJECT(databox), "nb_plot", (gpointer)nb_plot);
gfloat *X = g_new0 (gfloat, NB_POINTS);
g_object_set_data(G_OBJECT(databox), "X", X);
gpointer *Y = g_new0 (gpointer, nb_plot);
g_object_set_data(G_OBJECT(databox), "Y", Y);
guint nb_data = 0;
g_object_set_data(G_OBJECT(databox), "nb_data", (gpointer)nb_data);
guint _time = 0;
g_object_set_data(G_OBJECT(databox), "time", (gpointer)_time);
guint i;
for (i=0; i< nb_plot; i++) {
Y[i] = g_new0 (gfloat, NB_POINTS);
GtkDataboxGraph *graph = gtk_databox_lines_new (NB_POINTS, X, Y[i], (GdkColor*)&(colors[i%NB_COLORS]), 1);
gtk_databox_graph_add (GTK_DATABOX (databox), graph);
}
// GtkDataboxGraph *grid = gtk_databox_grid_new (10, 10, (GdkColor*)&(colors[3]), 2);
// gtk_databox_graph_add (GTK_DATABOX (databox), grid);
g_timeout_add(REFRESH_RATE, timeout_callback, databox);
return databox;
}
void sliding_plot_update(GtkWidget* plot, float* values) {
guint i, j;
gfloat *X = g_object_get_data(G_OBJECT(plot), "X");
gpointer *Y = g_object_get_data(G_OBJECT(plot), "Y");
guint nb_data = (guint)g_object_get_data(G_OBJECT(plot), "nb_data");
guint _time = (guint)g_object_get_data(G_OBJECT(plot), "time");
guint nb_plot = (guint)g_object_get_data(G_OBJECT(plot), "nb_plot");
if (nb_data >= NB_POINTS) {
nb_data -= NB_POINTS_BY_STEP;
guint mem_to_move = (NB_POINTS - NB_POINTS_BY_STEP)*sizeof(gfloat);
memmove(X, &(X[NB_POINTS_BY_STEP]), mem_to_move);
for (i=0; i< nb_plot; i++) {
gfloat* y = Y[i];
memmove(y, &(y[NB_POINTS_BY_STEP]), mem_to_move);
}
}
for (j=nb_data; j< NB_POINTS; j++) {
X[j] = _time;
for (i=0; i< nb_plot; i++) {
gfloat* y = Y[i];
y[j] = values[i];
}
}
_time++;
g_object_set_data(G_OBJECT(plot), "time", (gpointer)_time);
nb_data++;
g_object_set_data(G_OBJECT(plot), "nb_data", (gpointer)nb_data);
// gtk_databox_auto_rescale (GTK_DATABOX (plot), 0.);
}
static gboolean timeout_callback(gpointer user_data) {
GtkDatabox* databox = GTK_DATABOX (user_data);
gtk_databox_auto_rescale (databox, 0.);
return TRUE;
}
-9
View File
@@ -1,9 +0,0 @@
#ifndef SLIDING_PLOT_H
#define SLIDING_PLOT_H
#include <gtk/gtk.h>
extern GtkWidget* sliding_plot_new(guint nb_plot);
extern void sliding_plot_update(GtkWidget* plot, float* values);
#endif /* SLIDING_PLOT_H */
-131
View File
@@ -1,131 +0,0 @@
/* $Id$
*
* tmclient, an telemetry client to distribute paparazzi location data
* Copyright (C) 2007 Martin Mueller <martinmm@pfump.org>
*
* This file is part of paparazzi.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with paparazzi; see the file COPYING. If not, write to
* the Free Software Foundation, 59 Temple Place - Suite 330,
* Boston, MA 02111-1307, USA.
*
*/
#include <sys/types.h>
#include <sys/socket.h>
#include <netinet/in.h>
#include <arpa/inet.h>
#include <netdb.h>
#include <stdio.h>
#include <string.h>
#include <stdlib.h>
#include <stdio.h>
#include <unistd.h>
#include <glib.h>
#include <Ivy/ivy.h>
#include <Ivy/ivyglibloop.h>
#define PORT 7123
#define HOSTADDR "localhost"
#define PACKET_SIZE 9
int sock, length;
struct sockaddr_in server;
char hostaddr[4096] = {HOSTADDR};
unsigned int uvalue[PACKET_SIZE];
unsigned char cvalue[4*PACKET_SIZE];
static const char usage_str[] =
"client [options]\n"
"options:\n"
" -s HOST server address\n";
void on_FLIGHT_PARAM_STATUS(IvyClientPtr app, void *user_data, int argc, char *argv[])
{
int count, cnt;
float ftemp;
if (argc != 10) return;
uvalue[0] = 42;//atoi(argv[0]);
cvalue[0] = uvalue[0] & 0xFF;
cvalue[1] = 0;
cvalue[2] = 'P';
cvalue[3] = 'Z';
for (count=1; count < PACKET_SIZE; count++) {
ftemp = atof(argv[count]);
uvalue[count] = *(unsigned int*) &ftemp;
uvalue[count] = htonl(uvalue[count]);
for (cnt=0; cnt<4; cnt++) {
cvalue[count*4 + cnt] = (uvalue[count] >> (cnt*8)) & 0xFF;
}
}
/* send data as binary 32bit floats through UDP */
count = sendto(sock, cvalue, PACKET_SIZE*4, 0, (struct sockaddr*) &server, length);
if (count != PACKET_SIZE*4) perror("sendto");
}
int main ( int argc, char** argv) {
struct hostent *hent;
int c;
GMainLoop *ml = g_main_loop_new(NULL, FALSE);
while ((c = getopt(argc, argv, "h:s:")) != EOF) {
switch (c) {
case 'h':
printf(usage_str);
break;
case 's':
strncpy(hostaddr, optarg, strlen(optarg)+1);
break;
}
}
IvyInit ("IvyFlightParams", "IvyFlightParams READY", NULL, NULL, NULL, NULL);
IvyBindMsg(on_FLIGHT_PARAM_STATUS, NULL, "^\\S* FLIGHT_PARAM (\\S*) (\\S*) (\\S*) (\\S*) (\\S*) (\\S*) (\\S*) (\\S*) (\\S*) (\\S*)");
IvyStart("127.255.255.255");
printf("Using server: %s\n", hostaddr);
sock= socket(AF_INET, SOCK_DGRAM, 0);
if (sock < 0) perror("socket");
server.sin_family = AF_INET;
hent = gethostbyname(hostaddr);
if (hent == 0) {
perror("unknown host %s");
exit(1);
}
memcpy((char *)&server.sin_addr,
(char *)hent->h_addr,
hent->h_length);
server.sin_port = htons(PORT);
length=sizeof(struct sockaddr_in);
g_main_loop_run(ml);
return 0;
}
-139
View File
@@ -1,139 +0,0 @@
/* $Id$
*
* tmdata, an telemetry client to distribute paparazzi location data
* Copyright (C) 2007 Martin Mueller <martinmm@pfump.org>
*
* This file is part of paparazzi.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with paparazzi; see the file COPYING. If not, write to
* the Free Software Foundation, 59 Temple Place - Suite 330,
* Boston, MA 02111-1307, USA.
*
*/
#include <sys/types.h>
#include <sys/socket.h>
#include <sys/time.h>
#include <netinet/in.h>
#include <arpa/inet.h>
#include <netdb.h>
#include <stdio.h>
#include <string.h>
#include <stdlib.h>
#include <stdio.h>
#include <unistd.h>
#define PORT_OUT 7124
#define HOSTADDR "localhost"
#define BUFSIZE 0x10000
int sock, length, fromlen;
struct sockaddr_in server;
char hostaddr[4096] = {HOSTADDR};
static const char usage_str[] =
"tmdata [options] [parameter]\n"
"options:\n"
" -s HOST server address\n";
int main ( int argc, char** argv) {
struct hostent *hent;
char buf[BUFSIZE];
int c, count;
fd_set fds;
struct timeval tvt;
char noparam = 0;
char *param = &noparam;
while ((c = getopt(argc, argv, "hs:")) != EOF)
{
switch (c)
{
case 'h':
printf(usage_str);
break;
case 's':
strncpy(hostaddr, optarg, strlen(optarg)+1);
break;
}
}
if (argv[optind])
{
param = argv[optind];
}
sock = socket(PF_INET, SOCK_STREAM, 0);
if (sock < 0)
{
perror("socket");
exit(1);
}
server.sin_family = AF_INET;
hent = gethostbyname(hostaddr);
if (hent == 0)
{
perror("unknown host");
exit(1);
}
memcpy((char *)hent->h_addr,
(char *)&server.sin_addr,
hent->h_length);
server.sin_port = htons(PORT_OUT);
length=sizeof(struct sockaddr_in);
if (connect(sock, &server, length))
{
perror("connect");
exit(1);
}
/* send some data to trigger output */
count = send(sock, param, strlen(param), 0);
/* we will wait for data 500ms */
tvt.tv_sec = 0;
tvt.tv_usec = 500000;
FD_CLEAR(&fds);
FD_SET(sock, &fds);
count = select(sock+1, &fds, NULL, NULL, &tvt);
if (count > 0)
{
/* receive data packet containing formatted data */
count = recv(sock, buf, sizeof(buf), 0);
if (count < 0)
{
perror("recv");
exit(1);
}
write(1, buf, count);
}
else
{
perror("select");
}
return 0;
}
-378
View File
@@ -1,378 +0,0 @@
/* $Id$
*
* tmserver, an telemetry server to distribute paparazzi location data
* Copyright (C) 2007 Martin Mueller <martinmm@pfump.org>
*
* This file is part of paparazzi.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with paparazzi; see the file COPYING. If not, write to
* the Free Software Foundation, 59 Temple Place - Suite 330,
* Boston, MA 02111-1307, USA.
*
*/
#include <unistd.h>
#include <error.h>
#include <sys/time.h>
#include <sys/types.h>
#include <sys/socket.h>
#include <netinet/in.h>
#include <netdb.h>
#include <stdio.h>
#include <string.h>
#include <stdlib.h>
#define MAX(a, b) ((a > b) ? a : b)
#define PORT_IN 7123
#define PORT_OUT 7124
#define BUFSIZE 0x10000
#define PACKET_SIZE 9
#define AC_NUM 10
#define AC_TIMEOUT 5
typedef struct
{
long addr;
struct timeval tvvalid;
unsigned char ac_id;
float fval[PACKET_SIZE];
} ac_dat_t;
static char ppfg[] = {"ppfg"};
static char ppua[] = {"ppua"};
static char ppac[] = {"ppac"};
int getac(ac_dat_t * ac_dati, unsigned char ac_id, long addr)
{
int count;
for(count=0; count < AC_NUM; count++)
{
if ((ac_dati[count].ac_id == ac_id) &&
(ac_dati[count].addr == addr))
{
return count;
}
}
for(count=0; count < AC_NUM; count++)
{
if (ac_dati[count].ac_id == 0) return count;
}
return -1;
}
int getnumac(ac_dat_t * ac_dati)
{
int count, num=0;
for(count=0; count < AC_NUM; count++)
{
if (ac_dati[count].ac_id != 0) num++;
}
return num;
}
int cleanupac(ac_dat_t * ac_dati)
{
int count, num=0;
struct timeval tvcur;
gettimeofday(&tvcur, NULL);
for(count=0; count < AC_NUM; count++)
{
if (ac_dati[count].tvvalid.tv_sec + AC_TIMEOUT < tvcur.tv_sec)
{
ac_dati[count].ac_id = 0;
}
}
return num;
}
int main(int argc, char *argv[])
{
int length, fromlen, tolen, n, count, cnt, fdmax, ac;
int sourcesock, sinksock, consock;
struct sockaddr_in sourceaddr, sinkaddr, from;
char buf[BUFSIZE];
char *pbuf;
unsigned int itemp;
fd_set fds;
struct timeval tvt, tvcur;
ac_dat_t ac_dat[AC_NUM];
int on = 1;
memset(ac_dat, 0, sizeof(ac_dat));
/* open sockets */
sourcesock = socket(AF_INET, SOCK_DGRAM, 0);
sinksock = socket(PF_INET, SOCK_STREAM, 0);
consock = 0;
if ((sourcesock < 0) || (sinksock < 0))
{
perror("socket");
exit(1);
}
tolen = sizeof(struct sockaddr_in);
length = sizeof(sourceaddr);
memset(&sourceaddr, 0, sizeof(sourceaddr));
memset(&sinkaddr, 0, sizeof(sinkaddr));
sourceaddr.sin_family = AF_INET;
sourceaddr.sin_addr.s_addr = INADDR_ANY;
sourceaddr.sin_port = htons(PORT_IN);
sinkaddr.sin_family = AF_INET;
sinkaddr.sin_addr.s_addr = INADDR_ANY;
sinkaddr.sin_port = htons(PORT_OUT);
setsockopt(sinksock, SOL_SOCKET, SO_REUSEADDR, (void *)&on, sizeof(on)) ;
if ((bind(sourcesock, (struct sockaddr *)&sourceaddr, length) < 0) ||
(bind(sinksock, (struct sockaddr *)&sinkaddr, length) < 0))
{
perror("bind");
exit(1);
}
if (listen(sinksock, 3))
{
perror("listen");
exit(1);
}
fdmax = MAX(sourcesock, sinksock);
FD_ZERO(&fds);
while (1)
{
FD_SET(sourcesock, &fds);
FD_SET(sinksock, &fds);
/* loop every second */
tvt.tv_sec = 1;
tvt.tv_usec = 0;
count = select(fdmax+1, &fds, NULL, NULL, &tvt);
if (FD_ISSET(sourcesock, &fds))
{
gettimeofday(&tvcur, NULL);
n = recvfrom(sourcesock, buf, sizeof(buf), 0, (struct sockaddr *)&sourceaddr, &fromlen);
if (n < 0) perror("recvfrom");
if (n == PACKET_SIZE*4)
{
ac = getac(ac_dat, *(unsigned char*)(buf), ntohl(sourceaddr.sin_addr.s_addr));
if (ac >= 0)
{
ac_dat[ac].ac_id = *(unsigned char*)(buf);
ac_dat[ac].addr = ntohl(sourceaddr.sin_addr.s_addr);
ac_dat[ac].tvvalid.tv_sec = tvcur.tv_sec;
for (count=1; count<PACKET_SIZE; count++)
{
itemp = 0;
for (cnt=0; cnt<4; cnt++)
{
itemp |= (*(unsigned char*)(buf+count*4+cnt) << (cnt*8));
}
itemp = ntohl(itemp);
ac_dat[ac].fval[count] = *(float*) &itemp;
}
}
}
}
if (FD_ISSET(sinksock, &fds))
{
consock = accept(sinksock, (struct sockaddr *) &sinkaddr, &fromlen);
if (consock < 0)
{
perror("socket");
exit(1);
}
FD_SET(consock, &fds);
fdmax=MAX(fdmax, consock);
}
if (FD_ISSET(consock, &fds))
{
n = recv(consock, buf, sizeof(buf), 0);
if (n < 0) perror("recv");
if (strncmp(ppua, buf, 4) == 0)
{
pbuf = buf;
ac = getnumac(ac_dat);
pbuf += sprintf(pbuf,"Cache-Control: no-cache\n");
pbuf += sprintf(pbuf,"Pragma: no-cache\n");
pbuf += sprintf(pbuf,"Content-type: text/xml\n\n");
pbuf += sprintf(pbuf,"<?xml version=\"1.0\" encoding=\"UTF-8\" ?>\n");
pbuf += sprintf(pbuf,"<kml xmlns=\"http://earth.google.com/kml/2.1\">\n");
pbuf += sprintf(pbuf,"<NetworkLinkControl>\n");
pbuf += sprintf(pbuf," <Update>\n");
pbuf += sprintf(pbuf," <targetHref>http://localhost/maps/fg_server_xml.cgi?ppac</targetHref>\n");
for (count = 0; count < ac; count++)
{
if (ac_dat[count].ac_id > 0)
{
pbuf += sprintf(pbuf, " <Change>\n");
pbuf += sprintf(pbuf, " <Placemark targetId=\"%i\">\n", count);
#if 0
pbuf += sprintf(pbuf, " <LookAt>\n");
pbuf += sprintf(pbuf, " <longitude>%f</longitude>\n", ac_dat[count].fval[4]);
pbuf += sprintf(pbuf, " <latitude>%f</latitude>\n", ac_dat[count].fval[3]);
pbuf += sprintf(pbuf, " <altitude>%f</altitude>\n", ac_dat[count].fval[7]);
pbuf += sprintf(pbuf, " <range>100</range>\n");
pbuf += sprintf(pbuf, " <tilt>55</tilt>\n");
pbuf += sprintf(pbuf, " <heading>%f</heading>\n", ac_dat[count].fval[6]);
pbuf += sprintf(pbuf, " <altitudeMode>absolute</altitudeMode>\n");
pbuf += sprintf(pbuf, " </LookAt>\n");
#endif
pbuf += sprintf(pbuf, " <Model>\n");
pbuf += sprintf(pbuf, " <Location>\n");
pbuf += sprintf(pbuf, " <latitude>%f</latitude>\n", ac_dat[count].fval[3]);
pbuf += sprintf(pbuf, " <longitude>%f</longitude>\n", ac_dat[count].fval[4]);
pbuf += sprintf(pbuf, " <altitude>%f</altitude>\n", ac_dat[count].fval[7]);
pbuf += sprintf(pbuf, " </Location>\n");
pbuf += sprintf(pbuf, " <Orientation>\n");
pbuf += sprintf(pbuf, " <heading>%f</heading>\n", ac_dat[count].fval[6]);
pbuf += sprintf(pbuf, " <tilt>%f</tilt>\n", -ac_dat[count].fval[2]);
pbuf += sprintf(pbuf, " <roll>%f</roll>\n", -ac_dat[count].fval[1]);
pbuf += sprintf(pbuf, " </Orientation>\n");
pbuf += sprintf(pbuf, " </Model>\n");
pbuf += sprintf(pbuf, " </Placemark>\n");
pbuf += sprintf(pbuf, " </Change>\n");
}
}
pbuf += sprintf(pbuf, " </Update>\n");
pbuf += sprintf(pbuf, "</NetworkLinkControl>\n");
pbuf += sprintf(pbuf, "</kml>\n");
}
else if (strncmp(ppac, buf, 4) == 0)
{
pbuf = buf;
ac = getnumac(ac_dat);
pbuf += sprintf(pbuf,"Cache-Control: no-cache\n");
pbuf += sprintf(pbuf,"Pragma: no-cache\n");
pbuf += sprintf(pbuf,"Content-type: text/xml\n\n");
pbuf += sprintf(pbuf,"<?xml version=\"1.0\" encoding=\"UTF-8\" ?>\n");
pbuf += sprintf(pbuf,"<kml xmlns=\"http://earth.google.com/kml/2.1\">\n");
pbuf += sprintf(pbuf," <Document id=\"mpmap\">\n");
pbuf += sprintf(pbuf," <name>Paparazzi live aircrafts</name>\n");
pbuf += sprintf(pbuf," <visibility>1</visibility>\n");
for (count = 0; count < ac; count++)
{
if (ac_dat[count].ac_id > 0)
{
pbuf += sprintf(pbuf, " <Placemark id=\"%i\">\n", count);
pbuf += sprintf(pbuf, " <name>%i</name>\n", ac_dat[count].ac_id);
#if 0
pbuf += sprintf(pbuf, " <LookAt>\n");
pbuf += sprintf(pbuf, " <longitude>%f</longitude>\n", ac_dat[count].fval[4]);
pbuf += sprintf(pbuf, " <latitude>%f</latitude>\n", ac_dat[count].fval[3]);
pbuf += sprintf(pbuf, " <altitude>%f</altitude>\n", ac_dat[count].fval[7]);
pbuf += sprintf(pbuf, " <range>500</range>\n");
pbuf += sprintf(pbuf, " <tilt>55</tilt>\n");
pbuf += sprintf(pbuf, " <heading>%f</heading>\n", ac_dat[count].fval[7]);
pbuf += sprintf(pbuf, " <altitudeMode>absolute</altitudeMode>\n");
pbuf += sprintf(pbuf, " </LookAt>\n");
#endif
pbuf += sprintf(pbuf, " <description>Paparazzi</description>\n");
pbuf += sprintf(pbuf, " <Model>\n");
pbuf += sprintf(pbuf, " <altitudeMode>absolute</altitudeMode>\n");
pbuf += sprintf(pbuf, " <Location>\n");
pbuf += sprintf(pbuf, " <latitude>%f</latitude>\n", ac_dat[count].fval[3]);
pbuf += sprintf(pbuf, " <longitude>%f</longitude>\n", ac_dat[count].fval[4]);
pbuf += sprintf(pbuf, " <altitude>%f</altitude>\n", ac_dat[count].fval[7]);
pbuf += sprintf(pbuf, " </Location>\n");
pbuf += sprintf(pbuf, " <Orientation>\n");
pbuf += sprintf(pbuf, " <heading>%f</heading>\n", ac_dat[count].fval[6]);
pbuf += sprintf(pbuf, " <tilt>%f</tilt>\n", -ac_dat[count].fval[2]);
pbuf += sprintf(pbuf, " <roll>%f</roll>\n", -ac_dat[count].fval[1]);
pbuf += sprintf(pbuf, " </Orientation>\n");
pbuf += sprintf(pbuf, " <Scale>\n");
pbuf += sprintf(pbuf, " <x>150.0</x>\n");
pbuf += sprintf(pbuf, " <y>150.0</y>\n");
pbuf += sprintf(pbuf, " <z>150.0</z>\n");
pbuf += sprintf(pbuf, " </Scale>\n");
pbuf += sprintf(pbuf, " <Link>\n");
pbuf += sprintf(pbuf, " <href>http://localhost/maps/c172p.dae</href>\n");
pbuf += sprintf(pbuf, " <refreshMode>onChange</refreshMode>\n");
pbuf += sprintf(pbuf, " </Link>\n");
pbuf += sprintf(pbuf, " </Model>\n");
pbuf += sprintf(pbuf, " </Placemark>\n\n");
}
}
pbuf += sprintf(pbuf, " <NetworkLink id=\"fgmap_update\">\n");
pbuf += sprintf(pbuf, " <name>Update</name>\n");
pbuf += sprintf(pbuf, " <Link>\n");
pbuf += sprintf(pbuf, " <href>http://localhost/maps/fg_server_xml.cgi?ppua</href>\n");
pbuf += sprintf(pbuf, " <refreshMode>onInterval</refreshMode>\n");
pbuf += sprintf(pbuf, " <refreshInterval>1</refreshInterval>\n");
pbuf += sprintf(pbuf, " </Link>\n");
pbuf += sprintf(pbuf, " </NetworkLink>\n</Document>\n");
pbuf += sprintf(pbuf, "</kml>\n");
}
else //if strncmp(ppfg, buf, 4) == 0)
{
pbuf=buf;
ac = getnumac(ac_dat);
pbuf += sprintf(pbuf,"Cache-Control: no-cache\n");
pbuf += sprintf(pbuf,"Pragma: no-cache\n");
pbuf += sprintf(pbuf, "Content-type: text/xml\n\n<fg_server pilot_cnt=\"%d\">\n", ac);
for (count = 0; count < ac; count++)
{
if (ac_dat[count].ac_id > 0)
{
pbuf += sprintf(pbuf, "<marker callsign=\"%i\" server_ip=\"%u.%u.%u.%u\" model=\"c172p\" lat=\"%f\" lng=\"%f\" alt=\"%f\" heading=\"%f\" pitch=\"%f\" roll=\"%f\"/>\n",
ac_dat[count].ac_id,
(unsigned char)(ac_dat[count].addr >> 24),
(unsigned char)(ac_dat[count].addr >> 16),
(unsigned char)(ac_dat[count].addr >> 8),
(unsigned char)(ac_dat[count].addr & 0xff),
ac_dat[count].fval[3],
ac_dat[count].fval[4],
ac_dat[count].fval[7],
ac_dat[count].fval[6],
ac_dat[count].fval[2],
ac_dat[count].fval[1]);
}
}
pbuf += sprintf(pbuf, "</fg_server>\n");
}
// else buf[0]=0;
if (ntohl(sinkaddr.sin_addr.s_addr) == INADDR_LOOPBACK)
{
count = send(consock, buf, strlen(buf), 0);
}
close(consock);
FD_CLR(consock, &fds);
fdmax = MAX(sourcesock, sinksock);
}
cleanupac(ac_dat);
}
return 0;
}
-36
View File
@@ -1,36 +0,0 @@
#include "utils.h"
#include <netinet/in.h>
//#include <simgear/io/lowlevel.hxx> // endian tests
void htond (double *x)
{
// if ( sgIsLittleEndian() ) {
int *Double_Overlay;
int Holding_Buffer;
Double_Overlay = (int *) x;
Holding_Buffer = Double_Overlay [0];
Double_Overlay [0] = htonl (Double_Overlay [1]);
Double_Overlay [1] = htonl (Holding_Buffer);
// } else {
// return;
// }
}
// Float version
void htonf (float *x)
{
// if ( sgIsLittleEndian() ) {
int *Float_Overlay;
int Holding_Buffer;
Float_Overlay = (int *) x;
Holding_Buffer = Float_Overlay [0];
Float_Overlay [0] = htonl (Holding_Buffer);
// } else {
// return;
// }
}
-25
View File
@@ -1,25 +0,0 @@
#ifndef UTILS_H
#define UTILS_H
#include <math.h>
extern void htond (double *x);
extern void htonf (float *x);
#define RAD_OF_DEG(d) (d*M_PI/180.)
#define NORM_ANGLE_RAD(r) { \
while (r>2*M_PI) \
r -= 2*M_PI; \
while (r<0) \
r += 2*M_PI; \
}
#define NORM_ANGLE_DEG(d) { \
while (d>180) \
d -= 360; \
while (d<=-180) \
d += 360; \
}
#endif /* UTILS_H */