diff options
author | Andreas Antener <antener_a@gmx.ch> | 2015-02-27 16:55:19 +0100 |
---|---|---|
committer | Andreas Antener <antener_a@gmx.ch> | 2015-02-28 20:03:49 +0100 |
commit | 5706e1d7789afdab9316cc056b74d23a30676909 (patch) | |
tree | d381a49bc10d5ad3a6d0cfed20180560bba654c7 /integrationtests | |
parent | 7fb82e74c89eeb7f542080305a95b94098a548ab (diff) | |
download | px4-firmware-5706e1d7789afdab9316cc056b74d23a30676909.tar.gz px4-firmware-5706e1d7789afdab9316cc056b74d23a30676909.tar.bz2 px4-firmware-5706e1d7789afdab9316cc056b74d23a30676909.zip |
use mavros arming service to arm
Diffstat (limited to 'integrationtests')
-rwxr-xr-x | integrationtests/demo_tests/mavros_offboard_posctl_test.py | 7 |
1 files changed, 7 insertions, 0 deletions
diff --git a/integrationtests/demo_tests/mavros_offboard_posctl_test.py b/integrationtests/demo_tests/mavros_offboard_posctl_test.py index 7468ad53f..59f8276b1 100755 --- a/integrationtests/demo_tests/mavros_offboard_posctl_test.py +++ b/integrationtests/demo_tests/mavros_offboard_posctl_test.py @@ -49,6 +49,7 @@ from px4.msg import vehicle_control_mode from std_msgs.msg import Header from geometry_msgs.msg import PoseStamped, Quaternion from tf.transformations import quaternion_from_euler +from mavros.srv import CommandBool class OffboardPosctlTest(unittest.TestCase): @@ -57,6 +58,7 @@ class OffboardPosctlTest(unittest.TestCase): 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.hasPos = False @@ -111,10 +113,15 @@ class OffboardPosctlTest(unittest.TestCase): self.assertTrue(count < timeout, "took too long to get to position") + def arm(self): + return self.cmdArm(value=True) + # # Test offboard POSCTL # def test_posctl(self): + self.assertTrue(self.arm(), "Could not arm") + # prepare flight path assertion positions = ( (0,0,0), |