mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
uncrustify ArduPlane/commands_process.pde
This commit is contained in:
parent
6fd4a68c5c
commit
a7ffcfd037
@ -6,7 +6,7 @@ void change_command(uint8_t cmd_index)
|
|||||||
{
|
{
|
||||||
struct Location temp = get_cmd_with_index(cmd_index);
|
struct Location temp = get_cmd_with_index(cmd_index);
|
||||||
|
|
||||||
if (temp.id > MAV_CMD_NAV_LAST ){
|
if (temp.id > MAV_CMD_NAV_LAST ) {
|
||||||
gcs_send_text_P(SEVERITY_LOW,PSTR("Bad Request - cannot change to non-Nav cmd"));
|
gcs_send_text_P(SEVERITY_LOW,PSTR("Bad Request - cannot change to non-Nav cmd"));
|
||||||
} else {
|
} else {
|
||||||
gcs_send_text_fmt(PSTR("Received Request - jump to command #%i"),cmd_index);
|
gcs_send_text_fmt(PSTR("Received Request - jump to command #%i"),cmd_index);
|
||||||
@ -25,8 +25,8 @@ void change_command(uint8_t cmd_index)
|
|||||||
// --------------------
|
// --------------------
|
||||||
static void update_commands(void)
|
static void update_commands(void)
|
||||||
{
|
{
|
||||||
if(control_mode == AUTO){
|
if(control_mode == AUTO) {
|
||||||
if(home_is_set == true && g.command_total > 1){
|
if(home_is_set == true && g.command_total > 1) {
|
||||||
process_next_command();
|
process_next_command();
|
||||||
}
|
}
|
||||||
} // Other (eg GCS_Auto) modes may be implemented here
|
} // Other (eg GCS_Auto) modes may be implemented here
|
||||||
@ -34,11 +34,11 @@ static void update_commands(void)
|
|||||||
|
|
||||||
static void verify_commands(void)
|
static void verify_commands(void)
|
||||||
{
|
{
|
||||||
if(verify_nav_command()){
|
if(verify_nav_command()) {
|
||||||
nav_command_ID = NO_COMMAND;
|
nav_command_ID = NO_COMMAND;
|
||||||
}
|
}
|
||||||
|
|
||||||
if(verify_condition_command()){
|
if(verify_condition_command()) {
|
||||||
non_nav_command_ID = NO_COMMAND;
|
non_nav_command_ID = NO_COMMAND;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -54,7 +54,7 @@ static void process_next_command()
|
|||||||
|
|
||||||
// these are Navigation/Must commands
|
// these are Navigation/Must commands
|
||||||
// ---------------------------------
|
// ---------------------------------
|
||||||
if (nav_command_ID == NO_COMMAND){ // no current navigation command loaded
|
if (nav_command_ID == NO_COMMAND) { // no current navigation command loaded
|
||||||
old_index = nav_command_index;
|
old_index = nav_command_index;
|
||||||
temp.id = MAV_CMD_NAV_LAST;
|
temp.id = MAV_CMD_NAV_LAST;
|
||||||
while(temp.id >= MAV_CMD_NAV_LAST && nav_command_index <= g.command_total) {
|
while(temp.id >= MAV_CMD_NAV_LAST && nav_command_index <= g.command_total) {
|
||||||
@ -64,7 +64,7 @@ static void process_next_command()
|
|||||||
|
|
||||||
gcs_send_text_fmt(PSTR("Nav command index updated to #%i"),nav_command_index);
|
gcs_send_text_fmt(PSTR("Nav command index updated to #%i"),nav_command_index);
|
||||||
|
|
||||||
if(nav_command_index > g.command_total){
|
if(nav_command_index > g.command_total) {
|
||||||
// we are out of commands!
|
// we are out of commands!
|
||||||
gcs_send_text_P(SEVERITY_LOW,PSTR("out of commands!"));
|
gcs_send_text_P(SEVERITY_LOW,PSTR("out of commands!"));
|
||||||
handle_no_commands();
|
handle_no_commands();
|
||||||
|
Loading…
Reference in New Issue
Block a user