Copter: remove home variable

home has moved to ahrs
saves 15 bytes of RAM
This commit is contained in:
Randy Mackay 2014-06-11 11:03:19 +09:00
parent 5c305989b9
commit d0194b7a9d
3 changed files with 4 additions and 5 deletions

View File

@ -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;

View File

@ -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

View File

@ -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;
}