From 581e52f0d421164164aa53391aa1888ee6a8c6be Mon Sep 17 00:00:00 2001
From: Andrew Tridgell <tridge@samba.org>
Date: Fri, 27 Apr 2012 14:41:31 +1000
Subject: [PATCH] autotest: fixed levelling for ACM with MAVLink 1.0

---
 Tools/autotest/arducopter.py | 5 ++---
 1 file changed, 2 insertions(+), 3 deletions(-)

diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py
index b6ba3db47..805a35608 100644
--- a/Tools/autotest/arducopter.py
+++ b/Tools/autotest/arducopter.py
@@ -21,9 +21,8 @@ def hover(mavproxy, mav):
 def calibrate_level(mavproxy, mav):
     '''init the accelerometers'''
     print("Initialising accelerometers")
-    MAV_ACTION_CALIBRATE_ACC = 19
-    mav.mav.action_send(mav.target_system, mav.target_component, MAV_ACTION_CALIBRATE_ACC)
-    mavproxy.expect('APM: action received')
+    mav.calibrate_level()
+    mavproxy.expect(['APM: action received', 'COMMAND_ACK'])
     return True
 
 def arm_motors(mavproxy, mav):
-- 
GitLab