diff options
Diffstat (limited to 'src/core')
-rw-r--r-- | src/core/ao_data.h | 6 | ||||
-rw-r--r-- | src/core/ao_flight.c | 4 | ||||
-rw-r--r-- | src/core/ao_kalman.c | 3 | ||||
-rw-r--r-- | src/core/ao_pyro.c | 4 | ||||
-rw-r--r-- | src/core/ao_quaternion.h | 116 | ||||
-rw-r--r-- | src/core/ao_sample.c | 98 | ||||
-rw-r--r-- | src/core/ao_sample.h | 3 | ||||
-rw-r--r-- | src/core/ao_telemetry.c | 1 | ||||
-rw-r--r-- | src/core/ao_telemetry.h | 2 |
9 files changed, 222 insertions, 15 deletions
diff --git a/src/core/ao_data.h b/src/core/ao_data.h index 339afe69..5a232885 100644 --- a/src/core/ao_data.h +++ b/src/core/ao_data.h @@ -18,6 +18,8 @@ #ifndef _AO_DATA_H_ #define _AO_DATA_H_ +#define GRAVITY 9.80665 + #if HAS_ADC #define AO_DATA_ADC (1 << 0) #else @@ -300,8 +302,8 @@ typedef int16_t accel_t; #define HAS_GYRO 1 -typedef int16_t gyro_t; -typedef int32_t angle_t; +typedef int16_t gyro_t; /* in raw sample units */ +typedef int16_t angle_t; /* in degrees */ /* Y axis is aligned with the direction of motion (along) */ /* X axis is aligned in the other board axis (across) */ diff --git a/src/core/ao_flight.c b/src/core/ao_flight.c index 2495a44b..240b348a 100644 --- a/src/core/ao_flight.c +++ b/src/core/ao_flight.c @@ -20,6 +20,10 @@ #include <ao_log.h> #endif +#if HAS_MPU6000 +#include <ao_quaternion.h> +#endif + #ifndef HAS_ACCEL #error Please define HAS_ACCEL #endif diff --git a/src/core/ao_kalman.c b/src/core/ao_kalman.c index 762b2c0a..7fd4f889 100644 --- a/src/core/ao_kalman.c +++ b/src/core/ao_kalman.c @@ -292,7 +292,4 @@ ao_kalman(void) else #endif ao_avg_height = (ao_avg_height_scaled + 63) >> 7; -#ifdef AO_FLIGHT_TEST - ao_sample_prev_tick = ao_sample_tick; -#endif } diff --git a/src/core/ao_pyro.c b/src/core/ao_pyro.c index 531e1f50..24c9fe99 100644 --- a/src/core/ao_pyro.c +++ b/src/core/ao_pyro.c @@ -113,7 +113,7 @@ ao_pyro_ready(struct ao_pyro *pyro) continue; break; -#if HAS_ORIENT +#if HAS_GYRO case ao_pyro_orient_less: if (ao_orient <= pyro->orient_less) continue; @@ -310,7 +310,7 @@ const struct { { "h<", ao_pyro_height_less, offsetof(struct ao_pyro, height_less), HELP("height less (m)") }, { "h>", ao_pyro_height_greater, offsetof(struct ao_pyro, height_greater), HELP("height greater (m)") }, -#if HAS_ORIENT +#if HAS_GYRO { "o<", ao_pyro_orient_less, offsetof(struct ao_pyro, orient_less), HELP("orient less (deg)") }, { "o>", ao_pyro_orient_greater, offsetof(struct ao_pyro, orient_greater), HELP("orient greater (deg)") }, #endif diff --git a/src/core/ao_quaternion.h b/src/core/ao_quaternion.h new file mode 100644 index 00000000..f4b8aaa4 --- /dev/null +++ b/src/core/ao_quaternion.h @@ -0,0 +1,116 @@ +/* + * 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. + */ + +#ifndef _AO_QUATERNION_H_ +#define _AO_QUATERNION_H_ + +#include <math.h> + +struct ao_quaternion { + float r; /* real bit */ + float x, y, z; /* imaginary bits */ +}; + +static inline void ao_quaternion_multiply(struct ao_quaternion *r, + struct ao_quaternion *a, + struct ao_quaternion *b) +{ + struct ao_quaternion t; +#define T(_a,_b) (((a)->_a) * ((b)->_b)) + t.r = T(r,r) - T(x,x) - T(y,y) - T(z,z); + t.x = T(r,x) + T(x,r) + T(y,z) - T(z,y); + t.y = T(r,y) - T(x,z) + T(y,r) + T(z,x); + t.z = T(r,z) + T(x,y) - T(y,x) + T(z,r); +#undef T + *r = t; +} + +static inline void ao_quaternion_conjugate(struct ao_quaternion *r, + struct ao_quaternion *a) +{ + r->r = a->r; + r->x = -a->x; + r->y = -a->y; + r->z = -a->z; +} + +static inline float ao_quaternion_normal(struct ao_quaternion *a) +{ +#define S(_a) (((a)->_a) * ((a)->_a)) + return S(r) + S(x) + S(y) + S(z); +#undef S +} + +static inline void ao_quaternion_scale(struct ao_quaternion *r, + struct ao_quaternion *a, + float b) +{ + r->r = a->r * b; + r->x = a->x * b; + r->y = a->y * b; + r->z = a->z * b; +} + +static inline void ao_quaternion_normalize(struct ao_quaternion *r, + struct ao_quaternion *a) +{ + float n = ao_quaternion_normal(a); + + if (n > 0) + ao_quaternion_scale(r, a, 1/sqrtf(n)); + else + *r = *a; +} + +static inline void ao_quaternion_rotate(struct ao_quaternion *r, + struct ao_quaternion *a, + struct ao_quaternion *b) +{ + struct ao_quaternion c; + struct ao_quaternion t; + + ao_quaternion_conjugate(&c, b); + ao_quaternion_multiply(&t, b, a); + ao_quaternion_multiply(r, &t, &c); +} + +static inline void ao_quaternion_init_vector(struct ao_quaternion *r, + float x, float y, float z) +{ + r->r = 0; + r->x = x; + r->y = y; + r->z = z; +} + +static inline void ao_quaternion_init_rotation(struct ao_quaternion *r, + float x, float y, float z, + float s, float c) +{ + r->r = c; + r->x = s * x; + r->y = s * y; + r->z = s * z; +} + +static inline void ao_quaternion_init_zero_rotation(struct ao_quaternion *r) +{ + r->r = 1; + r->x = r->y = r->z = 0; +} + +#endif /* _AO_QUATERNION_H_ */ diff --git a/src/core/ao_sample.c b/src/core/ao_sample.c index dec44f9f..676e0ffd 100644 --- a/src/core/ao_sample.c +++ b/src/core/ao_sample.c @@ -20,6 +20,10 @@ #include <ao_data.h> #endif +#if HAS_GYRO +#include <ao_quaternion.h> +#endif + /* * Current sensor values */ @@ -44,8 +48,7 @@ __pdata accel_t ao_sample_accel_through; __pdata gyro_t ao_sample_roll; __pdata gyro_t ao_sample_pitch; __pdata gyro_t ao_sample_yaw; -__pdata angle_t ao_sample_angle; -__pdata angle_t ao_sample_roll_angle; +__pdata angle_t ao_orient; #endif __data uint8_t ao_sample_data; @@ -86,6 +89,8 @@ __pdata int32_t ao_sample_accel_through_sum; __pdata int32_t ao_sample_pitch_sum; __pdata int32_t ao_sample_yaw_sum; __pdata int32_t ao_sample_roll_sum; +static struct ao_quaternion ao_rotation; +static struct ao_quaternion ao_pad_orientation; #endif static void @@ -129,11 +134,91 @@ ao_sample_preflight_set(void) ao_sample_pitch_sum = 0; ao_sample_yaw_sum = 0; ao_sample_roll_sum = 0; - ao_sample_angle = 0; + ao_orient = 0; + + /* No rotation yet */ + ao_quaternion_init_zero_rotation(&ao_rotation); + + /* XXX Assume we're pointing straight up for now */ + ao_quaternion_init_vector(&ao_pad_orientation, + ao_ground_accel_across, + ao_ground_accel_through, + -ao_ground_accel_along); + ao_quaternion_normalize(&ao_pad_orientation, + &ao_pad_orientation); + + printf ("pad r%8.5f x%8.5f y%8.5f z%8.5f\n", + ao_pad_orientation.r, + ao_pad_orientation.x, + ao_pad_orientation.y, + ao_pad_orientation.z); #endif nsamples = 0; } +#if HAS_GYRO +static void +ao_sample_rotate(void) +{ +#ifdef AO_FLIGHT_TEST + float dt = (ao_sample_tick - ao_sample_prev_tick) / 100.0; +#else + static const float dt = 1/100.0; +#endif + float x = ao_mpu6000_gyro(ao_sample_pitch - ao_ground_pitch) * dt; + float y = ao_mpu6000_gyro(ao_sample_yaw - ao_ground_yaw) * dt; + float z = ao_mpu6000_gyro(ao_sample_roll - ao_ground_roll) * dt; + + float n_2, n; + float s, c; + + struct ao_quaternion rot; + struct ao_quaternion point; + + /* The amount of rotation is just the length of the vector. Now, + * here's the trick -- assume that the rotation amount is small. In this case, + * sin(x) ≃ x, so we can just make this the sin. + */ + + n_2 = x*x + y*y + z*z; + n = sqrtf(n_2); + s = n / 2; + if (s > 1) + s = 1; + c = sqrtf(1 - s*s); + + /* Make unit vector */ + if (n > 0) { + x /= n; + y /= n; + z /= n; + } + + /* Now compute the unified rotation quaternion */ + + ao_quaternion_init_rotation(&rot, + x, y, z, + s, c); + + /* Integrate with the previous rotation amount */ + ao_quaternion_multiply(&ao_rotation, &ao_rotation, &rot); + + /* And normalize to make sure it remains a unit vector */ + ao_quaternion_normalize(&ao_rotation, &ao_rotation); + + /* Compute pitch angle from vertical by taking the pad + * orientation vector and rotating it by the current total + * rotation value. That will be a unit vector pointing along + * the airframe axis. The Z value will be the cosine of the + * change in the angle from vertical since boost + */ + + ao_quaternion_rotate(&point, &ao_pad_orientation, &ao_rotation); + + ao_orient = acosf(point.z) * (float) (180.0/M_PI); +} +#endif + static void ao_sample_preflight(void) { @@ -232,9 +317,12 @@ ao_sample(void) ao_sample_preflight_update(); ao_kalman(); #if HAS_GYRO - /* do quaternion stuff here... */ + ao_sample_rotate(); #endif } +#ifdef AO_FLIGHT_TEST + ao_sample_prev_tick = ao_sample_tick; +#endif ao_sample_data = ao_data_ring_next(ao_sample_data); } return !ao_preflight; @@ -264,7 +352,7 @@ ao_sample_init(void) ao_sample_pitch = 0; ao_sample_yaw = 0; ao_sample_roll = 0; - ao_sample_angle = 0; + ao_orient = 0; #endif ao_sample_data = ao_data_head; ao_preflight = TRUE; diff --git a/src/core/ao_sample.h b/src/core/ao_sample.h index 5bd29536..1d1bcc7c 100644 --- a/src/core/ao_sample.h +++ b/src/core/ao_sample.h @@ -64,8 +64,6 @@ * for all further flight computations */ -#define GRAVITY 9.80665 - /* * Above this height, the baro sensor doesn't work */ @@ -118,6 +116,7 @@ extern __pdata accel_t ao_ground_accel_through; extern __pdata gyro_t ao_ground_pitch; extern __pdata gyro_t ao_ground_yaw; extern __pdata gyro_t ao_ground_roll; +extern __pdata angle_t ao_orient; #endif void ao_sample_init(void); diff --git a/src/core/ao_telemetry.c b/src/core/ao_telemetry.c index 6b47a06a..a2726016 100644 --- a/src/core/ao_telemetry.c +++ b/src/core/ao_telemetry.c @@ -115,6 +115,7 @@ ao_send_mega_sensor(void) telemetry.generic.tick = packet->tick; telemetry.generic.type = AO_TELEMETRY_MEGA_SENSOR; + telemetry.mega_sensor.orient = ao_orient; telemetry.mega_sensor.accel = ao_data_accel(packet); telemetry.mega_sensor.pres = ao_data_pres(packet); telemetry.mega_sensor.temp = ao_data_temp(packet); diff --git a/src/core/ao_telemetry.h b/src/core/ao_telemetry.h index fd6b76b3..237a35ab 100644 --- a/src/core/ao_telemetry.h +++ b/src/core/ao_telemetry.h @@ -162,7 +162,7 @@ struct ao_telemetry_mega_sensor { uint16_t tick; /* 2 */ uint8_t type; /* 4 */ - uint8_t pad5; /* 5 */ + uint8_t orient; /* 5 angle from vertical */ int16_t accel; /* 6 Z axis */ int32_t pres; /* 8 Pa * 10 */ |