mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
Plane: Reset home to AHRS position rather then snapshotting GPS
This commit is contained in:
parent
adf215998f
commit
fbf6050876
@ -136,10 +136,12 @@ void Plane::update_home()
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
if (home_is_set == HOME_SET_NOT_LOCKED) {
|
if (home_is_set == HOME_SET_NOT_LOCKED) {
|
||||||
Location loc = gps.location();
|
Location loc;
|
||||||
ahrs.set_home(loc);
|
if(ahrs.get_position(loc)) {
|
||||||
Log_Write_Home_And_Origin();
|
ahrs.set_home(loc);
|
||||||
GCS_MAVLINK::send_home_all(loc);
|
Log_Write_Home_And_Origin();
|
||||||
|
GCS_MAVLINK::send_home_all(loc);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
barometer.update_calibration();
|
barometer.update_calibration();
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user