summaryrefslogtreecommitdiff
path: root/src/test
diff options
context:
space:
mode:
Diffstat (limited to 'src/test')
-rw-r--r--src/test/.gitignore4
-rw-r--r--src/test/Makefile24
-rw-r--r--src/test/ao_flight_test.c651
-rw-r--r--src/test/ao_gps_test.c16
-rw-r--r--src/test/ao_gps_test_skytraq.c17
-rw-r--r--src/test/ao_gps_test_ublox.c22
-rw-r--r--src/test/ao_int64_test.c115
-rw-r--r--src/test/ao_ms5607_convert_test.c96
-rw-r--r--src/test/ao_quaternion_test.c154
-rw-r--r--src/test/mega.flights12
-rwxr-xr-xsrc/test/plot-rot30
-rwxr-xr-xsrc/test/plotmm26
-rwxr-xr-xsrc/test/run-all-mm2
-rwxr-xr-xsrc/test/run-mm59
14 files changed, 810 insertions, 418 deletions
diff --git a/src/test/.gitignore b/src/test/.gitignore
index 90af6517..b8b2513e 100644
--- a/src/test/.gitignore
+++ b/src/test/.gitignore
@@ -5,6 +5,10 @@ ao_flight_test_baro
ao_flight_test_accel
ao_gps_test
ao_gps_test_skytraq
+ao_gps_test_ublox
+ao_int64_test
+ao_ms5607_convert_test
+ao_quaternion_test
ao_convert_test
ao_convert_pa_test
ao_fat_test
diff --git a/src/test/Makefile b/src/test/Makefile
index 76d50f16..7ae06a80 100644
--- a/src/test/Makefile
+++ b/src/test/Makefile
@@ -1,14 +1,15 @@
-vpath % ..:../core:../drivers:../util:../micropeak:../aes
+vpath % ..:../core:../drivers:../util:../micropeak:../aes:../product
PROGS=ao_flight_test ao_flight_test_baro ao_flight_test_accel ao_flight_test_noisy_accel ao_flight_test_mm \
ao_gps_test ao_gps_test_skytraq ao_gps_test_ublox ao_convert_test ao_convert_pa_test ao_fec_test \
- ao_aprs_test ao_micropeak_test ao_fat_test ao_aes_test
+ ao_aprs_test ao_micropeak_test ao_fat_test ao_aes_test ao_int64_test \
+ ao_ms5607_convert_test ao_quaternion_test
-INCS=ao_kalman.h ao_ms5607.h ao_log.h ao_data.h altitude-pa.h altitude.h
+INCS=ao_kalman.h ao_ms5607.h ao_log.h ao_data.h altitude-pa.h altitude.h ao_quaternion.h
KALMAN=make-kalman
-CFLAGS=-I.. -I. -I../core -I../drivers -I../micropeak -O0 -g -Wall
+CFLAGS=-I.. -I. -I../core -I../drivers -I../micropeak -I../product -O0 -g -Wall
all: $(PROGS) ao_aprs_data.wav
@@ -29,16 +30,16 @@ ao_flight_test_baro: ao_flight_test.c ao_host.h ao_flight.c ao_sample.c ao_kalm
ao_flight_test_accel: ao_flight_test.c ao_host.h ao_flight.c ao_sample.c ao_kalman.c $(INCS)
cc $(CFLAGS) -o $@ -DFORCE_ACCEL=1 ao_flight_test.c
-ao_flight_test_mm: ao_flight_test.c ao_host.h ao_flight.c ao_sample.c ao_kalman.c $(INCS)
+ao_flight_test_mm: ao_flight_test.c ao_host.h ao_flight.c ao_sample.c ao_kalman.c ao_pyro.c ao_pyro.h $(INCS)
cc -DTELEMEGA=1 $(CFLAGS) -o $@ $< -lm
ao_gps_test: ao_gps_test.c ao_gps_sirf.c ao_gps_print.c ao_host.h
cc $(CFLAGS) -o $@ $<
-ao_gps_test_skytraq: ao_gps_test_skytraq.c ao_gps_skytraq.c ao_gps_print.c ao_host.h
+ao_gps_test_skytraq: ao_gps_test_skytraq.c ao_gps_skytraq.c ao_gps_print.c ao_gps_show.c ao_host.h
cc $(CFLAGS) -o $@ $<
-ao_gps_test_ublox: ao_gps_test_ublox.c ao_gps_ublox.c ao_gps_print.c ao_host.h ao_gps_ublox.h
+ao_gps_test_ublox: ao_gps_test_ublox.c ao_gps_ublox.c ao_gps_print.c ao_gps_show.c ao_host.h ao_gps_ublox.h
cc $(CFLAGS) -o $@ $<
ao_convert_test: ao_convert_test.c ao_convert.c altitude.h
@@ -73,3 +74,12 @@ ao_fat_test: ao_fat_test.c ao_fat.c ao_bufio.c
ao_aes_test: ao_aes_test.c ao_aes.c ao_aes_tables.c
cc $(CFLAGS) -o $@ ao_aes_test.c
+
+ao_int64_test: ao_int64_test.c ao_int64.c ao_int64.h
+ cc $(CFLAGS) -o $@ ao_int64_test.c
+
+ao_ms5607_convert_test: ao_ms5607_convert_test.c ao_ms5607_convert_8051.c ao_int64.c ao_int64.h
+ cc $(CFLAGS) -o $@ ao_ms5607_convert_test.c
+
+ao_quaternion_test: ao_quaternion_test.c ao_quaternion.h
+ cc $(CFLAGS) -o $@ ao_quaternion_test.c -lm
diff --git a/src/test/ao_flight_test.c b/src/test/ao_flight_test.c
index 99bed7ee..0abb4090 100644
--- a/src/test/ao_flight_test.c
+++ b/src/test/ao_flight_test.c
@@ -20,10 +20,13 @@
#include <stdint.h>
#include <stdio.h>
#include <stdlib.h>
+#include <stddef.h>
#include <string.h>
#include <getopt.h>
#include <math.h>
+#define GRAVITY 9.80665
+
#define AO_HERTZ 100
#define HAS_ADC 1
@@ -35,11 +38,17 @@
#define AO_MS_TO_SPEED(ms) ((int16_t) ((ms) * 16))
#define AO_MSS_TO_ACCEL(mss) ((int16_t) ((mss) * 16))
+#define AO_GPS_NEW_DATA 1
+#define AO_GPS_NEW_TRACKING 2
+
+int ao_gps_new;
+
#if TELEMEGA
#define AO_ADC_NUM_SENSE 6
#define HAS_MS5607 1
#define HAS_MPU6000 1
#define HAS_MMA655X 1
+#define HAS_HMC5883 1
struct ao_adc {
int16_t sense[AO_ADC_NUM_SENSE];
@@ -83,6 +92,95 @@ struct ao_adc {
#include <ao_data.h>
#include <ao_log.h>
+#include <ao_telemetry.h>
+
+#if TELEMEGA
+int ao_gps_count;
+struct ao_telemetry_location ao_gps_first;
+struct ao_telemetry_location ao_gps_prev;
+struct ao_telemetry_location ao_gps_static;
+
+struct ao_telemetry_satellite ao_gps_tracking;
+
+static inline double sqr(double a) { return a * a; }
+
+void
+cc_great_circle (double start_lat, double start_lon,
+ double end_lat, double end_lon,
+ double *dist, double *bearing)
+{
+ const double rad = M_PI / 180;
+ const double earth_radius = 6371.2 * 1000; /* in meters */
+ double lat1 = rad * start_lat;
+ double lon1 = rad * -start_lon;
+ double lat2 = rad * end_lat;
+ double lon2 = rad * -end_lon;
+
+// double d_lat = lat2 - lat1;
+ double d_lon = lon2 - lon1;
+
+ /* From http://en.wikipedia.org/wiki/Great-circle_distance */
+ double vdn = sqrt(sqr(cos(lat2) * sin(d_lon)) +
+ sqr(cos(lat1) * sin(lat2) -
+ sin(lat1) * cos(lat2) * cos(d_lon)));
+ double vdd = sin(lat1) * sin(lat2) + cos(lat1) * cos(lat2) * cos(d_lon);
+ double d = atan2(vdn,vdd);
+ double course;
+
+ if (cos(lat1) < 1e-20) {
+ if (lat1 > 0)
+ course = M_PI;
+ else
+ course = -M_PI;
+ } else {
+ if (d < 1e-10)
+ course = 0;
+ else
+ course = acos((sin(lat2)-sin(lat1)*cos(d)) /
+ (sin(d)*cos(lat1)));
+ if (sin(lon2-lon1) > 0)
+ course = 2 * M_PI-course;
+ }
+ *dist = d * earth_radius;
+ *bearing = course * 180/M_PI;
+}
+
+double
+ao_distance_from_pad(void)
+{
+ double dist, bearing;
+ if (!ao_gps_count)
+ return 0;
+
+ cc_great_circle(ao_gps_first.latitude / 1e7,
+ ao_gps_first.longitude / 1e7,
+ ao_gps_static.latitude / 1e7,
+ ao_gps_static.longitude / 1e7,
+ &dist, &bearing);
+ return dist;
+}
+
+double
+ao_gps_angle(void)
+{
+ double dist, bearing;
+ double height;
+ double angle;
+
+ if (ao_gps_count < 2)
+ return 0;
+
+ cc_great_circle(ao_gps_prev.latitude / 1e7,
+ ao_gps_prev.longitude / 1e7,
+ ao_gps_static.latitude / 1e7,
+ ao_gps_static.longitude / 1e7,
+ &dist, &bearing);
+ height = ao_gps_static.altitude - ao_gps_prev.altitude;
+
+ angle = atan2(dist, height);
+ return angle * 180/M_PI;
+}
+#endif
#define to_fix16(x) ((int16_t) ((x) * 65536.0 + 0.5))
#define to_fix32(x) ((int32_t) ((x) * 65536.0 + 0.5))
@@ -120,6 +218,7 @@ int ao_summary = 0;
#define ao_rdf_set(rdf)
#define ao_packet_slave_start()
#define ao_packet_slave_stop()
+#define flush()
enum ao_igniter {
ao_igniter_drogue = 0,
@@ -137,6 +236,18 @@ int tick_offset;
static int32_t ao_k_height;
+int16_t
+ao_time(void)
+{
+ return ao_data_static.tick;
+}
+
+void
+ao_delay(int16_t interval)
+{
+ return;
+}
+
void
ao_ignite(enum ao_igniter igniter)
{
@@ -200,6 +311,8 @@ struct ao_cmds {
#include <ao_ms5607.h>
struct ao_ms5607_prom ms5607_prom;
#include "ao_ms5607_convert.c"
+#define AO_PYRO_NUM 4
+#include <ao_pyro.h>
#else
#include "ao_convert.c"
#endif
@@ -210,6 +323,12 @@ struct ao_config {
int16_t accel_minus_g;
uint8_t pad_orientation;
uint16_t apogee_lockout;
+#if TELEMEGA
+ struct ao_pyro pyro[AO_PYRO_NUM]; /* minor version 12 */
+ int16_t accel_zero_along;
+ int16_t accel_zero_across;
+ int16_t accel_zero_through;
+#endif
};
#define AO_PAD_ORIENTATION_ANTENNA_UP 0
@@ -222,7 +341,6 @@ struct ao_config ao_config;
#define DATA_TO_XDATA(x) (x)
-#define GRAVITY 9.80665
extern int16_t ao_ground_accel, ao_flight_accel;
extern int16_t ao_accel_2g;
@@ -246,6 +364,22 @@ uint16_t prev_tick;
#include "ao_sqrt.c"
#include "ao_sample.c"
#include "ao_flight.c"
+#if TELEMEGA
+#define AO_PYRO_NUM 4
+
+#define AO_PYRO_0 0
+#define AO_PYRO_1 1
+#define AO_PYRO_2 2
+#define AO_PYRO_3 3
+
+static void
+ao_pyro_pin_set(uint8_t pin, uint8_t value)
+{
+ printf ("set pyro %d %d\n", pin, value);
+}
+
+#include "ao_pyro.c"
+#endif
#define to_double(f) ((f) / 65536.0)
@@ -305,17 +439,20 @@ ao_test_exit(void)
exit(0);
}
-#if HAS_MPU6000
-static double
-ao_mpu6000_accel(int16_t sensor)
-{
- return sensor / 32767.0 * MPU6000_ACCEL_FULLSCALE * GRAVITY;
-}
+#ifdef TELEMEGA
+struct ao_azel {
+ int az;
+ int el;
+};
-static double
-ao_mpu6000_gyro(int32_t sensor)
+static void
+azel (struct ao_azel *r, struct ao_quaternion *q)
{
- return sensor / 32767.0 * MPU6000_GYRO_FULLSCALE;
+ double v;
+
+ r->az = floor (atan2(q->y, q->x) * 180/M_PI + 0.5);
+ v = sqrt (q->x*q->x + q->y*q->y);
+ r->el = floor (atan2(q->z, v) * 180/M_PI + 0.5);
}
#endif
@@ -342,6 +479,7 @@ ao_insert(void)
double height = ao_pres_to_altitude(ao_data_static.adc.pres_real) - ao_ground_height;
#endif
+ (void) accel;
if (!tick_offset)
tick_offset = -ao_data_static.tick;
if ((prev_tick - ao_data_static.tick) > 0x400)
@@ -372,25 +510,115 @@ ao_insert(void)
}
if (!ao_summary) {
+#if TELEMEGA
+ static struct ao_quaternion ao_ground_mag;
+ static int ao_ground_mag_set;
+
+ if (!ao_ground_mag_set) {
+ ao_quaternion_init_vector (&ao_ground_mag,
+ ao_data_mag_across(&ao_data_static),
+ ao_data_mag_through(&ao_data_static),
+ ao_data_mag_along(&ao_data_static));
+ ao_quaternion_normalize(&ao_ground_mag, &ao_ground_mag);
+ ao_quaternion_rotate(&ao_ground_mag, &ao_ground_mag, &ao_rotation);
+ ao_ground_mag_set = 1;
+ }
+
+ struct ao_quaternion ao_mag, ao_mag_rot;
+
+ ao_quaternion_init_vector(&ao_mag,
+ ao_data_mag_across(&ao_data_static),
+ ao_data_mag_through(&ao_data_static),
+ ao_data_mag_along(&ao_data_static));
+
+ ao_quaternion_normalize(&ao_mag, &ao_mag);
+ ao_quaternion_rotate(&ao_mag_rot, &ao_mag, &ao_rotation);
+
+ float ao_dot;
+ int ao_mag_angle;
+
+ ao_dot = ao_quaternion_dot(&ao_mag_rot, &ao_ground_mag);
+
+ struct ao_azel ground_azel, mag_azel, rot_azel;
+
+ azel(&ground_azel, &ao_ground_mag);
+ azel(&mag_azel, &ao_mag);
+ azel(&rot_azel, &ao_mag_rot);
+
+ ao_mag_angle = floor (acos(ao_dot) * 180 / M_PI + 0.5);
+
+ (void) ao_mag_angle;
+
+ static struct ao_quaternion ao_x = { .r = 0, .x = 1, .y = 0, .z = 0 };
+ struct ao_quaternion ao_out;
+
+ ao_quaternion_rotate(&ao_out, &ao_x, &ao_rotation);
+
+ int out = floor (atan2(ao_out.y, ao_out.x) * 180 / M_PI);
+
+#if 0
+ printf ("%7.2f state %-8.8s height %8.4f tilt %4d rot %4d mag_tilt %4d mag_rot %4d\n",
+ time,
+ ao_state_names[ao_flight_state],
+ ao_k_height / 65536.0,
+ ao_sample_orient, out,
+ mag_azel.el,
+ mag_azel.az);
+#endif
+ printf ("%7.2f state %-8.8s height %8.4f tilt %4d rot %4d dist %12.2f gps_tilt %4d gps_sats %2d\n",
+ time,
+ ao_state_names[ao_flight_state],
+ ao_k_height / 65536.0,
+ ao_sample_orient, out,
+ ao_distance_from_pad(),
+ (int) floor (ao_gps_angle() + 0.5),
+ (ao_gps_static.flags & 0xf) * 10);
+
+#if 0
+ printf ("\t\tstate %-8.8s ground az: %4d el %4d mag az %4d el %4d rot az %4d el %4d el_diff %4d az_diff %4d angle %4d tilt %4d ground %8.5f %8.5f %8.5f cur %8.5f %8.5f %8.5f rot %8.5f %8.5f %8.5f\n",
+ ao_state_names[ao_flight_state],
+ ground_azel.az, ground_azel.el,
+ mag_azel.az, mag_azel.el,
+ rot_azel.az, rot_azel.el,
+ ground_azel.el - rot_azel.el,
+ ground_azel.az - rot_azel.az,
+ ao_mag_angle,
+ ao_sample_orient,
+ ao_ground_mag.x,
+ ao_ground_mag.y,
+ ao_ground_mag.z,
+ ao_mag.x,
+ ao_mag.y,
+ ao_mag.z,
+ ao_mag_rot.x,
+ ao_mag_rot.y,
+ ao_mag_rot.z);
+#endif
+#endif
+
+#if 0
printf("%7.2f height %8.2f accel %8.3f "
#if TELEMEGA
- "roll %8.3f angle %8.3f qangle %8.3f "
- "accel_x %8.3f accel_y %8.3f accel_z %8.3f gyro_x %8.3f gyro_y %8.3f gyro_z %8.3f "
+ "angle %5d "
+ "accel_x %8.3f accel_y %8.3f accel_z %8.3f gyro_x %8.3f gyro_y %8.3f gyro_z %8.3f mag_x %8d mag_y %8d, mag_z %8d mag_angle %4d "
#endif
"state %-8.8s k_height %8.2f k_speed %8.3f k_accel %8.3f avg_height %5d drogue %4d main %4d error %5d\n",
time,
height,
accel,
#if TELEMEGA
- ao_mpu6000_gyro(ao_sample_roll_angle) / 100.0,
- ao_mpu6000_gyro(ao_sample_angle) / 100.0,
- ao_sample_qangle,
+ ao_sample_orient,
+
ao_mpu6000_accel(ao_data_static.mpu6000.accel_x),
ao_mpu6000_accel(ao_data_static.mpu6000.accel_y),
ao_mpu6000_accel(ao_data_static.mpu6000.accel_z),
ao_mpu6000_gyro(ao_data_static.mpu6000.gyro_x - ao_ground_mpu6000.gyro_x),
ao_mpu6000_gyro(ao_data_static.mpu6000.gyro_y - ao_ground_mpu6000.gyro_y),
ao_mpu6000_gyro(ao_data_static.mpu6000.gyro_z - ao_ground_mpu6000.gyro_z),
+ ao_data_static.hmc5883.x,
+ ao_data_static.hmc5883.y,
+ ao_data_static.hmc5883.z,
+ ao_mag_angle,
#endif
ao_state_names[ao_flight_state],
ao_k_height / 65536.0,
@@ -400,6 +628,7 @@ ao_insert(void)
drogue_height,
main_height,
ao_error_h_sq_avg);
+#endif
// if (ao_flight_state == ao_flight_landed)
// ao_test_exit();
@@ -407,125 +636,6 @@ ao_insert(void)
}
}
-#define AO_MAX_CALLSIGN 8
-#define AO_MAX_VERSION 8
-#define AO_MAX_TELEMETRY 128
-
-struct ao_telemetry_generic {
- uint16_t serial; /* 0 */
- uint16_t tick; /* 2 */
- uint8_t type; /* 4 */
- uint8_t payload[27]; /* 5 */
- /* 32 */
-};
-
-#define AO_TELEMETRY_SENSOR_TELEMETRUM 0x01
-#define AO_TELEMETRY_SENSOR_TELEMINI 0x02
-#define AO_TELEMETRY_SENSOR_TELENANO 0x03
-
-struct ao_telemetry_sensor {
- uint16_t serial; /* 0 */
- uint16_t tick; /* 2 */
- uint8_t type; /* 4 */
-
- uint8_t state; /* 5 flight state */
- int16_t accel; /* 6 accelerometer (TM only) */
- int16_t pres; /* 8 pressure sensor */
- int16_t temp; /* 10 temperature sensor */
- int16_t v_batt; /* 12 battery voltage */
- int16_t sense_d; /* 14 drogue continuity sense (TM/Tm) */
- int16_t sense_m; /* 16 main continuity sense (TM/Tm) */
-
- int16_t acceleration; /* 18 m/s² * 16 */
- int16_t speed; /* 20 m/s * 16 */
- int16_t height; /* 22 m */
-
- int16_t ground_pres; /* 24 average pres on pad */
- int16_t ground_accel; /* 26 average accel on pad */
- int16_t accel_plus_g; /* 28 accel calibration at +1g */
- int16_t accel_minus_g; /* 30 accel calibration at -1g */
- /* 32 */
-};
-
-#define AO_TELEMETRY_CONFIGURATION 0x04
-
-struct ao_telemetry_configuration {
- uint16_t serial; /* 0 */
- uint16_t tick; /* 2 */
- uint8_t type; /* 4 */
-
- uint8_t device; /* 5 device type */
- uint16_t flight; /* 6 flight number */
- uint8_t config_major; /* 8 Config major version */
- uint8_t config_minor; /* 9 Config minor version */
- uint16_t apogee_delay; /* 10 Apogee deploy delay in seconds */
- uint16_t main_deploy; /* 12 Main deploy alt in meters */
- uint16_t flight_log_max; /* 14 Maximum flight log size in kB */
- char callsign[AO_MAX_CALLSIGN]; /* 16 Radio operator identity */
- char version[AO_MAX_VERSION]; /* 24 Software version */
- /* 32 */
-};
-
-#define AO_TELEMETRY_LOCATION 0x05
-
-#define AO_GPS_MODE_NOT_VALID 'N'
-#define AO_GPS_MODE_AUTONOMOUS 'A'
-#define AO_GPS_MODE_DIFFERENTIAL 'D'
-#define AO_GPS_MODE_ESTIMATED 'E'
-#define AO_GPS_MODE_MANUAL 'M'
-#define AO_GPS_MODE_SIMULATED 'S'
-
-struct ao_telemetry_location {
- uint16_t serial; /* 0 */
- uint16_t tick; /* 2 */
- uint8_t type; /* 4 */
-
- uint8_t flags; /* 5 Number of sats and other flags */
- int16_t altitude; /* 6 GPS reported altitude (m) */
- int32_t latitude; /* 8 latitude (degrees * 10⁷) */
- int32_t longitude; /* 12 longitude (degrees * 10⁷) */
- uint8_t year; /* 16 (- 2000) */
- uint8_t month; /* 17 (1-12) */
- uint8_t day; /* 18 (1-31) */
- uint8_t hour; /* 19 (0-23) */
- uint8_t minute; /* 20 (0-59) */
- uint8_t second; /* 21 (0-59) */
- uint8_t pdop; /* 22 (m * 5) */
- uint8_t hdop; /* 23 (m * 5) */
- uint8_t vdop; /* 24 (m * 5) */
- uint8_t mode; /* 25 */
- uint16_t ground_speed; /* 26 cm/s */
- int16_t climb_rate; /* 28 cm/s */
- uint8_t course; /* 30 degrees / 2 */
- uint8_t unused[1]; /* 31 */
- /* 32 */
-};
-
-#define AO_TELEMETRY_SATELLITE 0x06
-
-struct ao_telemetry_satellite_info {
- uint8_t svid;
- uint8_t c_n_1;
-};
-
-struct ao_telemetry_satellite {
- uint16_t serial; /* 0 */
- uint16_t tick; /* 2 */
- uint8_t type; /* 4 */
- uint8_t channels; /* 5 number of reported sats */
-
- struct ao_telemetry_satellite_info sats[12]; /* 6 */
- uint8_t unused[2]; /* 30 */
- /* 32 */
-};
-
-union ao_telemetry_all {
- struct ao_telemetry_generic generic;
- struct ao_telemetry_sensor sensor;
- struct ao_telemetry_configuration configuration;
- struct ao_telemetry_location location;
- struct ao_telemetry_satellite satellite;
-};
uint16_t
uint16(uint8_t *bytes, int off)
@@ -555,207 +665,6 @@ int32(uint8_t *bytes, int off)
static int log_format;
-#if TELEMEGA
-
-static double
-ao_vec_norm(double x, double y, double z)
-{
- return x*x + y*y + z*z;
-}
-
-static void
-ao_vec_normalize(double *x, double *y, double *z)
-{
- double scale = 1/sqrt(ao_vec_norm(*x, *y, *z));
-
- *x *= scale;
- *y *= scale;
- *z *= scale;
-}
-
-struct ao_quat {
- double q0, q1, q2, q3;
-};
-
-static void
-ao_quat_mul(struct ao_quat *r, struct ao_quat *a, struct ao_quat *b)
-{
- r->q0 = a->q0 * b->q0 - a->q1 * b->q1 - a->q2 * b->q2 - a->q3 * b->q3;
- r->q1 = a->q0 * b->q1 + a->q1 * b->q0 + a->q2 * b->q3 - a->q3 * b->q2;
- r->q2 = a->q0 * b->q2 - a->q1 * b->q3 + a->q2 * b->q0 + a->q3 * b->q1;
- r->q3 = a->q0 * b->q3 + a->q1 * b->q2 - a->q2 * b->q1 + a->q3 * b->q0;
-}
-
-#if 0
-static void
-ao_quat_scale(struct ao_quat *r, struct ao_quat *a, double s)
-{
- r->q0 = a->q0 * s;
- r->q1 = a->q1 * s;
- r->q2 = a->q2 * s;
- r->q3 = a->q3 * s;
-}
-#endif
-
-static void
-ao_quat_conj(struct ao_quat *r, struct ao_quat *a)
-{
- r->q0 = a->q0;
- r->q1 = -a->q1;
- r->q2 = -a->q2;
- r->q3 = -a->q3;
-}
-
-static void
-ao_quat_rot(struct ao_quat *r, struct ao_quat *a, struct ao_quat *q)
-{
- struct ao_quat t;
- struct ao_quat c;
- ao_quat_mul(&t, q, a);
- ao_quat_conj(&c, q);
- ao_quat_mul(r, &t, &c);
-}
-
-static void
-ao_quat_from_angle(struct ao_quat *r,
- double x_rad,
- double y_rad,
- double z_rad)
-{
- double angle = sqrt (x_rad * x_rad + y_rad * y_rad + z_rad * z_rad);
- double s = sin(angle/2);
- double c = cos(angle/2);
-
- r->q0 = c;
- r->q1 = x_rad * s / angle;
- r->q2 = y_rad * s / angle;
- r->q3 = z_rad * s / angle;
-}
-
-static void
-ao_quat_from_vector(struct ao_quat *r, double x, double y, double z)
-{
- ao_vec_normalize(&x, &y, &z);
- double x_rad = atan2(z, y);
- double y_rad = atan2(x, z);
- double z_rad = atan2(y, x);
-
- ao_quat_from_angle(r, x_rad, y_rad, z_rad);
-}
-
-static double
-ao_quat_norm(struct ao_quat *a)
-{
- return (a->q0 * a->q0 +
- a->q1 * a->q1 +
- a->q2 * a->q2 +
- a->q3 * a->q3);
-}
-
-static void
-ao_quat_normalize(struct ao_quat *a)
-{
- double norm = ao_quat_norm(a);
-
- if (norm) {
- double m = 1/sqrt(norm);
-
- a->q0 *= m;
- a->q1 *= m;
- a->q2 *= m;
- a->q3 *= m;
- }
-}
-
-static struct ao_quat ao_up, ao_current;
-static struct ao_quat ao_orient;
-static int ao_orient_tick;
-
-void
-set_orientation(double x, double y, double z, int tick)
-{
- struct ao_quat t;
-
- printf ("set_orientation %g %g %g\n", x, y, z);
- ao_quat_from_vector(&ao_orient, x, y, z);
- ao_up.q1 = ao_up.q2 = 0;
- ao_up.q0 = ao_up.q3 = sqrt(2)/2;
- ao_orient_tick = tick;
-
- ao_orient.q0 = 1;
- ao_orient.q1 = 0;
- ao_orient.q2 = 0;
- ao_orient.q3 = 0;
-
- printf ("orient (%g) %g %g %g up (%g) %g %g %g\n",
- ao_orient.q0,
- ao_orient.q1,
- ao_orient.q2,
- ao_orient.q3,
- ao_up.q0,
- ao_up.q1,
- ao_up.q2,
- ao_up.q3);
-
- ao_quat_rot(&t, &ao_up, &ao_orient);
- printf ("pad orient (%g) %g %g %g\n",
- t.q0,
- t.q1,
- t.q2,
- t.q3);
-
-}
-
-void
-update_orientation (double rate_x, double rate_y, double rate_z, int tick)
-{
- struct ao_quat q_dot;
- double lambda;
- double dt = (tick - ao_orient_tick) / 100.0;
-
- ao_orient_tick = tick;
-
-// lambda = 1 - ao_quat_norm(&ao_orient);
- lambda = 0;
-
- q_dot.q0 = -0.5 * (ao_orient.q1 * rate_x + ao_orient.q2 * rate_y + ao_orient.q3 * rate_z) + lambda * ao_orient.q0;
- q_dot.q1 = 0.5 * (ao_orient.q0 * rate_x + ao_orient.q2 * rate_z - ao_orient.q3 * rate_y) + lambda * ao_orient.q1;
- q_dot.q2 = 0.5 * (ao_orient.q0 * rate_y + ao_orient.q3 * rate_x - ao_orient.q1 * rate_z) + lambda * ao_orient.q2;
- q_dot.q3 = 0.5 * (ao_orient.q0 * rate_z + ao_orient.q1 * rate_y - ao_orient.q2 * rate_x) + lambda * ao_orient.q3;
-
-#if 0
- printf ("update_orientation %g %g %g (%g s)\n", rate_x, rate_y, rate_z, dt);
- printf ("q_dot (%g) %g %g %g\n",
- q_dot.q0,
- q_dot.q1,
- q_dot.q2,
- q_dot.q3);
-#endif
-
- ao_orient.q0 += q_dot.q0 * dt;
- ao_orient.q1 += q_dot.q1 * dt;
- ao_orient.q2 += q_dot.q2 * dt;
- ao_orient.q3 += q_dot.q3 * dt;
-
- ao_quat_normalize(&ao_orient);
-
- ao_quat_rot(&ao_current, &ao_up, &ao_orient);
-
- ao_sample_qangle = 180 / M_PI * acos(ao_current.q3 * sqrt(2));
-#if 0
- printf ("orient (%g) %g %g %g current (%g) %g %g %g\n",
- ao_orient.q0,
- ao_orient.q1,
- ao_orient.q2,
- ao_orient.q3,
- ao_current.q0,
- ao_current.q1,
- ao_current.q2,
- ao_current.q3);
-#endif
-}
-#endif
-
void
ao_sleep(void *wchan)
{
@@ -771,6 +680,10 @@ ao_sleep(void *wchan)
char *words[64];
int nword;
+#if TELEMEGA
+ if (ao_flight_state >= ao_flight_boost && ao_flight_state < ao_flight_landed)
+ ao_pyro_check();
+#endif
for (;;) {
if (ao_records_read > 2 && ao_flight_state == ao_flight_startup)
{
@@ -826,43 +739,31 @@ ao_sleep(void *wchan)
ao_data_static.ms5607_raw.temp = int32(bytes, 4);
ao_ms5607_convert(&ao_data_static.ms5607_raw, &value);
ao_data_static.mpu6000.accel_x = int16(bytes, 8);
- ao_data_static.mpu6000.accel_y = -int16(bytes, 10);
+ ao_data_static.mpu6000.accel_y = int16(bytes, 10);
ao_data_static.mpu6000.accel_z = int16(bytes, 12);
ao_data_static.mpu6000.gyro_x = int16(bytes, 14);
- ao_data_static.mpu6000.gyro_y = -int16(bytes, 16);
+ ao_data_static.mpu6000.gyro_y = int16(bytes, 16);
ao_data_static.mpu6000.gyro_z = int16(bytes, 18);
+ ao_data_static.hmc5883.x = int16(bytes, 20);
+ ao_data_static.hmc5883.y = int16(bytes, 22);
+ ao_data_static.hmc5883.z = int16(bytes, 24);
#if HAS_MMA655X
ao_data_static.mma655x = int16(bytes, 26);
#endif
- if (ao_records_read == 0)
- ao_ground_mpu6000 = ao_data_static.mpu6000;
- else if (ao_records_read < 10) {
-#define f(f) ao_ground_mpu6000.f = ao_ground_mpu6000.f + ((ao_data_static.mpu6000.f - ao_ground_mpu6000.f) >> 2)
- f(accel_x);
- f(accel_y);
- f(accel_z);
- f(gyro_x);
- f(gyro_y);
- f(gyro_z);
-
- double accel_x = ao_mpu6000_accel(ao_ground_mpu6000.accel_x);
- double accel_y = ao_mpu6000_accel(ao_ground_mpu6000.accel_y);
- double accel_z = ao_mpu6000_accel(ao_ground_mpu6000.accel_z);
-
- /* X and Y are in the ground plane, arbitraryily picked as MPU X and Z axes
- * Z is normal to the ground, the MPU y axis
- */
- set_orientation(accel_x, accel_z, accel_y, tick);
- } else {
- double rate_x = ao_mpu6000_gyro(ao_data_static.mpu6000.gyro_x - ao_ground_mpu6000.gyro_x);
- double rate_y = ao_mpu6000_gyro(ao_data_static.mpu6000.gyro_y - ao_ground_mpu6000.gyro_y);
- double rate_z = ao_mpu6000_gyro(ao_data_static.mpu6000.gyro_z - ao_ground_mpu6000.gyro_z);
-
- update_orientation(rate_x * M_PI / 180, rate_z * M_PI / 180, rate_y * M_PI / 180, tick);
- }
ao_records_read++;
ao_insert();
return;
+ case 'G':
+ ao_gps_prev = ao_gps_static;
+ ao_gps_static.tick = tick;
+ ao_gps_static.latitude = int32(bytes, 0);
+ ao_gps_static.longitude = int32(bytes, 4);
+ ao_gps_static.altitude = int32(bytes, 8);
+ ao_gps_static.flags = bytes[13];
+ if (!ao_gps_count)
+ ao_gps_first = ao_gps_static;
+ ao_gps_count++;
+ break;
}
continue;
} else if (nword == 3 && strcmp(words[0], "ms5607") == 0) {
@@ -883,6 +784,23 @@ ao_sleep(void *wchan)
else if (strcmp(words[1], "crc:") == 0)
ms5607_prom.crc = strtoul(words[2], NULL, 10);
continue;
+ } else if (nword >= 3 && strcmp(words[0], "Pyro") == 0) {
+ int p = strtoul(words[1], NULL, 10);
+ int i, j;
+ struct ao_pyro *pyro = &ao_config.pyro[p];
+
+ for (i = 2; i < nword; i++) {
+ for (j = 0; j < NUM_PYRO_VALUES; j++)
+ if (!strcmp (words[2], ao_pyro_values[j].name))
+ break;
+ if (j == NUM_PYRO_VALUES)
+ continue;
+ pyro->flags |= ao_pyro_values[j].flag;
+ if (ao_pyro_values[j].offset != NO_VALUE && i + 1 < nword) {
+ int16_t val = strtoul(words[++i], NULL, 10);
+ *((int16_t *) ((char *) pyro + ao_pyro_values[j].offset)) = val;
+ }
+ }
}
#else
if (nword == 4 && log_format != AO_LOG_FORMAT_TELEMEGA) {
@@ -899,6 +817,13 @@ ao_sleep(void *wchan)
} else if (nword >= 6 && strcmp(words[0], "Accel") == 0) {
ao_config.accel_plus_g = atoi(words[3]);
ao_config.accel_minus_g = atoi(words[5]);
+#ifdef TELEMEGA
+ } else if (nword >= 8 && strcmp(words[0], "IMU") == 0) {
+ ao_config.accel_zero_along = atoi(words[3]);
+ ao_config.accel_zero_across = atoi(words[5]);
+ ao_config.accel_zero_through = atoi(words[7]);
+ printf ("%d %d %d\n", ao_config.accel_zero_along, ao_config.accel_zero_across, ao_config.accel_zero_through);
+#endif
} else if (nword >= 4 && strcmp(words[0], "Main") == 0) {
ao_config.main_deploy = atoi(words[2]);
} else if (nword >= 3 && strcmp(words[0], "Apogee") == 0 &&
diff --git a/src/test/ao_gps_test.c b/src/test/ao_gps_test.c
index 3844a326..e799ab0f 100644
--- a/src/test/ao_gps_test.c
+++ b/src/test/ao_gps_test.c
@@ -26,6 +26,9 @@
#define AO_GPS_NUM_SAT_MASK (0xf << 0)
#define AO_GPS_NUM_SAT_SHIFT (0)
+#define AO_GPS_NEW_DATA 1
+#define AO_GPS_NEW_TRACKING 2
+
#define AO_GPS_VALID (1 << 4)
#define AO_GPS_RUNNING (1 << 5)
#define AO_GPS_DATE_VALID (1 << 6)
@@ -427,11 +430,18 @@ void
ao_dump_state(void *wchan)
{
int i;
- if (wchan == &ao_gps_data)
+
+ if (wchan != &ao_gps_new)
+ return;
+
+ if (ao_gps_new & AO_GPS_NEW_DATA) {
ao_gps_print(&ao_gps_data);
- else
+ putchar('\n');
+ }
+ if (ao_gps_new & AO_GPS_NEW_TRACKING) {
ao_gps_tracking_print(&ao_gps_tracking_data);
- putchar('\n');
+ putchar('\n');
+ }
return;
printf ("%02d:%02d:%02d",
ao_gps_data.hour, ao_gps_data.minute,
diff --git a/src/test/ao_gps_test_skytraq.c b/src/test/ao_gps_test_skytraq.c
index 81008b39..1b590d5e 100644
--- a/src/test/ao_gps_test_skytraq.c
+++ b/src/test/ao_gps_test_skytraq.c
@@ -26,6 +26,9 @@
#define AO_GPS_NUM_SAT_MASK (0xf << 0)
#define AO_GPS_NUM_SAT_SHIFT (0)
+#define AO_GPS_NEW_DATA 1
+#define AO_GPS_NEW_TRACKING 2
+
#define AO_GPS_VALID (1 << 4)
#define AO_GPS_RUNNING (1 << 5)
#define AO_GPS_DATE_VALID (1 << 6)
@@ -75,6 +78,11 @@ struct ao_gps_tracking_orig {
#define ao_telemetry_satellite ao_gps_tracking_orig
#define ao_telemetry_satellite_info ao_gps_sat_orig
+extern __xdata struct ao_telemetry_location ao_gps_data;
+extern __xdata struct ao_telemetry_satellite ao_gps_tracking_data;
+
+uint8_t ao_gps_mutex;
+
void
ao_mutex_get(uint8_t *mutex)
{
@@ -432,17 +440,14 @@ uint8_t ao_task_minimize_latency;
#define ao_usb_getchar() 0
#include "ao_gps_print.c"
+#include "ao_gps_show.c"
#include "ao_gps_skytraq.c"
void
ao_dump_state(void *wchan)
{
- if (wchan == &ao_gps_data)
- ao_gps_print(&ao_gps_data);
- else
- ao_gps_tracking_print(&ao_gps_tracking_data);
- putchar('\n');
- return;
+ if (wchan == &ao_gps_new)
+ ao_gps_show();
}
int
diff --git a/src/test/ao_gps_test_ublox.c b/src/test/ao_gps_test_ublox.c
index 80671735..4eb4b837 100644
--- a/src/test/ao_gps_test_ublox.c
+++ b/src/test/ao_gps_test_ublox.c
@@ -26,6 +26,9 @@
#define AO_GPS_NUM_SAT_MASK (0xf << 0)
#define AO_GPS_NUM_SAT_SHIFT (0)
+#define AO_GPS_NEW_DATA 1
+#define AO_GPS_NEW_TRACKING 2
+
#define AO_GPS_VALID (1 << 4)
#define AO_GPS_RUNNING (1 << 5)
#define AO_GPS_DATE_VALID (1 << 6)
@@ -77,6 +80,11 @@ struct ao_telemetry_satellite {
#define ao_gps_tracking_orig ao_telemetry_satellite
#define ao_gps_sat_orig ao_telemetry_satellite_info
+extern __xdata struct ao_telemetry_location ao_gps_data;
+extern __xdata struct ao_telemetry_satellite ao_gps_tracking_data;
+
+uint8_t ao_gps_mutex;
+
void
ao_mutex_get(uint8_t *mutex)
{
@@ -125,7 +133,7 @@ static uint16_t recv_len;
static void check_ublox_message(char *which, uint8_t *msg);
char
-ao_serial1_getchar(void)
+ao_gps_getchar(void)
{
char c;
uint8_t uc;
@@ -158,7 +166,7 @@ static int message_len;
static uint16_t send_len;
void
-ao_serial1_putchar(char c)
+ao_gps_putchar(char c)
{
int i;
uint8_t uc = (uint8_t) c;
@@ -191,7 +199,7 @@ ao_serial1_putchar(char c)
#define AO_SERIAL_SPEED_115200 3
static void
-ao_serial1_set_speed(uint8_t speed)
+ao_gps_set_speed(uint8_t speed)
{
int fd = ao_gps_fd;
struct termios termios;
@@ -224,6 +232,7 @@ uint8_t ao_task_minimize_latency;
#define ao_usb_getchar() 0
#include "ao_gps_print.c"
+#include "ao_gps_show.c"
#include "ao_gps_ublox.c"
static void
@@ -341,11 +350,8 @@ check_ublox_message(char *which, uint8_t *msg)
void
ao_dump_state(void *wchan)
{
- if (wchan == &ao_gps_data)
- ao_gps_print(&ao_gps_data);
- else
- ao_gps_tracking_print(&ao_gps_tracking_data);
- putchar('\n');
+ if (wchan == &ao_gps_new)
+ ao_gps_show();
return;
}
diff --git a/src/test/ao_int64_test.c b/src/test/ao_int64_test.c
new file mode 100644
index 00000000..8557a1c7
--- /dev/null
+++ b/src/test/ao_int64_test.c
@@ -0,0 +1,115 @@
+/*
+ * Copyright © 2013 Keith Packard <keithp@keithp.com>
+ *
+ * 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; version 2 of the License.
+ *
+ * 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.
+ */
+
+#define __data
+#define __pdata
+#define __xdata
+#define __reentrant
+
+#include <ao_int64.h>
+#include <ao_int64.c>
+#include <stdio.h>
+#include <stdlib.h>
+
+int errors;
+
+#define test_o(op,func,mod,a,b,ao_a,ao_b) do { \
+ r = (a) op (b); \
+ func(&ao_r, ao_a, ao_b); \
+ c = ao_cast64(&ao_r); \
+ if (c != r) { \
+ printf ("trial %4d: %lld " #func mod " %lld = %lld (should be %lld)\n", \
+ trial, (int64_t) (a), (int64_t) b, c, r); \
+ ++errors; \
+ } \
+ } while (0)
+
+#define test(op,func,a,b,ao_a,ao_b) test_o(op,func,"",a,b,ao_a,ao_b)
+
+#define test_a(op,func,a,b,ao_a,ao_b) do { \
+ ao_r = *ao_a; \
+ test_o(op,func,"_a",a,b,&ao_r,ao_b); \
+ } while (0)
+
+#define test_b(op,func,a,b,ao_a,ao_b) do { \
+ ao_r = *ao_b; \
+ test_o(op,func,"_b",a,b,ao_a,&ao_r); \
+ } while (0)
+
+#define test_x(op,func,a,b,ao_a,ao_b) do { \
+ ao_r = *ao_a; \
+ test_o(op,func,"_xa",a,a,&ao_r,&ao_r); \
+ ao_r = *ao_b; \
+ test_o(op,func,"_xb",b,b,&ao_r,&ao_r); \
+ } while (0)
+
+void
+do_test(int trial, int64_t a, int64_t b)
+{
+ int64_t r, c;
+ ao_int64_t ao_a, ao_b, ao_r;
+
+ ao_int64_init64(&ao_a, a >> 32, a);
+ ao_int64_init64(&ao_b, b >> 32, b);
+
+ test(+, ao_plus64, a, b, &ao_a, &ao_b);
+ test_a(+, ao_plus64, a, b, &ao_a, &ao_b);
+ test_b(+, ao_plus64, a, b, &ao_a, &ao_b);
+ test_x(+, ao_plus64, a, b, &ao_a, &ao_b);
+ test(-, ao_minus64, a, b, &ao_a, &ao_b);
+ test_a(-, ao_minus64, a, b, &ao_a, &ao_b);
+ test_b(-, ao_minus64, a, b, &ao_a, &ao_b);
+ test_x(-, ao_minus64, a, b, &ao_a, &ao_b);
+ test(*, ao_mul64_32_32,(int64_t) (int32_t) a, (int32_t) b, (int32_t) a, (int32_t) b);
+ test(*, ao_mul64, a, b, &ao_a, &ao_b);
+ test_a(*, ao_mul64, a, b, &ao_a, &ao_b);
+ test_b(*, ao_mul64, a, b, &ao_a, &ao_b);
+ test_x(*, ao_mul64, a, b, &ao_a, &ao_b);
+ test(*, ao_mul64_64_16, a, (uint16_t) b, &ao_a, (uint16_t) b);
+ test_a(*, ao_mul64_64_16, a, (uint16_t) b, &ao_a, (uint16_t) b);
+ test(>>, ao_rshift64, a, (uint8_t) b & 0x3f, &ao_a, (uint8_t) b & 0x3f);
+ test_a(>>, ao_rshift64, a, (uint8_t) b & 0x3f, &ao_a, (uint8_t) b & 0x3f);
+ test(<<, ao_lshift64, a, (uint8_t) b & 0x3f, &ao_a, (uint8_t) b & 0x3f);
+ test_a(<<, ao_lshift64, a, (uint8_t) b & 0x3f, &ao_a, (uint8_t) b & 0x3f);
+}
+
+#define TESTS 10000000
+
+static int64_t
+random64(void)
+{
+ return (int64_t) random() + ((int64_t) random() << 31) /* + ((int64_t) random() << 33) */;
+}
+
+int
+main (int argc, char **argv)
+{
+ int i, start;
+
+ if (argv[1])
+ start = atoi(argv[1]);
+ else
+ start = 0;
+ srandom(1000);
+ for (i = 0; i < TESTS; i++) {
+ int64_t a = random64();
+ int64_t b = random64();
+ if (i >= start)
+ do_test(i, a, b);
+ }
+ return errors;
+}
diff --git a/src/test/ao_ms5607_convert_test.c b/src/test/ao_ms5607_convert_test.c
new file mode 100644
index 00000000..ad593204
--- /dev/null
+++ b/src/test/ao_ms5607_convert_test.c
@@ -0,0 +1,96 @@
+/*
+ * Copyright © 2013 Keith Packard <keithp@keithp.com>
+ *
+ * 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; version 2 of the License.
+ *
+ * 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.
+ */
+
+#define __xdata
+#define __data
+#define __pdata
+#define __reentrant
+
+#include <stdint.h>
+#include <ao_ms5607.h>
+
+struct ao_ms5607_prom ms5607_prom = {
+ 0x002c,
+ 0xa6e0,
+ 0x988e,
+ 0x6814,
+ 0x5eff,
+ 0x8468,
+ 0x6c86,
+ 0xa271,
+};
+
+int32_t D1_mm = 6179630;
+int32_t D2_mm = 8933155;
+
+#include <ao_ms5607_convert.c>
+#define ao_ms5607_convert ao_ms5607_convert_8051
+#include <ao_ms5607_convert_8051.c>
+#include <ao_int64.c>
+#include <stdio.h>
+#include <stdlib.h>
+
+struct ao_ms5607_sample ao_sample = {
+ 6179630,
+ 8933155
+};
+
+int errors;
+
+void test(int trial, struct ao_ms5607_sample *sample)
+{
+ struct ao_ms5607_value value, value_8051;
+
+ ao_ms5607_convert(sample, &value);
+ ao_ms5607_convert_8051(sample, &value_8051);
+ if (value.temp != value_8051.temp || value.pres != value_8051.pres) {
+ ++errors;
+ printf ("trial %d: %d, %d -> %d, %d (should be %d, %d)\n",
+ trial,
+ sample->pres, sample->temp,
+ value_8051.pres, value_8051.temp,
+ value.pres, value.temp);
+ }
+}
+
+#define TESTS 10000000
+
+#include <stdlib.h>
+
+static int32_t rand24(void) { return random() & 0xffffff; }
+
+int
+main(int argc, char **argv)
+{
+ struct ao_ms5607_sample sample;
+ int i, start;
+
+ if (argv[1])
+ start = atoi(argv[1]);
+ else
+ start = 0;
+
+ srandom(10000);
+ test(-1, &ao_sample);
+ for (i = 0; i < TESTS; i++) {
+ sample.pres = rand24();
+ sample.temp = rand24();
+ if (i >= start)
+ test(i, &sample);
+ }
+ return errors;
+}
diff --git a/src/test/ao_quaternion_test.c b/src/test/ao_quaternion_test.c
new file mode 100644
index 00000000..b630f1d3
--- /dev/null
+++ b/src/test/ao_quaternion_test.c
@@ -0,0 +1,154 @@
+/*
+ * Copyright © 2013 Keith Packard <keithp@keithp.com>
+ *
+ * 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; version 2 of the License.
+ *
+ * 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.
+ */
+
+#define _GNU_SOURCE
+
+#include <stdint.h>
+#include <stdio.h>
+#include <stdlib.h>
+#include <stddef.h>
+#include <string.h>
+#include <getopt.h>
+#include <math.h>
+
+#include "ao_quaternion.h"
+
+#if 0
+static void
+print_q(char *name, struct ao_quaternion *q)
+{
+ printf ("%8.8s: r%8.5f x%8.5f y%8.5f z%8.5f ", name,
+ q->r, q->x, q->y, q->z);
+}
+#endif
+
+#define STEPS 16
+
+#define DEG (1.0f * 3.1415926535f / 180.0f)
+
+struct ao_rotation {
+ int steps;
+ float x, y, z;
+};
+
+static struct ao_rotation ao_path[] = {
+ { .steps = 45, .x = 2*DEG, .y = 0, .z = 0 },
+
+ { .steps = 45, .x = 0, .y = 2*DEG, .z = 0 },
+
+ { .steps = 45, .x = -2*DEG, .y = 0, .z = 0 },
+
+ { .steps = 45, .x = 0, .y = -2*DEG, .z = 0 },
+};
+
+#define NUM_PATH (sizeof ao_path / sizeof ao_path[0])
+
+static int close(float a, float b) {
+ return fabsf (a - b) < 1e-5;
+}
+
+static int check_quaternion(char *where, struct ao_quaternion *got, struct ao_quaternion *expect) {
+ if (!close (got->r, expect->r) ||
+ !close (got->x, expect->x) ||
+ !close (got->y, expect->y) ||
+ !close (got->z, expect->z))
+ {
+ printf ("%s: got r%8.5f x%8.5f y%8.5f z%8.5f expect r%8.5f x%8.5f y%8.5f z%8.5f\n",
+ where,
+ got->r, got->x, got->y, got->z,
+ expect->r, expect->x, expect->y, expect->z);
+ return 1;
+ }
+ return 0;
+}
+
+int main(int argc, char **argv)
+{
+ struct ao_quaternion position;
+ struct ao_quaternion position_expect;
+ struct ao_quaternion rotation;
+ struct ao_quaternion rotated;
+ struct ao_quaternion little_rotation;
+ int i;
+ int p;
+ int ret = 0;
+
+ /* vector */
+ ao_quaternion_init_vector(&position, 1, 1, 1);
+ ao_quaternion_init_vector(&position_expect, -1, -1, 1);
+
+ /* zero rotation */
+ ao_quaternion_init_zero_rotation(&rotation);
+
+#define dump() do { \
+ \
+ ao_quaternion_rotate(&rotated, &position, &rotation); \
+ print_q("rotated", &rotated); \
+ print_q("rotation", &rotation); \
+ printf ("\n"); \
+ } while (0)
+
+// dump();
+
+ for (p = 0; p < NUM_PATH; p++) {
+ ao_quaternion_init_half_euler(&little_rotation,
+ ao_path[p].x / 2.0f,
+ ao_path[p].y / 2.0f,
+ ao_path[p].z / 2.0f);
+// printf ("\t\tx: %8.4f, y: %8.4f, z: %8.4f ", ao_path[p].x, ao_path[p].y, ao_path[p].z);
+// print_q("step", &little_rotation);
+// printf("\n");
+ for (i = 0; i < ao_path[p].steps; i++) {
+ ao_quaternion_multiply(&rotation, &little_rotation, &rotation);
+
+ ao_quaternion_normalize(&rotation, &rotation);
+
+// dump();
+ }
+ }
+
+ ao_quaternion_rotate(&rotated, &position, &rotation);
+
+ ret += check_quaternion("rotation", &rotated, &position_expect);
+
+ struct ao_quaternion vertical;
+ struct ao_quaternion angle;
+ struct ao_quaternion rot;
+
+ ao_quaternion_init_vector(&vertical, 0, 0, 1);
+ ao_quaternion_init_vector(&angle, 0, 0, 1);
+
+ ao_quaternion_init_half_euler(&rot,
+ M_PI * 3.0 / 8.0 , 0, 0);
+
+ ao_quaternion_rotate(&angle, &angle, &rot);
+
+ struct ao_quaternion rot_compute;
+
+ ao_quaternion_vectors_to_rotation(&rot_compute, &vertical, &angle);
+
+ ret += check_quaternion("vector rotation", &rot_compute, &rot);
+
+ struct ao_quaternion rotd;
+
+ ao_quaternion_rotate(&rotd, &vertical, &rot_compute);
+
+ ret += check_quaternion("vector rotated", &rotd, &angle);
+
+ return ret;
+}
+
diff --git a/src/test/mega.flights b/src/test/mega.flights
new file mode 100644
index 00000000..71c44e65
--- /dev/null
+++ b/src/test/mega.flights
@@ -0,0 +1,12 @@
+2013-10-12-serial-0094-flight-0001.eeprom
+2013-09-02-serial-094-flight-002.eeprom
+2013-03-02-serial-069-flight-002.eeprom
+2013-03-02-serial-069-flight-001.eeprom
+2013-05-27-serial-084-flight-001.mega
+2013-05-26-serial-085-flight-002.mega
+2013-05-19-serial-084-flight-003.mega
+2013-04-21-serial-069-flight-002.mega
+2012-10-20-serial-068-flight-004.mega
+2012-07-03-serial-058-flight-007.mega
+2012-06-30-serial-058-flight-006.mega
+2012-06-30-serial-058-flight-005.mega
diff --git a/src/test/plot-rot b/src/test/plot-rot
new file mode 100755
index 00000000..b6b77c93
--- /dev/null
+++ b/src/test/plot-rot
@@ -0,0 +1,30 @@
+#!/bin/sh
+
+case $# in
+1)
+ file="$1"
+ title="$1"
+ ;;
+2)
+ file="$1"
+ title="$2"
+ ;;
+*)
+ echo "Usage: $0 <data-file> <title>"
+ exit 1
+esac
+
+gnuplot -persist << EOF
+set ylabel "altitude (m)"
+set y2label "angle (d)"
+set xlabel "time (s)"
+set xtics border out nomirror
+set ytics border out nomirror
+set y2tics border out nomirror
+set title "$title"
+plot "$file" using 1:5 with lines axes x1y1 title "height",\
+"$file" using 1:9 with lines axes x1y2 title "gyro rot", \
+"$file" using 1:7 with lines axes x1y2 title "gyro tilt", \
+"$file" using 1:13 with lines axes x1y2 title "mag rot", \
+"$file" using 1:11 with lines axes x1y2 title "mag tilt"
+EOF
diff --git a/src/test/plotmm b/src/test/plotmm
index 5f5bd2ca..27f8ddcd 100755
--- a/src/test/plotmm
+++ b/src/test/plotmm
@@ -1,11 +1,29 @@
+#!/bin/sh
+
+case $# in
+1)
+ file="$1"
+ title="$1"
+ ;;
+2)
+ file="$1"
+ title="$2"
+ ;;
+*)
+ echo "Usage: $0 <data-file> <title>"
+ exit 1
+esac
+
gnuplot -persist << EOF
-set ylabel "altitude (m)"
+set ylabel "distance (m)"
set y2label "angle (d)"
set xlabel "time (s)"
set xtics border out nomirror
set ytics border out nomirror
set y2tics border out nomirror
-plot "$1" using 1:3 with lines axes x1y1 title "raw height",\
-"$1" using 1:9 with lines axes x1y2 title "angle",\
-"$1" using 1:11 with lines axes x1y2 title "qangle"
+set title "$title"
+plot "$file" using 1:5 with lines axes x1y1 title "height",\
+"$file" using 1:7 with lines axes x1y2 title "angle",\
+"$file" using 1:13 with lines axes x1y2 title "gps angle",\
+"$file" using 1:15 with lines axes x1y2 title "sats"
EOF
diff --git a/src/test/run-all-mm b/src/test/run-all-mm
new file mode 100755
index 00000000..d9c2043d
--- /dev/null
+++ b/src/test/run-all-mm
@@ -0,0 +1,2 @@
+#!/bin/sh
+./run-mm `cat mega.flights`
diff --git a/src/test/run-mm b/src/test/run-mm
index 6f3d97a2..ae5e5f42 100755
--- a/src/test/run-mm
+++ b/src/test/run-mm
@@ -3,15 +3,20 @@
DIR=~/misc/rockets/flights
for i in "$@"; do
-case "$i" in
- */*)
- file="$i"
- ;;
- *)
- file="$DIR/$i"
- ;;
-esac
-./ao_flight_test_mm "$file" > run-out.mm
+ case "$i" in
+ */*)
+ file="$i"
+ ;;
+ *)
+ file="$DIR/$i"
+ ;;
+ esac
+ base=`basename "$i" .eeprom`
+
+ ./ao_flight_test_mm "$file" > $base.plot
+
+ sh ./plotmm $base.plot `basename "$file"`
+done
#./ao_flight_test_accel "$file" > run-out.accel
#"run-out.accel" using 1:9 with lines lt 4 axes x1y1 title "accel height",\
@@ -21,21 +26,21 @@ esac
#"run-out.accel" using 1:17 with lines lt 4 axes x1y1 title "accel main",\
#
-gnuplot << EOF
-set ylabel "altitude (m)"
-set y2label "velocity (m/s), acceleration(m/s²)"
-set xlabel "time (s)"
-set xtics border out nomirror
-set ytics border out nomirror
-set y2tics border out nomirror
-set title "$i"
-plot "run-out.mm" using 1:3 with lines lw 2 lt 1 axes x1y1 title "raw height",\
-"run-out.mm" using 1:5 with lines lw 2 lt 1 axes x1y2 title "raw accel",\
-"run-out.mm" using 1:21 with lines lt 2 axes x1y1 title "mm height",\
-"run-out.mm" using 1:23 with lines lt 2 axes x1y2 title "mm speed",\
-"run-out.mm" using 1:25 with lines lt 2 axes x1y2 title "mm accel",\
-"run-out.mm" using 1:29 with lines lt 2 axes x1y1 title "mm drogue",\
-"run-out.mm" using 1:31 with lines lt 2 axes x1y1 title "mm main"
-pause mouse close
-EOF
-done \ No newline at end of file
+#gnuplot << EOF
+#set ylabel "altitude (m)"
+#set y2label "velocity (m/s), acceleration(m/s²)"
+#set xlabel "time (s)"
+#set xtics border out nomirror
+#set ytics border out nomirror
+#set y2tics border out nomirror
+#set title "$i"
+#plot "run-out.mm" using 1:3 with lines lw 2 lt 1 axes x1y1 title "raw height",\
+#"run-out.mm" using 1:5 with lines lw 2 lt 1 axes x1y2 title "raw accel",\
+#"run-out.mm" using 1:21 with lines lt 2 axes x1y1 title "mm height",\
+#"run-out.mm" using 1:23 with lines lt 2 axes x1y2 title "mm speed",\
+#"run-out.mm" using 1:25 with lines lt 2 axes x1y2 title "mm accel",\
+#"run-out.mm" using 1:29 with lines lt 2 axes x1y1 title "mm drogue",\
+#"run-out.mm" using 1:31 with lines lt 2 axes x1y1 title "mm main"
+#pause mouse close
+#EOF
+#done \ No newline at end of file