diff --git a/ArduCopter/commands_logic.pde b/ArduCopter/commands_logic.pde index 31b8bd25df09ce46643dec2815d2445ab3e225b3..2a71e3f6d045ccfe60f606875e9552c0491546fe 100644 --- a/ArduCopter/commands_logic.pde +++ b/ArduCopter/commands_logic.pde @@ -47,6 +47,7 @@ static void process_nav_command() } +// process_cond_command - main switch statement to initiate the next conditional command in the command_cond_queue static void process_cond_command() { switch(command_cond_queue.id) { @@ -72,6 +73,8 @@ static void process_cond_command() } } +// process_now_command - main switch statement to initiate the next now command in the command_cond_queue +// now commands are conditional commands that are executed immediately so they do not require a corresponding verify to be run later static void process_now_command() { switch(command_cond_queue.id) { @@ -136,9 +139,9 @@ static void process_now_command() // Verify command Handlers /********************************************************************************/ -// verify_must - switch statement to ensure the active navigation command is progressing +// verify_nav_command - switch statement to ensure the active navigation command is progressing // returns true once the active navigation command completes successfully -static bool verify_must() +static bool verify_nav_command() { switch(command_nav_queue.id) { @@ -181,9 +184,9 @@ static bool verify_must() } } -// verify_may - switch statement to ensure the active conditional command is progressing +// verify_cond_command - switch statement to ensure the active conditional command is progressing // returns true once the active conditional command completes successfully -static bool verify_may() +static bool verify_cond_command() { switch(command_cond_queue.id) { diff --git a/ArduCopter/commands_process.pde b/ArduCopter/commands_process.pde index 550546b233fb0e8b608f6497c66dd01f418841d1..99f0bf6bc1eaf0696179234396c40f2986593d8d 100644 --- a/ArduCopter/commands_process.pde +++ b/ArduCopter/commands_process.pde @@ -145,7 +145,7 @@ static void execute_nav_command(void) static void verify_commands(void) { // check if navigation command completed - if(verify_must()) { + if(verify_nav_command()) { // clear navigation command queue so next command can be loaded command_nav_queue.id = NO_COMMAND; @@ -158,7 +158,7 @@ static void verify_commands(void) } // check if conditional command completed - if(verify_may()) { + if(verify_cond_command()) { // clear conditional command queue so next command can be loaded command_cond_queue.id = NO_COMMAND; }