From 77da1227bb2d681559c2be131e4a36187b9b69e0 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sat, 19 Nov 2011 23:21:49 -0800 Subject: [PATCH] renamed set_cmd function --- ArduCopter/commands.pde | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/ArduCopter/commands.pde b/ArduCopter/commands.pde index 0c3298fbab..c00a5a9fa0 100644 --- a/ArduCopter/commands.pde +++ b/ArduCopter/commands.pde @@ -50,11 +50,11 @@ static struct Location get_cmd_with_index(int i) } // Add on home altitude if we are a nav command (or other command with altitude) and stored alt is relative - //if((temp.id < MAV_CMD_NAV_LAST || temp.id == MAV_CMD_CONDITION_CHANGE_ALT) && temp.options & WP_OPTION_ALT_RELATIVE){ + //if((temp.id < MAV_CMD_NAV_LAST || temp.id == MAV_CMD_CONDITION_CHANGE_ALT) && temp.options & MASK_OPTIONS_RELATIVE_ALT){ //temp.alt += home.alt; //} - if(temp.options & WP_OPTION_RELATIVE){ + if(temp.options & MASK_OPTIONS_RELATIVE_ALT){ // If were relative, just offset from home temp.lat += home.lat; temp.lng += home.lng; @@ -65,7 +65,7 @@ static struct Location get_cmd_with_index(int i) // Setters // ------- -static void set_command_with_index(struct Location temp, int i) +static void set_cmd_with_index(struct Location temp, int i) { i = constrain(i, 0, g.command_total.get()); //Serial.printf("set_command: %d with id: %d\n", i, temp.id); @@ -203,7 +203,7 @@ static void init_home() // Save Home to EEPROM // ------------------- // no need to save this to EPROM - set_command_with_index(home, 0); + set_cmd_with_index(home, 0); print_wp(&home, 0); // Save prev loc this makes the calcs look better before commands are loaded