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

Plane: fixed takeoff direction with no yaw source #28730

Open
wants to merge 2 commits into
base: master
Choose a base branch
from

Conversation

tridge
Copy link
Contributor

@tridge tridge commented Nov 25, 2024

in TAKEOFF mode with either very poor yaw source or no yaw source we need to use ground vector and wait for sufficient ground speed
fixes #28681

in TAKEOFF mode with either very poor yaw source or no yaw source we
need to use ground vector and wait for sufficient ground speed
eventually trigger
*/
if (!plane.throttle_suppressed &&
groundspeed > plane.aparm.airspeed_min*0.3) {
Copy link
Contributor

Choose a reason for hiding this comment

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

So basically you will not allow the heading to "lock-in" until some groundspeed is gained, deeming the heading valid.
Sounds reasonable.

if abs(bearing_from_home - start_loc.heading) > bearing_margin:
raise NotAchievedException(f"Did not takeoff in the right direction {bearing_from_home}")

self.fly_home_land_and_disarm()
Copy link
Contributor

Choose a reason for hiding this comment

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

Since the test is only about the takeoff, does it make sense to not wait for the landing, but end the test early here? This would alleviate the test server a bit.

Copy link
Collaborator

@Hwurzburg Hwurzburg left a comment

Choose a reason for hiding this comment

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

shouldn't the course lock based on GPS course be based on when the GPS speed is valid? and this is not really airspeeed dependent at all?

  • in Auto takeoffs, its set 2s after exceeding 5m/s ground speed from GPS (which I think could be set immediately after exceeding this since modern GPS's have been accurate for years, unlike when this bit was written)
  • in my pending Autoland Lua script PR , I use 5m/s with a modern cheap GPS (M8) and it works great capturing takeoff direction, even in very strong crosswinds in compassless hand launches
  • your criteria is 2.7m/s in the default case anyway
    I think that it should just be set to a magic number of X (3-5m/s?) since the quality of the GPS heading is not really related to anything to do with airspeed

@menschel
Copy link
Contributor

Off-Topic Question - Does takeoff compensate for cross-wind ?

Because until now I was convinced that the heading error is also present in auto takeoff mission item.
After reviewing the code,
https://github.com/ArduPilot/ardupilot/blob/master/ArduPlane/ArduPlane.cpp#L190C5-L190C34
https://github.com/ArduPilot/ardupilot/blob/master/ArduPlane/commands_logic.cpp#L566
it appears to be legit and all that is left for the massive course deviation is the crosswind of ~15km/h here. Approx 100m over 300m take-off.
24-11-23_08-42-26.bin

@Hwurzburg
Copy link
Collaborator

Hwurzburg commented Nov 25, 2024

No navigation other than heading lock

const Vector2f &groundspeed2d = ahrs.groundspeed_vector();
const float direction = wrap_360(degrees(groundspeed2d.angle()));
const float groundspeed = groundspeed2d.length();

// see if we will skip takeoff as already flying
if (plane.is_flying() && (millis() - plane.started_flying_ms > 10000U) && ahrs.groundspeed() > 3) {
Copy link
Member

Choose a reason for hiding this comment

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

Suggested change
if (plane.is_flying() && (millis() - plane.started_flying_ms > 10000U) && ahrs.groundspeed() > 3) {
if (plane.is_flying() && (millis() - plane.started_flying_ms > 10000U) && groundspeed > 3) {

Copy link
Member

@IamPete1 IamPete1 Dec 2, 2024

Choose a reason for hiding this comment

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

Is there a chance that the ground speed check here will trigger before the new one on line 129. If your min airspeed is larger than 10m/s (3/0.3) and it takes longer than 10 seconds to get there then its will skip the full takeoff every time. Really this skip takeoff path should only be done once. Maybe it should be moved to the mode enter?

Copy link
Member

@IamPete1 IamPete1 left a comment

Choose a reason for hiding this comment

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

Looks good for a 4.6 fix.

Future work to move the is-flying check into the mode enter and unify the methods between Auto takeoff and mode takeoff.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
Status: No status
Development

Successfully merging this pull request may close these issues.

regression in plane takeoff behaviour in 4.6
6 participants