Arducopter SITL invariant of wall clock time?

Hello Copter Simulation forum,

I would like to develop an application controlling an Arducopter. In conjunction with the physical system, I’d like to use Arducopter SITL to help me make more total flights and crash the physical system less. In the course of development, I expect the application controller wall clock runtime to vary in computational expense from the very short to the very long.

In the detail below, I have tested some variations of stock autotest tests. The variations seem to show that adding time.sleep changes simulation results. I was hoping for my tests, simulation results would be invariant of time.sleep.

Two questions:

    1. Can Arducopter SITL be driven to produce the same behavior from run to run regardless of how much wall clock time passes?
    1. If yes, then what is the best example code or documentation illustrating the required APIs?

Thanks in advance,

Jeff Henrikson

Detail

Ardupilot version:

ardupilot source on github, master branch, commit 4b24a6 on Mon Jul 9 22:26:49 2018

Scenario

My hypothesis for how I will test my application controller with SITL is to write tests that connect to a SITL process like this one over TCP port 5760:

../build/sitl/bin/arducopter --home -35,149,584,270 --model quad

In order to understand time semantics of Arducopter SITL, I have started by experimenting with this file:

Tools/autotest/arducopter.py

I can run the file as follows, and get changes to tests to respond:

../Tools/autotest/autotest.py --frame=quad build.ArduCopter fly.ArduCopter

I have run the wait_altitude call here in three different variations:

    class AutoTestCopter(AutoTest):
    . . .
        def takeoff(self, alt_min=30, takeoff_throttle=1700, arm=False):
            """Takeoff get to 30m altitude."""
    . . .
            if alt < alt_min:
                self.wait_altitude(alt_min,
                                   (alt_min + 5),
                                   timeout=30,
                                   relative=True)

Variations

Variation 1

Make the 30 second timeout explicit instead of a default argument.
Expected result: Altitude OK.
Actual result: Altitude OK.

            if alt < alt_min:
                self.wait_altitude(alt_min,
                                   (alt_min + 5),
                                   timeout=30,
                                   relative=True)
        =>
            AUTOTEST: Got mode STABILIZE
            rc 3 1700
            rc 3 1700
            STABILIZE> AUTOTEST: Waiting for altitude between 10 and 15
            AUTOTEST: Wait Altitude: Cur:0, min_alt:10, climb_rate: 0
            AUTOTEST: Wait Altitude: Cur:0, min_alt:10, climb_rate: 0
            AUTOTEST: Wait Altitude: Cur:0, min_alt:10, climb_rate: 0
            AUTOTEST: Wait Altitude: Cur:0, min_alt:10, climb_rate: 0
            AUTOTEST: Wait Altitude: Cur:0, min_alt:10, climb_rate: 0
            AUTOTEST: Wait Altitude: Cur:0, min_alt:10, climb_rate: 0
            AUTOTEST: Wait Altitude: Cur:0, min_alt:10, climb_rate: 0
            AUTOTEST: Wait Altitude: Cur:0, min_alt:10, climb_rate: 0
            AUTOTEST: Wait Altitude: Cur:0, min_alt:10, climb_rate: 0
            AUTOTEST: Wait Altitude: Cur:1, min_alt:10, climb_rate: 0
            AUTOTEST: Wait Altitude: Cur:1, min_alt:10, climb_rate: 0
            AUTOTEST: Wait Altitude: Cur:2, min_alt:10, climb_rate: 0
            AUTOTEST: Wait Altitude: Cur:3, min_alt:10, climb_rate: 0
            APM: EKF2 IMU0 in-flight yaw alignment complete
            APM: EKF2 IMU1 in-flight yaw alignment complete
            AUTOTEST: Wait Altitude: Cur:4, min_alt:10, climb_rate: 0
            AUTOTEST: Wait Altitude: Cur:4, min_alt:10, climb_rate: 0
            AUTOTEST: Wait Altitude: Cur:5, min_alt:10, climb_rate: 0
            AUTOTEST: Wait Altitude: Cur:6, min_alt:10, climb_rate: 0
            AUTOTEST: Wait Altitude: Cur:7, min_alt:10, climb_rate: 0
            AUTOTEST: Wait Altitude: Cur:8, min_alt:10, climb_rate: 0
            AUTOTEST: Wait Altitude: Cur:9, min_alt:10, climb_rate: 0
            height 10
            AUTOTEST: Wait Altitude: Cur:10, min_alt:10, climb_rate: 1
            AUTOTEST: Altitude OK
            rc 3 1500
            rc 3 1500
            STABILIZE> AUTOTEST: TAKEOFF COMPLETE

Variation 2

Change the timeout to be 1 second.
Expected result: Failed to attain altitude range.
Actual result: Failed to attain altitude range.

                if alt < alt_min:
                    self.wait_altitude(alt_min,
                                       (alt_min + 5),
                                       timeout=1,
                                       relative=True)
        =>
            STABILIZE> AUTOTEST: Waiting for altitude between 10 and 15
            AUTOTEST: Wait Altitude: Cur:0, min_alt:10, climb_rate: 0
            AUTOTEST: Wait Altitude: Cur:0, min_alt:10, climb_rate: 0
            AUTOTEST: Wait Altitude: Cur:0, min_alt:10, climb_rate: 0
            AUTOTEST: Wait Altitude: Cur:0, min_alt:10, climb_rate: 0
            AUTOTEST: Failed to attain altitude range
            AUTOTEST: FAILED: "Takeoff to test fly Square": WaitAltitudeTimout()

Variation 3

Change the timeout to be 1 second, and precede with a 30 second time.sleep.
Expected result: Failed to attain altitude range, same as Variation 2.
Actual result: Failed to attain altitude range, but simulated height is up to 1020.

        #does wall clock sleep allow it to pass?
                    if alt < alt_min:
                        time.sleep(30)
                        self.wait_altitude(alt_min,
                                           (alt_min + 5),
                                           timeout=1,
                                           relative=True)
            =>
                AUTOTEST: Wait Altitude: Cur:1027, min_alt:-5, climb_rate: 0
                AUTOTEST: Wait Altitude: Cur:1027, min_alt:-5, climb_rate: 0
                AUTOTEST: Wait Altitude: Cur:1026, min_alt:-5, climb_rate: 0
                AUTOTEST: Failed to attain altitude range
                AUTOTEST: FAILED: "Fly copter mission": WaitAltitudeTimout()
                height 1020
                height 1010
                height 1000
                height 990
                height 980
                height 970
                height 960
                Flight battery 30 percent
                height 950
                height 940