From 85ac3e3515bc214a770074182617208b24ee0209 Mon Sep 17 00:00:00 2001 From: Andreas Antener Date: Mon, 23 Feb 2015 18:33:10 +0100 Subject: renamed tests, added placeholder for mavros test --- integrationtests/demo_tests/direct_arm_test.py | 37 ++++++++++++++++++++++++++ 1 file changed, 37 insertions(+) create mode 100755 integrationtests/demo_tests/direct_arm_test.py (limited to 'integrationtests/demo_tests/direct_arm_test.py') diff --git a/integrationtests/demo_tests/direct_arm_test.py b/integrationtests/demo_tests/direct_arm_test.py new file mode 100755 index 000000000..569e0af7c --- /dev/null +++ b/integrationtests/demo_tests/direct_arm_test.py @@ -0,0 +1,37 @@ +#!/usr/bin/env python +PKG = 'px4' + +import sys +import unittest +import rospy + +from px4.msg import actuator_armed +from manual_input import ManualInput + +class ArmTest(unittest.TestCase): + + # + # General callback functions used in tests + # + def actuator_armed_callback(self, data): + self.actuatorStatus = data + + # + # Test arming + # + def test_arm(self): + rospy.init_node('test_node', anonymous=True) + sub = rospy.Subscriber('px4_multicopter/actuator_armed', actuator_armed, self.actuator_armed_callback) + + # method to test + arm = ManualInput() + arm.arm() + + self.assertEquals(self.actuatorStatus.armed, True, "not armed") + + + + +if __name__ == '__main__': + import rostest + rostest.rosrun(PKG, 'arm_test', ArmTest) -- cgit v1.2.3