diff --git a/ArduCopter/test.pde b/ArduCopter/test.pde index 74037faf08..766b23205d 100644 --- a/ArduCopter/test.pde +++ b/ArduCopter/test.pde @@ -16,6 +16,7 @@ static int8_t test_imu(uint8_t argc, const Menu::arg *argv); //static int8_t test_dcm_eulers(uint8_t argc, const Menu::arg *argv); //static int8_t test_dcm(uint8_t argc, const Menu::arg *argv); //static int8_t test_omega(uint8_t argc, const Menu::arg *argv); +//static int8_t test_stab_d(uint8_t argc, const Menu::arg *argv); static int8_t test_battery(uint8_t argc, const Menu::arg *argv); //static int8_t test_boost(uint8_t argc, const Menu::arg *argv); //static int8_t test_wp_nav(uint8_t argc, const Menu::arg *argv); @@ -65,6 +66,7 @@ const struct Menu::command test_menu_commands[] PROGMEM = { {"imu", test_imu}, // {"dcm", test_dcm_eulers}, //{"omega", test_omega}, +// {"stab_d", test_stab_d}, {"battery", test_battery}, {"tune", test_tuning}, //{"tri", test_tri}, @@ -592,6 +594,42 @@ test_gps(uint8_t argc, const Menu::arg *argv) return 0; } +// used to test the gain scheduler for Stab_D +/* +static int8_t +test_stab_d(uint8_t argc, const Menu::arg *argv) +{ + int16_t i = 0; + g.stabilize_d = 1; + + g.stabilize_d_schedule = 1 + for (i = -4600; i < 4600; i+=10) { + new_radio_frame = true; + g.rc_1.control_in = i; + g.rc_2.control_in = i; + update_roll_pitch_mode(); + Serial.printf("rin:%d, d:%1.6f \tpin:%d, d:%1.6f\n",g.rc_1.control_in, roll_scale_d, g.rc_2.control_in, pitch_scale_d); + } + g.stabilize_d_schedule = .5 + for (i = -4600; i < 4600; i+=10) { + new_radio_frame = true; + g.rc_1.control_in = i; + g.rc_2.control_in = i; + update_roll_pitch_mode(); + Serial.printf("rin:%d, d:%1.6f \tpin:%d, d:%1.6f\n",g.rc_1.control_in, roll_scale_d, g.rc_2.control_in, pitch_scale_d); + } + + g.stabilize_d_schedule = 0 + for (i = -4600; i < 4600; i+=10) { + new_radio_frame = true; + g.rc_1.control_in = i; + g.rc_2.control_in = i; + update_roll_pitch_mode(); + Serial.printf("rin:%d, d:%1.6f \tpin:%d, d:%1.6f\n",g.rc_1.control_in, roll_scale_d, g.rc_2.control_in, pitch_scale_d); + } + +}*/ + /* //static int8_t //test_dcm(uint8_t argc, const Menu::arg *argv)