Copter: move update_commands to run_autopilot fn

update_commands was being run in the medium_loop counter but it is
easier to understand the flow of the code if it is consolidated along
with other autopilot calls.
This commit is contained in:
Randy Mackay 2013-04-24 20:59:49 +09:00
parent 6deaae3844
commit 74dca6da22
3 changed files with 10 additions and 18 deletions

View File

@ -1094,14 +1094,6 @@ static void medium_loop()
case 3: case 3:
medium_loopCounter++; medium_loopCounter++;
// perform next command
// --------------------
if(control_mode == AUTO) {
if(ap.home_is_set && (g.command_total > 1)) {
update_commands();
}
}
if(motors.armed()) { if(motors.armed()) {
if (g.log_bitmask & MASK_LOG_ATTITUDE_MED) { if (g.log_bitmask & MASK_LOG_ATTITUDE_MED) {
Log_Write_Attitude(); Log_Write_Attitude();

View File

@ -142,26 +142,24 @@ static void execute_nav_command(void)
} }
// verify_commands - high level function to check if navigation and conditional commands have completed // verify_commands - high level function to check if navigation and conditional commands have completed
// called after GPS navigation update - not constantly
static void verify_commands(void) static void verify_commands(void)
{ {
// check if navigation command completed
if(verify_must()) { if(verify_must()) {
//cliSerial->printf("verified must cmd %d\n" , command_nav_index); // clear navigation command queue so next command can be loaded
command_nav_queue.id = NO_COMMAND; command_nav_queue.id = NO_COMMAND;
// store our most recent executed nav command // store our most recent executed nav command
prev_nav_index = command_nav_index; prev_nav_index = command_nav_index;
// Wipe existing conditionals // Wipe existing conditionals
command_cond_index = NO_COMMAND; command_cond_index = NO_COMMAND;
command_cond_queue.id = NO_COMMAND; command_cond_queue.id = NO_COMMAND;
}else{
//cliSerial->printf("verified must false %d\n" , command_nav_index);
} }
// check if conditional command completed
if(verify_may()) { if(verify_may()) {
//cliSerial->printf("verified may cmd %d\n" , command_cond_index); // clear conditional command queue so next command can be loaded
command_cond_queue.id = NO_COMMAND; command_cond_queue.id = NO_COMMAND;
} }
} }
@ -195,7 +193,6 @@ static void exit_mission()
set_mode(LAND); set_mode(LAND);
}else{ }else{
set_mode(LOITER); set_mode(LOITER);
wp_nav.set_desired_alt(g.rtl_alt_final);
} }
} }

View File

@ -85,7 +85,10 @@ static void run_autopilot()
{ {
switch( control_mode ) { switch( control_mode ) {
case AUTO: case AUTO:
// majority of command logic is in commands_logic.pde // load the next command if the command queues are empty
update_commands();
// process the active navigation and conditional commands
verify_commands(); verify_commands();
break; break;
case GUIDED: case GUIDED: