diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index 1c5c114b2f..2139595041 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -162,7 +162,7 @@ def fly_square(mavproxy, mav, side=50, timeout=300): print("Failed to reach heading") success = False mavproxy.send('rc 4 1500\n') - mav.recv_match(condition='RC_CHANNELS_RAW.chan4_raw==1500', blocking=True) + mav.recv_match(condition='RC_CHANNELS.chan4_raw==1500', blocking=True) # save bottom left corner of box as waypoint print("Save WP 1 & 2") diff --git a/Tools/autotest/common.py b/Tools/autotest/common.py index 93c747d899..ec87bea978 100644 --- a/Tools/autotest/common.py +++ b/Tools/autotest/common.py @@ -236,13 +236,13 @@ def wait_waypoint(mav, wpnum_start, wpnum_end, allow_skip=True, max_dist=2, time def save_wp(mavproxy, mav): mavproxy.send('rc 7 1000\n') - mav.recv_match(condition='RC_CHANNELS_RAW.chan7_raw==1000', blocking=True) + mav.recv_match(condition='RC_CHANNELS.chan7_raw==1000', blocking=True) wait_seconds(mav, 1) mavproxy.send('rc 7 2000\n') - mav.recv_match(condition='RC_CHANNELS_RAW.chan7_raw==2000', blocking=True) + mav.recv_match(condition='RC_CHANNELS.chan7_raw==2000', blocking=True) wait_seconds(mav, 1) mavproxy.send('rc 7 1000\n') - mav.recv_match(condition='RC_CHANNELS_RAW.chan7_raw==1000', blocking=True) + mav.recv_match(condition='RC_CHANNELS.chan7_raw==1000', blocking=True) wait_seconds(mav, 1)