mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
Copter: use a common home with AHRS
This commit is contained in:
parent
57e0eb4db5
commit
c6e25483b4
@ -604,9 +604,8 @@ static int32_t baro_alt;
|
|||||||
////////////////////////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////////////////////////
|
||||||
// 3D Location vectors
|
// 3D Location vectors
|
||||||
////////////////////////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////////////////////////
|
||||||
// home location is stored when we have a good GPS lock and arm the copter
|
static const struct Location &home = ahrs.get_home();
|
||||||
// Can be reset each the copter is re-armed
|
|
||||||
static struct Location home;
|
|
||||||
// Current location of the copter
|
// Current location of the copter
|
||||||
static struct Location current_loc;
|
static struct Location current_loc;
|
||||||
// Holds the current loaded command from the EEPROM for navigation
|
// Holds the current loaded command from the EEPROM for navigation
|
||||||
|
@ -117,10 +117,7 @@ static int32_t get_RTL_alt()
|
|||||||
static void init_home()
|
static void init_home()
|
||||||
{
|
{
|
||||||
set_home_is_set(true);
|
set_home_is_set(true);
|
||||||
home.id = MAV_CMD_NAV_WAYPOINT;
|
ahrs.set_home(g_gps->latitude, g_gps->longitude, 0);
|
||||||
home.lng = g_gps->longitude; // Lon * 10**7
|
|
||||||
home.lat = g_gps->latitude; // Lat * 10**7
|
|
||||||
home.alt = 0; // Home is always 0
|
|
||||||
|
|
||||||
// Save Home to EEPROM
|
// Save Home to EEPROM
|
||||||
// -------------------
|
// -------------------
|
||||||
|
@ -645,10 +645,7 @@ static void do_set_home()
|
|||||||
if(command_cond_queue.p1 == 1) {
|
if(command_cond_queue.p1 == 1) {
|
||||||
init_home();
|
init_home();
|
||||||
} else {
|
} else {
|
||||||
home.id = MAV_CMD_NAV_WAYPOINT;
|
ahrs.set_home(command_cond_queue.lat, command_cond_queue.lng, 0);
|
||||||
home.lng = command_cond_queue.lng; // Lon * 10**7
|
|
||||||
home.lat = command_cond_queue.lat; // Lat * 10**7
|
|
||||||
home.alt = 0;
|
|
||||||
//home_is_set = true;
|
//home_is_set = true;
|
||||||
set_home_is_set(true);
|
set_home_is_set(true);
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user