diff --git a/Attic/attitude.c b/Attic/attitude.c deleted file mode 100644 index 92bc73f..0000000 --- a/Attic/attitude.c +++ /dev/null @@ -1,128 +0,0 @@ -#include "attitude.h" -#include "util.h" -#include - -struct dcm dcm = { - .matrix = MAT3_IDENTITY, - .down_ref = { 0, 0, -1 }, - .north_ref = { 1, 0, 0 }, -/* - .acc_kp = 1, .acc_ki = 0.001, - .mag_kp = 0, .mag_ki = 0 -*/ -}; - - -/** - * Apply an infinitesimal rotation w*dt to a direction cosine matrix A. - * An orthonormalization step is added to prevent rounding errors. - * - * Without the normalization, this would be a simple matrix multiplication: - * - * return mat3_matmul( A, (mat3f) { - * 1, -w.z, w.y, - * w.z, 1, -w.x, - * -w.y, w.x, 1 - * }; - */ -static mat3f dcm_integrate(mat3f A, vec3f w, float dt) -{ - w = vec3f_scale(w, dt); - - // Calculate the new x and y axes. z is calculated later. - // - vec3f x = vec3f_matmul(A, (vec3f){ 1, w.z, -w.y } ); - vec3f y = vec3f_matmul(A, (vec3f){ -w.z, 1, w.x } ); - - // Orthonormalization - // - // First we compute the dot product of the x and y rows of the matrix, which - // is supposed to be zero, so the result is a measure of how much the X and Y - // rows are rotating toward each other - // - float error = vec3f_dot(x, y); - - // We apportion half of the error each to the x and y rows, and approximately - // rotate the X and Y rows in the opposite direction by cross coupling: - // - vec3f xo, yo, zo; - xo = vec3f_sub(x, vec3f_scale(y, 0.5 * error)); - yo = vec3f_sub(y, vec3f_scale(x, 0.5 * error)); - - // Scale them to unit length and take a cross product for the Z axis - // - xo = vec3f_norm_fast(xo); - yo = vec3f_norm_fast(yo); - zo = vec3f_cross(xo, yo); - - return (mat3f) { - xo.x, yo.x, zo.x, - xo.y, yo.y, zo.y, - xo.z, yo.z, zo.z - }; -} - - -extern void dcm_update(vec3f gyro, vec3f acc, float dt) -{ - dcm.offset_p = vec3f_zero; - - // Apply accelerometer correction - // - vec3f down = vec3f_matmul(dcm.matrix, vec3f_norm_fast(acc)); - vec3f error = vec3f_cross(down, dcm.down_ref); - - dcm.debug = error; - - dcm.offset_p = vec3f_add(dcm.offset_p, vec3f_scale(error, dcm.acc_kp)); - dcm.offset_i = vec3f_add(dcm.offset_i, vec3f_scale(error, dcm.acc_ki)); - - // todo: magnetometer correction, once we have one - - // Calculate drift-corrected roll, pitch and yaw angles - // - dcm.omega = gyro; - dcm.omega = vec3f_add(dcm.omega, dcm.offset_p); - dcm.omega = vec3f_add(dcm.omega, dcm.offset_i); - - // Apply rotation to the direction cosine matrix - // - dcm.matrix = dcm_integrate(dcm.matrix, dcm.omega, dt); - dcm.euler = mat3f_to_euler(dcm.matrix); -} - - -void dcm_reset(void) -{ - dcm.matrix = mat3f_identity; - dcm.euler = vec3f_zero; - dcm.omega = vec3f_zero; - dcm.offset_p = vec3f_zero; - dcm.offset_i = vec3f_zero; -} - -// ----- -#include - - -void cmd_dcm_show(void) -{ - struct dcm d; - ATOMIC_COPY(&d, &dcm, sizeof(d)); - - printf(" x/roll y/pitch z/yaw\n"); - printf("down_ref : %10.4f %10.4f %10.4f\n", d.down_ref.x, d.down_ref.y, d.down_ref.z); - printf("north_ref : %10.4f %10.4f %10.4f\n", d.north_ref.x, d.north_ref.y, d.north_ref.z); - printf("\n"); - printf("offset_p : %10.4f %10.4f %10.4f\n", d.offset_p.x, d.offset_p.y, d.offset_p.z); - printf("offset_i : %10.4f %10.4f %10.4f\n", d.offset_i.x, d.offset_i.y, d.offset_i.z); - printf("\n"); - printf("dcm_omega : %10.4f %10.4f %10.4f\n", d.omega.x, d.omega.y, d.omega.z); - printf("dcm_euler : %10.4f %10.4f %10.4f\n", d.euler.x, d.euler.y, d.euler.z); - printf("\n"); - printf("dcm_matrix: %10.4f %10.4f %10.4f\n", d.matrix.m00, d.matrix.m01, d.matrix.m02); - printf(" %10.4f %10.4f %10.4f\n", d.matrix.m10, d.matrix.m11, d.matrix.m12); - printf(" %10.4f %10.4f %10.4f\n", d.matrix.m20, d.matrix.m21, d.matrix.m22); - printf("\n"); - printf("debug : %10.4f %10.4f %10.4f\n", d.debug.x, d.debug.y, d.debug.z); -} diff --git a/Attic/attitude.h b/Attic/attitude.h deleted file mode 100644 index f84ad04..0000000 --- a/Attic/attitude.h +++ /dev/null @@ -1,32 +0,0 @@ -#ifndef ATTITUDE_H -#define ATTITUDE_H - -#include "matrix3f.h" - -struct dcm { - mat3f matrix; ///< current direction cosine matrix - vec3f euler; ///< roll, pitch and yaw angles - vec3f omega; ///< drift corrected angular rates - - vec3f offset_p; ///< drift correction p-term - vec3f offset_i; ///< drift correction i-term - - vec3f down_ref; ///< accelerometer "down" reference - float acc_kp; ///< accelerometer p gain - float acc_ki; ///< accelerometer i gain - - vec3f north_ref; ///< magnetometer "north" reference - float mag_kp; ///< magnetometer p gain - float mag_ki; ///< magnetometer i gain - - vec3f debug; -}; - -extern struct dcm dcm; - -extern void dcm_update(vec3f gyro, vec3f acc, float dt); -extern void dcm_reset(void); - -extern void cmd_dcm_show(void); - -#endif diff --git a/Makefile b/Makefile index 7d0dc6f..f879368 100644 --- a/Makefile +++ b/Makefile @@ -207,6 +207,7 @@ CFLAGS += -ffunction-sections CFLAGS += -fdata-sections CFLAGS += -Wall CFLAGS += -Wstrict-prototypes +CFLAGS += -Wsign-compare #CFLAGS += -Wextra #CFLAGS += -Wpointer-arith #CFLAGS += -Winline diff --git a/Source/attitude.c b/Source/attitude.c index 31e6123..28cec1d 100644 --- a/Source/attitude.c +++ b/Source/attitude.c @@ -1,5 +1,6 @@ #include "attitude.h" #include "util.h" +#include "sensors.h" #include struct dcm dcm = { @@ -63,13 +64,13 @@ static mat3f dcm_integrate(mat3f A, vec3f w, float dt) } -extern void dcm_update(vec3f gyro, vec3f acc, float dt) +extern void dcm_update(struct sensor_data *sensor, float dt) { dcm.offset_p = vec3f_zero; // Apply accelerometer correction // - vec3f down = vec3f_matmul(dcm.matrix, vec3f_norm(acc)); + vec3f down = vec3f_matmul(dcm.matrix, vec3f_norm(sensor->acc)); vec3f error = vec3f_cross(down, dcm.down_ref); dcm.debug = error; @@ -81,7 +82,7 @@ extern void dcm_update(vec3f gyro, vec3f acc, float dt) // Calculate drift-corrected roll, pitch and yaw angles // - dcm.omega = gyro; + dcm.omega = sensor->gyro; dcm.omega = vec3f_add(dcm.omega, dcm.offset_p); dcm.omega = vec3f_add(dcm.omega, dcm.offset_i); @@ -103,12 +104,13 @@ void dcm_reset(void) // ----- #include +#include "command.h" -void cmd_dcm_show(void) +static void cmd_dcm_show(void) { struct dcm d; - ATOMIC_COPY(&d, &dcm, sizeof(d)); + memcpy(&d, &dcm, sizeof(d)); printf(" x/roll y/pitch z/yaw\n"); printf("down_ref : %10.4f %10.4f %10.4f\n", d.down_ref.x, d.down_ref.y, d.down_ref.z); @@ -126,3 +128,5 @@ void cmd_dcm_show(void) printf("\n"); printf("debug : %10.4f %10.4f %10.4f\n", d.debug.x, d.debug.y, d.debug.z); } + +SHELL_CMD(dcm_show, (cmdfunc_t)cmd_dcm_show, "show dcm values") diff --git a/Source/attitude.h b/Source/attitude.h index 5fc786f..e7460d0 100644 --- a/Source/attitude.h +++ b/Source/attitude.h @@ -1,6 +1,7 @@ #pragma once #include "matrix3f.h" +#include "sensors.h" struct dcm { mat3f matrix; ///< current direction cosine matrix @@ -23,8 +24,5 @@ struct dcm { extern struct dcm dcm; -extern void dcm_update(vec3f gyro, vec3f acc, float dt); +extern void dcm_update(struct sensor_data *sensor, float dt); extern void dcm_reset(void); - -extern void cmd_dcm_show(void); - diff --git a/Source/dma_io_driver.c b/Source/dma_io_driver.c index 0d5b965..53c5d7c 100644 --- a/Source/dma_io_driver.c +++ b/Source/dma_io_driver.c @@ -42,7 +42,7 @@ void DMA2_Stream7_IRQHandler(void) uint16_t tim7_cnt = TIM7->CNT; uint32_t hisr = DMA2->HISR; - const int len_2 = DMA_IO_RX_SIZE / 2; + const unsigned int len_2 = DMA_IO_RX_SIZE / 2; const uint8_t mask = ~dma_tx_ws2812_bits; if (hisr & DMA_HISR_HTIF7) { diff --git a/Source/dma_io_servo_in.c b/Source/dma_io_servo_in.c index 4a389d2..e3b415f 100644 --- a/Source/dma_io_servo_in.c +++ b/Source/dma_io_servo_in.c @@ -20,7 +20,7 @@ static void edge(uint32_t t, int ch, int rising) } -void dma_io_decode_servo(const void *dma_buf, int dma_len, uint8_t mask) +void dma_io_decode_servo(const void *dma_buf, unsigned int dma_len, uint8_t mask) { // TODO: filter edges // TODO: detect timeouts @@ -31,12 +31,12 @@ void dma_io_decode_servo(const void *dma_buf, int dma_len, uint8_t mask) const uint32_t *src = dma_buf; uint32_t mask32 = (mask<<24) | (mask<<16) | (mask<<8) | mask; - for (int i=0; i < dma_len / 4; i++) { + for (unsigned int i=0; i < dma_len / 4; i++) { uint32_t state = *src++ & mask32; uint32_t diff = last_state ^ state; if (diff) { - for (int j=0; j<32; j++) { + for (unsigned int j=0; j<32; j++) { if (diff & (1UL << j)) edge(t + (j>>3), j & 7, state & (1UL << j)); } diff --git a/Source/dma_io_servo_in.h b/Source/dma_io_servo_in.h index a403c13..7d26d1b 100644 --- a/Source/dma_io_servo_in.h +++ b/Source/dma_io_servo_in.h @@ -12,7 +12,6 @@ extern struct dma_io_servo_in dma_io_servo_in[8]; void dma_io_decode_servo( - const void *dma_buf, int dma_len, uint8_t mask + const void *dma_buf, unsigned int dma_len, uint8_t mask ); - diff --git a/Source/dma_io_servo_out.h b/Source/dma_io_servo_out.h index daa172d..1779d76 100644 --- a/Source/dma_io_servo_out.h +++ b/Source/dma_io_servo_out.h @@ -3,7 +3,6 @@ #include void dma_io_set_servo( - void *dma_buf, int dma_len, uint8_t mask, + void *dma_buf, unsigned int dma_len, uint8_t mask, int t_pulse ); - diff --git a/Source/filter.c b/Source/filter.c index c3ffca1..f0c22f2 100644 --- a/Source/filter.c +++ b/Source/filter.c @@ -142,7 +142,7 @@ void avg_reset(struct avg_filter *f, int32_t x) { f->index = 0; f->acc = x * f->size; - for (int i=0; isize; i++) + for (uint32_t i=0; isize; i++) f->buf[i] = x; } diff --git a/Source/flight_ctrl.c b/Source/flight_ctrl.c index 378d7fc..feffb50 100644 --- a/Source/flight_ctrl.c +++ b/Source/flight_ctrl.c @@ -3,6 +3,7 @@ #include "bldc_task.h" #include "rc_input.h" #include "util.h" +#include "attitude.h" #include "FreeRTOS.h" #include "task.h" @@ -11,16 +12,41 @@ static struct sensor_data sensor_data; static struct rc_input rc_input; -struct pid_ctrl pid_pitch = { .kp = 1, .ki = 0, .kd = 0, .min = -5, .max = 5, .dt = 1e-3 }; -struct pid_ctrl pid_roll = { .kp = 1, .ki = 0, .kd = 0, .min = -5, .max = 5, .dt = 1e-3 }; -struct pid_ctrl pid_yaw = { .kp = 1, .ki = 0, .kd = 0, .min = -5, .max = 5, .dt = 1e-3 }; +struct pid_ctrl pid_pitch = { .min = -5, .max = 5, .dt = 1e-3 }; +struct pid_ctrl pid_roll = { .min = -5, .max = 5, .dt = 1e-3 }; +struct pid_ctrl pid_yaw = { .min = -5, .max = 5, .dt = 1e-3 }; -float rc_pitch, rc_roll, rc_yaw, rc_thrust; +float rc_pitch, rc_roll, rc_yaw, rc_thrust; -float foo = 1; -float bar = 0; -float baz = 0; +float pid_p = 1; +float pid_i = 0; +float pid_d = 0; +uint8_t fc_state = 0; +/* +void systick_handler(void) +{ + dcm_update( + sensor_data.gyro, + sensor_data.acc, + 1.0 / SYSTICK_FREQ + ); + + flt_pid_update(&pid_pitch, (rc_pitch - dcm.euler.x), 0); + flt_pid_update(&pid_roll , (rc_roll - dcm.euler.y), 0); + flt_pid_update(&pid_yaw , (rc_yaw - dcm.euler.z), 0); + + int pwm_front = rc_thrust + pid_pitch.out + pid_yaw.out; + int pwm_back = rc_thrust - pid_pitch.out + pid_yaw.out; + int pwm_left = rc_thrust + pid_roll.out - pid_yaw.out; + int pwm_right = rc_thrust - pid_roll.out - pid_yaw.out; + + motor[ID_FRONT].pwm = clamp(pwm_front, 32, 400); + motor[ID_BACK ].pwm = clamp(pwm_back , 32, 400); + motor[ID_LEFT ].pwm = clamp(pwm_left , 32, 400); + motor[ID_RIGHT].pwm = clamp(pwm_right, 32, 400); +} +*/ void flight_ctrl(void *pvParameters) { //uint32_t t0 = xTaskGetTickCount(); @@ -32,8 +58,11 @@ void flight_ctrl(void *pvParameters) vTaskDelay(1000); - int ok = 0; - int old_ok = 0; + uint8_t ok = 0; + uint8_t old_ok = 0; + uint8_t stop_once = 0; + + dcm_reset(); for (;;) { sensor_read(&sensor_data); @@ -60,23 +89,31 @@ void flight_ctrl(void *pvParameters) ok = 0; } - pid_pitch.kp = foo; - pid_roll.kp = foo; - pid_yaw.kp = foo; - - pid_pitch.ki = bar; - pid_roll.ki = bar; - pid_yaw.ki = bar; + if (fc_state & 1) { + pid_pitch.kp = pid_p; + pid_roll .kp = pid_p; + pid_yaw .kp = pid_p; - pid_pitch.kd = baz; - pid_roll.kd = baz; - pid_yaw.kd = baz; + pid_pitch.ki = pid_i; + pid_roll .ki = pid_i; + pid_yaw .ki = pid_i; - pid_update(&pid_pitch, (rc_pitch - sensor_data.gyro.x), 0); - pid_update(&pid_roll , (rc_roll + sensor_data.gyro.y), 0); - pid_update(&pid_yaw , (rc_yaw + sensor_data.gyro.z), 0); + pid_pitch.kd = pid_d; + pid_roll .kd = pid_d; + pid_yaw .kd = pid_d; + } + if (fc_state & 2 || !(rc_input.channels[5] < 1500)) { + dcm_update(&sensor_data, 1e-3); + pid_update(&pid_pitch, (rc_pitch - dcm.euler.x), 0); + pid_update(&pid_roll , (rc_roll + dcm.euler.y), 0); + pid_update(&pid_yaw , (rc_yaw + dcm.euler.z), 0); + } else { + pid_update(&pid_pitch, (rc_pitch - sensor_data.gyro.x), 0); + pid_update(&pid_roll , (rc_roll + sensor_data.gyro.y), 0); + pid_update(&pid_yaw , (rc_yaw + sensor_data.gyro.z), 0); + } if (ok) { bldc_state.motors[ID_FL].u_d = clamp(rc_thrust + pid_pitch.u - pid_roll.u - pid_yaw.u, 1, 10); bldc_state.motors[ID_FR].u_d = clamp(rc_thrust + pid_pitch.u + pid_roll.u + pid_yaw.u, 1, 10); @@ -89,12 +126,14 @@ void flight_ctrl(void *pvParameters) bldc_state.motors[ID_RL].state = STATE_START; bldc_state.motors[ID_RR].state = STATE_START; } + stop_once = 0; } - else { + else if (!stop_once) { bldc_state.motors[ID_FL].state = STATE_STOP; bldc_state.motors[ID_FR].state = STATE_STOP; bldc_state.motors[ID_RL].state = STATE_STOP; bldc_state.motors[ID_RR].state = STATE_STOP; + stop_once = 1; } old_ok = ok; diff --git a/Source/flight_ctrl.h b/Source/flight_ctrl.h index 5dd63df..25a9270 100644 --- a/Source/flight_ctrl.h +++ b/Source/flight_ctrl.h @@ -2,3 +2,7 @@ void flight_ctrl(void *pvParameters); + + +extern float pid_p, pid_i, pid_d; +extern struct pid_ctrl pid_pitch, pid_roll, pid_yaw; diff --git a/Source/param_table.c b/Source/param_table.c index e67521e..d928ccb 100644 --- a/Source/param_table.c +++ b/Source/param_table.c @@ -7,11 +7,11 @@ #include "rc_ppm.h" #include "dma_io_driver.h" #include "sensors.h" +#include "flight_ctrl.h" +#include "attitude.h" static int board_address; -extern float foo, bar, baz; - const struct param_info param_table[] = { { 1, P_INT32(&board_address ), READONLY, .name = "board_address" }, { 4, P_INT32((int*)&warnings.w ), NOEEPROM, .name = "warning_flags" }, @@ -96,9 +96,68 @@ const struct param_info param_table[] = { .help = "PPM sum signal synchronization pulse width" }, - { 300, P_FLOAT(&foo) }, - { 301, P_FLOAT(&bar) }, - { 302, P_FLOAT(&baz) }, + { 300, P_FLOAT(&pid_p, 1, 0 , 10), + .name = "pid_p", + .help = "all gyro PID P Part" + }, + { 301, P_FLOAT(&pid_i, 0, 0, 10), + .name = "pid_i", + .help = "all gyro PID I Part" + }, + { 302, P_FLOAT(&pid_d, 0, 0, 10), + .name = "pid_d", + .help = "all gyro PID D Part" + }, + + + { 310, P_FLOAT(&pid_pitch.kp, 1, 0, 10), + .name = "pid_pitch.kp", + .help = "gyro pitch PID P Part" + }, + { 311, P_FLOAT(&pid_pitch.ki, 0, 0 ,10), + .name = "pid_pitch.ki", + .help = "gyro pitch PID I Part" + }, + { 312, P_FLOAT(&pid_pitch.kd, 0, 0, 10), + .name = "pid_pitch.kd", + .help = "gyro pitch PID D Part" + }, + + { 320, P_FLOAT(&pid_roll.kp, 1, 0, 10), + .name = "pid_roll.kp", + .help = "gyro roll PID P Part" + }, + { 321, P_FLOAT(&pid_roll.ki, 0, 0, 10), + .name = "pid_roll.ki", + .help = "gyro roll PID I Part" + }, + { 322, P_FLOAT(&pid_roll.kd, 0, 0, 10), + .name = "pid_roll.kd", + .help = "gyro roll PID D Part" + }, + + { 330, P_FLOAT(&pid_yaw.kp, 1, 0, 10), + .name = "pid_yaw.kp", + .help = "gyro yaw PID P Part" + }, + { 331, P_FLOAT(&pid_yaw.ki, 0, 0, 10), + .name = "pid_yaw.ki", + .help = "gyro yaw PID I Part" + }, + { 332, P_FLOAT(&pid_yaw.kd, 0, 0, 10), + .name = "pid_yaw.kd", + .help = "gyro yaw PID D Part" + }, + + { 360, P_FLOAT(&dcm.acc_kp, 0, 0, 10), + .name = "dcm.acc_kp", + .help = "DCM acc P Part" + }, + + { 361, P_FLOAT(&dcm.acc_ki, 0, 0, 10), + .name = "dcm.acc_ki", + .help = "DCM acc I Part" + }, // Debug DAC outputs // diff --git a/Source/rc_input.c b/Source/rc_input.c index f15657b..26481ed 100644 --- a/Source/rc_input.c +++ b/Source/rc_input.c @@ -76,7 +76,7 @@ static void cmd_rc_show(void) rc_strmode(rc_config.mode), rc.valid, rc.rssi, rc.num_channels ); - for (int i=0; i