Browse Source

removed saving - not needed for copters

mission-4.1.18
Jason Short 14 years ago
parent
commit
ddc5ced162
  1. 2
      ArduCopter/commands.pde
  2. 2
      ArduCopter/commands_process.pde

2
ArduCopter/commands.pde

@ -3,7 +3,7 @@ @@ -3,7 +3,7 @@
static void init_commands()
{
// zero is home, but we always load the next command (1), in the code.
g.waypoint_index.set_and_save(0);
g.waypoint_index = 0;
// This are registers for the current may and must commands
// setting to zero will allow them to be written to by new commands

2
ArduCopter/commands_process.pde

@ -11,7 +11,7 @@ static void change_command(uint8_t index) @@ -11,7 +11,7 @@ static void change_command(uint8_t index)
} else {
command_must_index = NO_COMMAND;
next_command.id = NO_COMMAND;
g.waypoint_index.set_and_save(index - 1);
g.waypoint_index = index - 1;
update_commands();
}
}

Loading…
Cancel
Save