From 2a298d0ea453fb74218e6988fd1d7e2389d644c0 Mon Sep 17 00:00:00 2001
From: Randy Mackay <rmackay9@yahoo.com>
Date: Sat, 19 Apr 2014 14:44:47 +0900
Subject: [PATCH] Plane: remove RALLY_WP_SIZE definition

---
 ArduPlane/defines.h | 3 +--
 1 file changed, 1 insertion(+), 2 deletions(-)

diff --git a/ArduPlane/defines.h b/ArduPlane/defines.h
index ca9ebd2144..0fd4fc791e 100644
--- a/ArduPlane/defines.h
+++ b/ArduPlane/defines.h
@@ -183,8 +183,7 @@ enum log_messages {
 
 // rally points shoehorned between fence points and waypoints
 #define MAX_RALLYPOINTS 10
-#define RALLY_WP_SIZE 15
-#define RALLY_START_BYTE (FENCE_START_BYTE-(MAX_RALLYPOINTS*RALLY_WP_SIZE))
+#define RALLY_START_BYTE (FENCE_START_BYTE-(MAX_RALLYPOINTS*AC_RALLY_WP_SIZE))
 
 // parameters get the first 1280 bytes of EEPROM, mission commands are stored between these params and the rally points
 #define MISSION_START_BYTE  0x500