aboutsummaryrefslogtreecommitdiff
path: root/integrationtests
diff options
context:
space:
mode:
authorAndreas Antener <antener_a@gmx.ch>2015-02-27 17:32:01 +0100
committerAndreas Antener <antener_a@gmx.ch>2015-02-28 20:03:49 +0100
commit5d8516b356a58c865de2336c211e1974f2f453e2 (patch)
treed3dd050218a743569d820b0b4401e4c2281edb81 /integrationtests
parent5706e1d7789afdab9316cc056b74d23a30676909 (diff)
downloadpx4-firmware-5d8516b356a58c865de2336c211e1974f2f453e2.tar.gz
px4-firmware-5d8516b356a58c865de2336c211e1974f2f453e2.tar.bz2
px4-firmware-5d8516b356a58c865de2336c211e1974f2f453e2.zip
wait on armin service and wait 2 seconds after calling it
Diffstat (limited to 'integrationtests')
-rwxr-xr-xintegrationtests/demo_tests/mavros_offboard_posctl_test.py6
1 files changed, 6 insertions, 0 deletions
diff --git a/integrationtests/demo_tests/mavros_offboard_posctl_test.py b/integrationtests/demo_tests/mavros_offboard_posctl_test.py
index 59f8276b1..533d9ad3c 100755
--- a/integrationtests/demo_tests/mavros_offboard_posctl_test.py
+++ b/integrationtests/demo_tests/mavros_offboard_posctl_test.py
@@ -55,12 +55,15 @@ class OffboardPosctlTest(unittest.TestCase):
def setUp(self):
rospy.init_node('test_node', anonymous=True)
+ rospy.wait_for_service('px4_multicopter/mavros/cmd/arming', 30)
rospy.Subscriber('px4_multicopter/vehicle_control_mode', vehicle_control_mode, self.vehicle_control_mode_callback)
rospy.Subscriber("px4_multicopter/mavros/position/local", PoseStamped, self.position_callback)
self.pubSpt = rospy.Publisher('px4_multicopter/mavros/setpoint/local_position', PoseStamped, queue_size=10)
self.cmdArm = rospy.ServiceProxy("px4_multicopter/mavros/cmd/arming", CommandBool)
self.rate = rospy.Rate(10) # 10hz
+ self.rateSec = rospy.Rate(1)
self.hasPos = False
+ self.controlMode = vehicle_control_mode()
#
# General callback functions used in tests
@@ -121,6 +124,9 @@ class OffboardPosctlTest(unittest.TestCase):
#
def test_posctl(self):
self.assertTrue(self.arm(), "Could not arm")
+ self.rateSec.sleep()
+ self.rateSec.sleep()
+ self.assertTrue(self.controlMode.flag_armed, "flag_armed is not set after 2 seconds")
# prepare flight path assertion
positions = (