From d0194b7a9d951d4c475cb01cad46cbe31ba3c0c5 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 11 Jun 2014 11:03:19 +0900 Subject: [PATCH] Copter: remove home variable home has moved to ahrs saves 15 bytes of RAM --- ArduCopter/ArduCopter.pde | 2 -- ArduCopter/GCS_Mavlink.pde | 4 ++-- ArduCopter/position_vector.pde | 3 ++- 3 files changed, 4 insertions(+), 5 deletions(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index ae1e412af8..89e3021f0e 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -583,8 +583,6 @@ static int32_t baro_alt; //////////////////////////////////////////////////////////////////////////////// // 3D Location vectors //////////////////////////////////////////////////////////////////////////////// -static const struct Location &home = ahrs.get_home(); - // Current location of the copter static struct Location current_loc; diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde index d1a4750a10..55e75b6963 100644 --- a/ArduCopter/GCS_Mavlink.pde +++ b/ArduCopter/GCS_Mavlink.pde @@ -245,7 +245,7 @@ static void NOINLINE send_location(mavlink_channel_t chan) current_loc.lat, // in 1E7 degrees current_loc.lng, // in 1E7 degrees gps.location().alt * 10UL, // millimeters above sea level - (current_loc.alt - home.alt) * 10, // millimeters above ground + current_loc.alt * 10, // millimeters above ground vel.x * 100, // X speed cm/s (+ve North) vel.y * 100, // Y speed cm/s (+ve East) vel.x * -100, // Z speed cm/s (+ve up) @@ -907,7 +907,7 @@ void GCS_MAVLINK::handle_change_alt_request(AP_Mission::Mission_Command &cmd) { // add home alt if needed if (cmd.content.location.options & LOCATION_MASK_OPTIONS_RELATIVE_ALT) { - cmd.content.location.alt += home.alt; + cmd.content.location.alt += ahrs.get_home().alt; } // To-Do: update target altitude for loiter or waypoint controller depending upon nav mode diff --git a/ArduCopter/position_vector.pde b/ArduCopter/position_vector.pde index e35773424b..a8ac35e758 100644 --- a/ArduCopter/position_vector.pde +++ b/ArduCopter/position_vector.pde @@ -10,7 +10,8 @@ // pv_latlon_to_vector - convert lat/lon coordinates to a position vector Vector3f pv_location_to_vector(const Location& loc) { - Vector3f tmp((loc.lat-home.lat) * LATLON_TO_CM, (loc.lng-home.lng) * LATLON_TO_CM * scaleLongDown, loc.alt); + const struct Location &temp_home = ahrs.get_home(); + Vector3f tmp((loc.lat-temp_home.lat) * LATLON_TO_CM, (loc.lng-temp_home.lng) * LATLON_TO_CM * scaleLongDown, loc.alt); return tmp; }