Rover: set home using EKF position

previously the home position could be set from DCM
This makes the setting of home slower but more accurate
This commit is contained in:
Randy Mackay 2017-09-18 17:22:51 +09:00
parent 894bf2a23f
commit de406da254

View File

@ -17,7 +17,7 @@ bool Rover::set_home_to_current_location(bool lock)
{ {
// use position from EKF if available otherwise use GPS // use position from EKF if available otherwise use GPS
Location temp_loc; Location temp_loc;
if (ahrs.get_position(temp_loc)) { if (ahrs.have_inertial_nav() && ahrs.get_position(temp_loc)) {
return set_home(temp_loc, lock); return set_home(temp_loc, lock);
} }
return false; return false;