bug fixes and updates

git-svn-id: https://arducopter.googlecode.com/svn/trunk@1751 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
jasonshort 2011-03-07 06:00:27 +00:00
parent b0e6f40562
commit 6b99e76fcb
4 changed files with 8 additions and 16 deletions

View File

@ -206,8 +206,6 @@ const char* flight_mode_strings[] = {
8 TBD 8 TBD
*/ */
long error_a;
// Radio // Radio
// ----- // -----
int motor_out[4]; int motor_out[4];

View File

@ -75,6 +75,7 @@ handle_process_now()
void void
handle_no_commands() handle_no_commands()
{ {
if (command_must_ID) return;
switch (control_mode){ switch (control_mode){
case LAND: case LAND:
// don't get a new command // don't get a new command
@ -84,6 +85,7 @@ handle_no_commands()
// set_mode(LOITER); // set_mode(LOITER);
default: default:
if()
set_mode(RTL); set_mode(RTL);
//next_command = get_LOITER_home_wp(); //next_command = get_LOITER_home_wp();
//SendDebug("MSG <load_next_command> Preload RTL cmd id: "); //SendDebug("MSG <load_next_command> Preload RTL cmd id: ");

View File

@ -63,6 +63,7 @@ void init_rc_out()
APM_RC.OutputCh(CH_3, g.rc_3.radio_min); APM_RC.OutputCh(CH_3, g.rc_3.radio_min);
APM_RC.OutputCh(CH_4, g.rc_3.radio_min); APM_RC.OutputCh(CH_4, g.rc_3.radio_min);
APM_RC.OutputCh(CH_7, g.rc_3.radio_min); APM_RC.OutputCh(CH_7, g.rc_3.radio_min);
APM_RC.OutputCh(CH_8, g.rc_3.radio_min); APM_RC.OutputCh(CH_8, g.rc_3.radio_min);
} }

View File

@ -11,7 +11,7 @@ static int8_t test_gps(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);
static int8_t test_omega(uint8_t argc, const Menu::arg *argv); //static int8_t test_omega(uint8_t argc, const Menu::arg *argv);
static int8_t test_battery(uint8_t argc, const Menu::arg *argv); static int8_t test_battery(uint8_t argc, const Menu::arg *argv);
static int8_t test_current(uint8_t argc, const Menu::arg *argv); static int8_t test_current(uint8_t argc, const Menu::arg *argv);
static int8_t test_relay(uint8_t argc, const Menu::arg *argv); static int8_t test_relay(uint8_t argc, const Menu::arg *argv);
@ -52,7 +52,7 @@ const struct Menu::command test_menu_commands[] PROGMEM = {
#endif #endif
{"imu", test_imu}, {"imu", test_imu},
//{"dcm", test_dcm}, //{"dcm", test_dcm},
{"omega", test_omega}, //{"omega", test_omega},
{"battery", test_battery}, {"battery", test_battery},
{"current", test_current}, {"current", test_current},
{"relay", test_relay}, {"relay", test_relay},
@ -238,7 +238,6 @@ test_stabilize(uint8_t argc, const Menu::arg *argv)
control_mode = STABILIZE; control_mode = STABILIZE;
Serial.printf_P(PSTR("g.pid_stabilize_roll.kP: %4.4f\n"), g.pid_stabilize_roll.kP()); Serial.printf_P(PSTR("g.pid_stabilize_roll.kP: %4.4f\n"), g.pid_stabilize_roll.kP());
Serial.printf_P(PSTR("max_stabilize_dampener:%d\n\n "), max_stabilize_dampener); Serial.printf_P(PSTR("max_stabilize_dampener:%d\n\n "), max_stabilize_dampener);
Serial.printf_P(PSTR("max_yaw_dampener:%d\n\n "), max_yaw_dampener);
trim_radio(); trim_radio();
@ -286,21 +285,14 @@ test_stabilize(uint8_t argc, const Menu::arg *argv)
set_servos_4(); set_servos_4();
ts_num++; ts_num++;
if (ts_num > 0){ if (ts_num > 10){
ts_num = 0; ts_num = 0;
/*
Serial.printf_P(PSTR("r: %d, p:%d, rc1:%d, "), Serial.printf_P(PSTR("r: %d, p:%d, rc1:%d, "),
(int)(dcm.roll_sensor/100), (int)(dcm.roll_sensor/100),
(int)(dcm.pitch_sensor/100), (int)(dcm.pitch_sensor/100),
g.rc_1.pwm_out); g.rc_1.pwm_out);
*/
Serial.printf_P(PSTR("e:%ld, 4out:%d, O%4.4f\n"), print_motor_out();
error_a,
g.rc_4.servo_out,
omega.z);
//print_motor_out();
} }
// R: 1417, L: 1453 F: 1453 B: 1417 // R: 1417, L: 1453 F: 1453 B: 1417
@ -619,8 +611,7 @@ test_dcm(uint8_t argc, const Menu::arg *argv)
} }
*/ */
///* /*static int8_t
static int8_t
test_omega(uint8_t argc, const Menu::arg *argv) test_omega(uint8_t argc, const Menu::arg *argv)
{ {
static byte ts_num; static byte ts_num;