Skip to content

Commit

Permalink
Autotest: Modify look_for_wiggle to test for individual servo movements
Browse files Browse the repository at this point in the history
  • Loading branch information
ohitstarik authored and tridge committed Oct 2, 2024
1 parent 9d58bfb commit 5ea787a
Showing 1 changed file with 15 additions and 6 deletions.
21 changes: 15 additions & 6 deletions Tools/autotest/arduplane.py
Original file line number Diff line number Diff line change
Expand Up @@ -5847,18 +5847,23 @@ def MAV_CMD_NAV_ALTITUDE_WAIT(self):
)
])

# Set initial conditions for servo wiggle testing
servo_wiggled = {1: False, 2: False, 4: False}

def look_for_wiggle(mav, m):
if m.get_type() == 'SERVO_OUTPUT_RAW':
# Throttle must be zero
if m.servo3_raw != 1000:
raise NotAchievedException(
"Throttle must be 0 in altitude wait, got %f" % m.servo3_raw)
# Aileron, elevator and rudder must all be the same
# However, aileron is revered, so we must un-reverse it
value = 1500 - (m.servo1_raw - 1500)
if (m.servo2_raw != value) or (m.servo4_raw != value):
raise NotAchievedException(
"Aileron, elevator and rudder must be the same")

# Check if all servos wiggle
if m.servo1_raw != 1500:
servo_wiggled[1] = True
if m.servo2_raw != 1500:
servo_wiggled[2] = True
if m.servo4_raw != 1500:
servo_wiggled[4] = True

# Start mission
self.change_mode('AUTO')
Expand All @@ -5878,6 +5883,10 @@ def look_for_wiggle(mav, m):
if not self.mode_is('AUTO'):
raise NotAchievedException("Must still be in AUTO")

# Raise error if not all servos have wiggled
if not all(servo_wiggled.values()):
raise NotAchievedException("Not all servos have moved within the test frame")

self.disarm_vehicle()

def start_flying_simple_rehome_mission(self, items):
Expand Down

0 comments on commit 5ea787a

Please sign in to comment.