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

autotest: Add catapult test #27125

Closed
wants to merge 1 commit into from

Conversation

Georacer
Copy link
Contributor

An autotest for a catapult launch has been added for Plane.
An auxiliary set_servo method has been added to vehicle_test_suite.py.

@Georacer
Copy link
Contributor Author

The way to call the test is

./Tools/autotest/autotest.py --no-clean --frame plane-catapult --speedup 10 build.Plane test.Plane.CatapultTakeoff

This PR is WIP because it's premature and failing.

There are two issues with it:

  1. This test is specific to the plane-catapult frame. I'd like some advice on how to prevent it from running automatically for all frames.

  2. For some reason the catapult refuses to launch the vehicle. I seem to successfully send the RC trigger to the catapult, but it does not produce forward acceleration.
    At some point the throttle picks up a bit (I don't know why) and the plane starts crawling on the ground).

image

Even more weirdly, autotest things the airspeed has risen, when the logs shows it hasn't.

AT-0004.1: airspeed=0.40 (want between 21.0 and 100)
AT-0004.1: AP: Triggered AUTO. GPS speed = 0.8
AT-0004.2: airspeed=13.59 (want between 21.0 and 100)
AT-0004.2: AP: SIM Hit ground at 3.284683 m/s
AT-0004.3: airspeed=27.58 (got between 21.0 and 100) (maintain=0.6/5.0)
AT-0004.3: AP: SIM Hit ground at 4.907945 m/s
AT-0004.3: AP: Holding course 35398 at 28.8m/s (-0.0)
AT-0004.4: airspeed=26.24 (got between 21.0 and 100) (maintain=1.7/5.0)
AT-0004.4: AP: SIM Hit ground at 4.911546 m/s
AT-0004.5: airspeed=25.58 (got between 21.0 and 100) (maintain=2.8/5.0)
AT-0004.6: AP: SIM Hit ground at 3.960280 m/s
AT-0004.6: airspeed=25.28 (got between 21.0 and 100) (maintain=3.8/5.0)
AT-0004.7: AP: SIM Hit ground at 3.963535 m/s
AT-0004.8: airspeed=25.92 (got between 21.0 and 100) (maintain=4.9/5.0)
AT-0004.8: AP: SIM Hit ground at 3.964641 m/s
AT-0004.8: Attained airspeed=25.871821010813992

There's a slight chance I'm looking at the wrong .bin. I inspected buildlogs/*2.bin and *3.bin.

Tools/autotest/vehicle_test_suite.py Outdated Show resolved Hide resolved
Tools/autotest/arduplane.py Outdated Show resolved Hide resolved
Tools/autotest/arduplane.py Show resolved Hide resolved
Tools/autotest/arduplane.py Outdated Show resolved Hide resolved
Tools/autotest/arduplane.py Outdated Show resolved Hide resolved
@tridge tridge removed the DevCallEU label May 22, 2024
@Georacer Georacer force-pushed the catapult-autotest branch from 6485a2d to 1890365 Compare May 22, 2024 15:01
@Georacer
Copy link
Contributor Author

@peterbarker thanks for the suggestions. I've implemented it and it's running now.

Question:
I modified the basic.txt mission, that is used in FlyEachFrame. It contains a DO_LAND_START and more waypoints than I need for this test.
Should I use it regardless, or next time I should code a mission small enough for my needs?

Remark:
I've places this test in the known-failing list, as I believe this behaviour is now bugged.
The throttle never recedes during climb and the aircraft overspeeds:
image

If you agree, we can consider this PR done and I can open an Issue ticket.

self.wait_ready_to_arm()
self.arm_vehicle()

# Throw the catapult.
Copy link
Contributor

Choose a reason for hiding this comment

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

Suggested change
# Throw the catapult.
self.progress("Throw the catapult")

Many times when I've put a comment like this in I've found it useful to put it in as a progress text instead. Just a suggestion.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Thanks! For now it's pretty evident (perhaps even more useful) by plotting RCOU[7]. But I'll keep that in mind.

@peterbarker
Copy link
Contributor

Question: I modified the basic.txt mission, that is used in FlyEachFrame. It contains a DO_LAND_START and more waypoints than I need for this test. Should I use it regardless, or next time I should code a mission small enough for my needs?

Whatever is most convenient, really. Crafting your own mission gives you exactly what you want with no complication, but takes longer. Note you can also load a "generic mission", a relatively new concept in the suite I'm still playing around with. e.g.

        self.load_generic_mission("CMAC-circuit.txt", strict=False)

There's something else you might be able to get away with, depending. Which is to just use "takeoff mode" to the appropriate altitude (it uses TECS). This may or may not reproduce, we do a few little interesting things in takeoff mode which might cause the problem to not reproduce.

You could possibly do something like this:

        self.takeoff(10)
        loc = self.mav.location()
        self.location_offset_ne(loc, 500, 500)
        loc.alt = 5000
        self.do_reposition(loc)

If you agree, we can consider this PR done and I can open an Issue ticket.

Yes - and you should use that ticket number in the disabled_tests method so people can look at the issue/analysis.

@Georacer Georacer changed the title WIP: autotest: Add catapult test autotest: Add catapult test May 23, 2024
@Georacer Georacer force-pushed the catapult-autotest branch from 1890365 to 471e0e2 Compare May 23, 2024 21:24
@Georacer
Copy link
Contributor Author

I have updated the PR to switch from a check for receding throttle to a check for correct airspeed regulation.
This is because currently TECS assumes that the TAKEOFF happens at full throttle.

@Georacer Georacer force-pushed the catapult-autotest branch from c707e42 to 3237e16 Compare May 25, 2024 17:51
An autotest for a catapult launch has been added for Plane.
Larger maximum pitch limit has been allowed, to demonstrate pitch
behaviour.
An auxiliary `set_servo` method has been added to `vehicle_test_suite.py`.
For now, it is placed as known failing test.
@tridge tridge dismissed peterbarker’s stale review May 29, 2024 07:08

peter is a happy camper

@tridge
Copy link
Contributor

tridge commented May 29, 2024

closing in favor of the test code in #27174

@tridge tridge closed this May 29, 2024
@IamPete1 IamPete1 removed the DevCallEU label Jun 4, 2024
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

5 participants