From f83fb23d7a07a7770bd30d8bdd0f6cea8ef5215f Mon Sep 17 00:00:00 2001 From: James Goppert Date: Sun, 2 Oct 2011 23:32:12 -0400 Subject: [PATCH] Removed extra waypoint loading. --- libraries/APO/AP_Guide.h | 8 +++----- 1 file changed, 3 insertions(+), 5 deletions(-) diff --git a/libraries/APO/AP_Guide.h b/libraries/APO/AP_Guide.h index fb4352f830..d546bacb4e 100644 --- a/libraries/APO/AP_Guide.h +++ b/libraries/APO/AP_Guide.h @@ -62,9 +62,7 @@ public: void setCurrentIndex(uint8_t val) { _cmdIndex.set_and_save(val); _command = AP_MavlinkCommand(getCurrentIndex()); - _command.load(); _previousCommand = AP_MavlinkCommand(getPreviousIndex()); - _previousCommand.load(); //_hal->gcs->sendMessage(MAVLINK_MSG_ID_WAYPOINT_CURRENT); } @@ -286,9 +284,9 @@ public: } _cmdIndex = getNextIndex(); - Serial.print("cmd : "); Serial.println(int(_cmdIndex)); - Serial.print("cmd prev : "); Serial.println(int(getPreviousIndex())); - Serial.print("cmd num : "); Serial.println(int(getNumberOfCommands())); + //Serial.print("cmd : "); Serial.println(int(_cmdIndex)); + //Serial.print("cmd prev : "); Serial.println(int(getPreviousIndex())); + //Serial.print("cmd num : "); Serial.println(int(getNumberOfCommands())); _command = AP_MavlinkCommand(getCurrentIndex()); _previousCommand = AP_MavlinkCommand(getPreviousIndex()); }