Copter: update home position when disarmed
This resolves the issue in which the vehicle's position jumped back to it's home location when disarmed and using the EKF. This also makes copter consistent with plane.
This commit is contained in:
parent
fd0b82f669
commit
58ac9de94b
@ -1211,6 +1211,11 @@ static void update_GPS(void)
|
||||
// start again if we lose 3d lock
|
||||
ground_start_count = 10;
|
||||
}
|
||||
} else {
|
||||
// update home position when not armed
|
||||
if (!motors.armed()) {
|
||||
update_home();
|
||||
}
|
||||
}
|
||||
|
||||
//If we are not currently armed, and we're ready to
|
||||
|
@ -26,5 +26,19 @@ static void init_home()
|
||||
scaleLongUp = 1.0f/scaleLongDown;
|
||||
}
|
||||
|
||||
// update_home - reset home to current location
|
||||
// should be called only when vehicle is disarmed
|
||||
static void update_home()
|
||||
{
|
||||
// copter uses 0 home altitude
|
||||
Location loc = gps.location();
|
||||
|
||||
// set ahrs object's home position
|
||||
ahrs.set_home(loc);
|
||||
|
||||
// update navigation scalers. used to offset the shrinking longitude as we go towards the poles
|
||||
scaleLongDown = longitude_scale(loc);
|
||||
scaleLongUp = 1.0f/scaleLongDown;
|
||||
}
|
||||
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user