Skip to content

Commit cfd0b3f

Browse files
committed
autotest: fix Clamp test altitude bounds for datum reset
The Clamp test checks that a clamped vehicle stays near ground level. With the height datum reset on arming, altitude is zeroed and baro noise can put it slightly negative (-0.01m). Change the lower bound from 0 to -1 to accommodate this.
1 parent 4e4caa0 commit cfd0b3f

File tree

1 file changed

+2
-2
lines changed

1 file changed

+2
-2
lines changed

Tools/autotest/arducopter.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -14408,7 +14408,7 @@ def Clamp(self):
1440814408
self.wait_statustext("SITL: Clamp: grabbed vehicle", check_context=True)
1440914409
self.arm_vehicle()
1441014410
self.set_rc(3, 2000)
14411-
self.wait_altitude(0, 5, minimum_duration=5, relative=True)
14411+
self.wait_altitude(-1, 5, minimum_duration=5, relative=True)
1441214412
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_SERVO, p1=11, p2=1000)
1441314413
self.wait_statustext("SITL: Clamp: released vehicle", check_context=True)
1441414414
self.wait_altitude(5, 5000, minimum_duration=1, relative=True)
@@ -14424,7 +14424,7 @@ def Clamp(self):
1442414424
self.wait_statustext("SITL: Clamp: grabbed vehicle", check_context=True)
1442514425
self.arm_vehicle()
1442614426
self.set_rc(3, 2000)
14427-
self.wait_altitude(0, 1, minimum_duration=5, relative=True)
14427+
self.wait_altitude(-1, 1, minimum_duration=5, relative=True)
1442814428
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_SERVO, p1=11, p2=1000)
1442914429
self.wait_statustext("SITL: Clamp: released vehicle", check_context=True)
1443014430
self.wait_altitude(5, 5000, minimum_duration=1, relative=True)

0 commit comments

Comments
 (0)