Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_NavEKF3: define Yaw alignment min GPS speed per vehicle #24206

Merged
merged 1 commit into from
Mar 25, 2024

Conversation

rmackay9
Copy link
Contributor

@rmackay9 rmackay9 commented Jul 3, 2023

This improves GSF performance for Copter and Rover 4.4 by reducing the minimum speed the vehicle must be travelling at for a GSF reset to occur.

The minimum speed requirement issue (see #24183) was introduced with PR #23515 but the minimum (5m/s) was likely designed with Planes in mind.This PR reduces the limit to 1m/s for all other vehicles (Copter, Helis, Boats, Rover, etc). While slightly arbitrary I have tested these and I could not make GSF produce an incorrect yaw even if I set the speed limit to zero.

Related discussion is here

Alternatively we could add a parameter although i wonder if anyone would ever set it.

This has been tested in SITL and on real vehicles for Copter, Rover and Boat and GSF always calculated the correct Yaw even when the limit was reduced to zero The user who reported the problem (and discovered the fix) has successfully tested 0.5m/s for Rover.

Below is a screen shot of a couple of tests on Copter and Rover. Some debug was added to show the exact GPS speed at the moment GSF was calculated. In these particular tests I was specifically trying to trigger GSF at low speeds to see if it would calculate the wrong heading (it didn't).
image

image

@IamPete1
Copy link
Member

IamPete1 commented Jul 3, 2023

I wonder if we could automatically reduce the threshold based on the reported GPS accuracy, might be more trouble than its worth tho.

#define GPS_VEL_YAW_ALIGN_MIN_SPD 5.0F
#else
// copter, heli or undefined
#define GPS_VEL_YAW_ALIGN_MIN_SPD 2.0F
Copy link
Contributor

@tridge tridge Jul 4, 2023

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I'd like input from @priseborough on whether lowering this is safe for copters. GSF can be very unreliable for low speed/low accel vehicles

@rmackay9
Copy link
Contributor Author

I've rebased this on master and this is being tested here.

@priseborough
Copy link
Contributor

There is no theoretical reason why that threshold cant be lowered for copter and rover platforms. The GSF alignment is more a function of acceleration profile than it is velocity. The velocity threshold does indirectly enforce a prior speed change and therefore horizontal acceleration event which is why it was added. During the initial development of this algorithm I flew a copter with no minimum speed requirement and alignment was OK provided the GSF GPS data fusion didn't start running until alignment, but that was with a well isolated IMU and good GPs data.

Has anyone else with a average HW quality copter tested this lower threshold?

@tridge tridge merged commit 65b4db5 into ArduPilot:master Mar 25, 2024
91 checks passed
@rmackay9 rmackay9 deleted the ekf3-gsf-fix branch March 25, 2024 23:12
@rmackay9
Copy link
Contributor Author

This is included in 4.5.2-beta1

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
Projects
Status: 4.5.2-beta1
Development

Successfully merging this pull request may close these issues.

5 participants