From 4430f7534464b0c7721b71313eab593345713e77 Mon Sep 17 00:00:00 2001 From: Adam M Rivera Date: Thu, 19 Apr 2012 10:21:04 -0500 Subject: [PATCH] navigation.pde: Put the new calc_GPS_velocity method in a compiler if that checks the new RETRO_LOITER_MODE config value (saves space and ensures its not being used unless retro loiter mode is enabled) --- ArduCopter/navigation.pde | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ArduCopter/navigation.pde b/ArduCopter/navigation.pde index 2ccb3b0762..47648eb429 100644 --- a/ArduCopter/navigation.pde +++ b/ArduCopter/navigation.pde @@ -90,12 +90,14 @@ static void calc_XY_velocity(){ last_latitude = g_gps->latitude; } +#if RETRO_LOITER_MODE == ENABLED static void calc_GPS_velocity() { float temp = radians((float)g_gps->ground_course/100.0); x_actual_speed = (float)g_gps->ground_speed * sin(temp); y_actual_speed = (float)g_gps->ground_speed * cos(temp); } +#endif static void calc_location_error(struct Location *next_loc) {