StoRC
Autonomous Payload Delivery System
controls.h File Reference

Controls header file, contains all controls variables, gains, constants, etc. More...

Go to the source code of this file.

Defines

#define KP_PSI2PHI   0.25
 45deg of bank / 180deg of error
#define target_LAT   399878890
#define target_LON   -752113880
#define DROP_THRESH   400
#define KP_THR   50.0
#define KI_THR   10.0
#define KP_RUD   5.0
#define KD_RUD   3.0
#define KI_RUD   1.0
#define KP_RP   0.05
#define KP_ELE   40.0
#define KI_ELE   10.0

Variables

int throttle_mix_result = 0
 Additional rc control to add to the rudder based on throttle.
unsigned long ptimer = 0
 Perturbation timer for step input perturbation routine.
int sw1 = 0
int sw2 = 0
long dist2drop = 10000000
long LAT_C = target_LAT
long LON_C = target_LON
long del_LAT = 1000000
long del_LON = 1000000
float psi_c = 0.0
float psi_error = 0
int del_ELE = 0
float I_ELE = 0
int rc_ele_trim = 1500
float kp_ele_gm = 1.0
float ki_ele_gm = 1.0
float q_c = 0.0
float q = 0.0
float alpha_q = 0.5
float q_filtered = 0.0
int updated_ALT = 0
float old_ALT = 0
float new_ALT = 0
float del_ALT = 0
int del_THR = 0
int I_THR = 0
int rc_thr_trim = 1500
float kp_thr_gm = 1.0
float ki_thr_gm = 1.0
int del_RUD = 0
int I_RUD = 0
int rc_rud_trim = 1500
float kp_rud_gm = 1.0
float kd_rud_gm = 1.0
float ki_rud_gm = 1.0
int phi_c = 0

Detailed Description

Controls header file, contains all controls variables, gains, constants, etc.

Author:
Michael Posner (CIS, MEAM '12)
Timothy Hennelly (ESE '12)
Jacob Orloff (MEAM '12)

Definition in file controls.h.


Define Documentation

#define DROP_THRESH   400

Definition at line 62 of file controls.h.

#define KD_RUD   3.0

Definition at line 70 of file controls.h.

#define KI_ELE   10.0

Definition at line 76 of file controls.h.

#define KI_RUD   1.0

Definition at line 71 of file controls.h.

#define KI_THR   10.0

Definition at line 66 of file controls.h.

#define KP_ELE   40.0

Definition at line 75 of file controls.h.

#define KP_PSI2PHI   0.25

45deg of bank / 180deg of error

Definition at line 41 of file controls.h.

#define KP_RP   0.05

Definition at line 74 of file controls.h.

#define KP_RUD   5.0

Definition at line 69 of file controls.h.

#define KP_THR   50.0

Definition at line 65 of file controls.h.

#define target_LAT   399878890

Definition at line 44 of file controls.h.

#define target_LON   -752113880

Definition at line 45 of file controls.h.


Variable Documentation

float alpha_q = 0.5

Definition at line 104 of file controls.h.

float del_ALT = 0

Definition at line 111 of file controls.h.

int del_ELE = 0

Definition at line 97 of file controls.h.

long del_LAT = 1000000

Definition at line 91 of file controls.h.

long del_LON = 1000000

Definition at line 92 of file controls.h.

int del_RUD = 0

Definition at line 119 of file controls.h.

int del_THR = 0

Definition at line 112 of file controls.h.

long dist2drop = 10000000

Definition at line 88 of file controls.h.

float I_ELE = 0

Definition at line 98 of file controls.h.

int I_RUD = 0

Definition at line 120 of file controls.h.

int I_THR = 0

Definition at line 113 of file controls.h.

float kd_rud_gm = 1.0

Definition at line 123 of file controls.h.

float ki_ele_gm = 1.0

Definition at line 101 of file controls.h.

float ki_rud_gm = 1.0

Definition at line 124 of file controls.h.

float ki_thr_gm = 1.0

Definition at line 116 of file controls.h.

float kp_ele_gm = 1.0

Definition at line 100 of file controls.h.

float kp_rud_gm = 1.0

Definition at line 122 of file controls.h.

float kp_thr_gm = 1.0

Definition at line 115 of file controls.h.

long LAT_C = target_LAT

Definition at line 89 of file controls.h.

long LON_C = target_LON

Definition at line 90 of file controls.h.

float new_ALT = 0

Definition at line 110 of file controls.h.

float old_ALT = 0

Definition at line 109 of file controls.h.

int phi_c = 0

Definition at line 125 of file controls.h.

float psi_c = 0.0

Definition at line 93 of file controls.h.

float psi_error = 0

Definition at line 94 of file controls.h.

unsigned long ptimer = 0

Perturbation timer for step input perturbation routine.

Definition at line 81 of file controls.h.

float q = 0.0

Definition at line 103 of file controls.h.

float q_c = 0.0

Definition at line 102 of file controls.h.

float q_filtered = 0.0

Definition at line 105 of file controls.h.

int rc_ele_trim = 1500

Definition at line 99 of file controls.h.

int rc_rud_trim = 1500

Definition at line 121 of file controls.h.

int rc_thr_trim = 1500

Definition at line 114 of file controls.h.

int sw1 = 0

Definition at line 84 of file controls.h.

int sw2 = 0

Definition at line 85 of file controls.h.

Additional rc control to add to the rudder based on throttle.

Definition at line 79 of file controls.h.

int updated_ALT = 0

Definition at line 108 of file controls.h.