Added tri test

git-svn-id: https://arducopter.googlecode.com/svn/trunk@2078 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
jasonshort 2011-05-03 22:13:48 +00:00
parent 2290deb925
commit 7532687495
1 changed files with 30 additions and 0 deletions

View File

@ -7,6 +7,7 @@ static int8_t test_radio(uint8_t argc, const Menu::arg *argv);
static int8_t test_failsafe(uint8_t argc, const Menu::arg *argv); static int8_t test_failsafe(uint8_t argc, const Menu::arg *argv);
static int8_t test_stabilize(uint8_t argc, const Menu::arg *argv); static int8_t test_stabilize(uint8_t argc, const Menu::arg *argv);
static int8_t test_gps(uint8_t argc, const Menu::arg *argv); static int8_t test_gps(uint8_t argc, const Menu::arg *argv);
static int8_t test_tri(uint8_t argc, const Menu::arg *argv);
static int8_t test_adc(uint8_t argc, const Menu::arg *argv); static int8_t test_adc(uint8_t argc, const Menu::arg *argv);
static int8_t test_imu(uint8_t argc, const Menu::arg *argv); static int8_t test_imu(uint8_t argc, const Menu::arg *argv);
//static int8_t test_dcm(uint8_t argc, const Menu::arg *argv); //static int8_t test_dcm(uint8_t argc, const Menu::arg *argv);
@ -57,6 +58,7 @@ const struct Menu::command test_menu_commands[] PROGMEM = {
//{"omega", test_omega}, //{"omega", test_omega},
{"battery", test_battery}, {"battery", test_battery},
{"tune", test_tuning}, {"tune", test_tuning},
{"tri", test_tri},
{"current", test_current}, {"current", test_current},
{"relay", test_relay}, {"relay", test_relay},
{"waypoints", test_wp}, {"waypoints", test_wp},
@ -109,6 +111,9 @@ test_radio_pwm(uint8_t argc, const Menu::arg *argv)
// ---------------------------------------------------------- // ----------------------------------------------------------
read_radio(); read_radio();
// servo Yaw
APM_RC.OutputCh(CH_7, g.rc_4.radio_out);
Serial.printf_P(PSTR("IN: 1: %d\t2: %d\t3: %d\t4: %d\t5: %d\t6: %d\t7: %d\t8: %d\n"), Serial.printf_P(PSTR("IN: 1: %d\t2: %d\t3: %d\t4: %d\t5: %d\t6: %d\t7: %d\t8: %d\n"),
g.rc_1.radio_in, g.rc_1.radio_in,
g.rc_2.radio_in, g.rc_2.radio_in,
@ -125,6 +130,31 @@ test_radio_pwm(uint8_t argc, const Menu::arg *argv)
} }
} }
static int8_t
test_tri(uint8_t argc, const Menu::arg *argv)
{
print_hit_enter();
delay(1000);
while(1){
delay(20);
// Filters radio input - adjust filters in the radio.pde file
// ----------------------------------------------------------
read_radio();
g.rc_4.servo_out = g.rc_4.control_in;
g.rc_4.calc_pwm();
Serial.printf_P(PSTR("input: %d\toutput%d\n"),
g.rc_4.control_in,
g.rc_4.radio_out);
if(Serial.available() > 0){
return (0);
}
}
}
static int8_t static int8_t
test_radio(uint8_t argc, const Menu::arg *argv) test_radio(uint8_t argc, const Menu::arg *argv)
{ {