mirror of https://github.com/ArduPilot/ardupilot
Copter: update current loc once home is set
This commit is contained in:
parent
f1a6b06586
commit
cc52bbbffb
|
@ -17,7 +17,7 @@ static void run_nav_updates(void)
|
||||||
|
|
||||||
// calc_position - get lat and lon positions from inertial nav library
|
// calc_position - get lat and lon positions from inertial nav library
|
||||||
static void calc_position(){
|
static void calc_position(){
|
||||||
if (inertial_nav.get_filter_status().flags.horiz_pos_abs) {
|
if (ap.home_is_set) {
|
||||||
// pull position from interial nav library
|
// pull position from interial nav library
|
||||||
current_loc.lng = inertial_nav.get_longitude();
|
current_loc.lng = inertial_nav.get_longitude();
|
||||||
current_loc.lat = inertial_nav.get_latitude();
|
current_loc.lat = inertial_nav.get_latitude();
|
||||||
|
|
Loading…
Reference in New Issue