mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-08 17:03:57 -04:00
Rover: Reset home to AHRS location rather then snapshotting GPS
Also corrects rover locking home altitude to EKF origin altitude
This commit is contained in:
parent
fbf6050876
commit
51c97af5b5
@ -95,17 +95,12 @@ void Rover::restart_nav()
|
|||||||
void Rover::update_home()
|
void Rover::update_home()
|
||||||
{
|
{
|
||||||
if (home_is_set == HOME_SET_NOT_LOCKED) {
|
if (home_is_set == HOME_SET_NOT_LOCKED) {
|
||||||
Location loc = gps.location();
|
Location loc;
|
||||||
Location origin;
|
if (ahrs.get_position(loc)) {
|
||||||
// if an EKF origin is available then we leave home equal to
|
ahrs.set_home(loc);
|
||||||
// the height of that origin. This ensures that our relative
|
Log_Write_Home_And_Origin();
|
||||||
// height calculations are using the same origin
|
GCS_MAVLINK::send_home_all(gps.location());
|
||||||
if (ahrs.get_origin(origin)) {
|
|
||||||
loc.alt = origin.alt;
|
|
||||||
}
|
}
|
||||||
ahrs.set_home(loc);
|
|
||||||
Log_Write_Home_And_Origin();
|
|
||||||
GCS_MAVLINK::send_home_all(gps.location());
|
|
||||||
}
|
}
|
||||||
barometer.update_calibration();
|
barometer.update_calibration();
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user