Copter: use a common home with AHRS

This commit is contained in:
Andrew Tridgell 2014-01-03 22:33:57 +11:00
parent 57e0eb4db5
commit c6e25483b4
3 changed files with 4 additions and 11 deletions

View File

@ -604,9 +604,8 @@ static int32_t baro_alt;
////////////////////////////////////////////////////////////////////////////////
// 3D Location vectors
////////////////////////////////////////////////////////////////////////////////
// home location is stored when we have a good GPS lock and arm the copter
// Can be reset each the copter is re-armed
static struct Location home;
static const struct Location &home = ahrs.get_home();
// Current location of the copter
static struct Location current_loc;
// Holds the current loaded command from the EEPROM for navigation

View File

@ -117,10 +117,7 @@ static int32_t get_RTL_alt()
static void init_home()
{
set_home_is_set(true);
home.id = MAV_CMD_NAV_WAYPOINT;
home.lng = g_gps->longitude; // Lon * 10**7
home.lat = g_gps->latitude; // Lat * 10**7
home.alt = 0; // Home is always 0
ahrs.set_home(g_gps->latitude, g_gps->longitude, 0);
// Save Home to EEPROM
// -------------------

View File

@ -645,10 +645,7 @@ static void do_set_home()
if(command_cond_queue.p1 == 1) {
init_home();
} else {
home.id = MAV_CMD_NAV_WAYPOINT;
home.lng = command_cond_queue.lng; // Lon * 10**7
home.lat = command_cond_queue.lat; // Lat * 10**7
home.alt = 0;
ahrs.set_home(command_cond_queue.lat, command_cond_queue.lng, 0);
//home_is_set = true;
set_home_is_set(true);
}