From 7af5d4a8ce7ffd1ec5d2efc612131d9c0b463f00 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Sat, 19 Apr 2014 14:44:38 +0900 Subject: [PATCH] Copter: remove RALLY_WP_SIZE definition --- ArduCopter/defines.h | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/ArduCopter/defines.h b/ArduCopter/defines.h index d25897e1bd..6df1d10313 100644 --- a/ArduCopter/defines.h +++ b/ArduCopter/defines.h @@ -297,8 +297,7 @@ enum FlipState { // rally points shoehorned between fence points and waypoints #define MAX_RALLYPOINTS 6 -#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)) #define RALLY_LIMIT_KM_DEFAULT 2.0 // we'll set a per-vehicle default for this // parameters get the first 1536 bytes of EEPROM