From 17f49ec8cb2da6034dcdaf1c1b6adf1baa73f5d7 Mon Sep 17 00:00:00 2001 From: Andreas Antener <antener_a@gmx.ch> Date: Sun, 11 Dec 2016 16:16:07 +0100 Subject: [PATCH] Integration tests: use separate commands to set mode and arm --- .../px4_it/mavros/mavros_offboard_attctl_test.py | 10 +++++++++- .../px4_it/mavros/mavros_offboard_posctl_test.py | 10 +++++++++- .../python_src/px4_it/mavros/mission_test.py | 13 ++++++++++--- 3 files changed, 28 insertions(+), 5 deletions(-) diff --git a/integrationtests/python_src/px4_it/mavros/mavros_offboard_attctl_test.py b/integrationtests/python_src/px4_it/mavros/mavros_offboard_attctl_test.py index 8668a34d2a..9c90289737 100755 --- a/integrationtests/python_src/px4_it/mavros/mavros_offboard_attctl_test.py +++ b/integrationtests/python_src/px4_it/mavros/mavros_offboard_attctl_test.py @@ -40,6 +40,7 @@ PKG = 'px4' import unittest import rospy import rosbag +import time from std_msgs.msg import Header from std_msgs.msg import Float64 @@ -122,7 +123,14 @@ class MavrosOffboardAttctlTest(unittest.TestCase): # (need to wait the first few rounds until PX4 has the offboard stream) if not armed and count > 5: self._srv_cmd_long(False, 176, False, - 128 | 1, 6, 0, 0, 0, 0, 0) + 1, 6, 0, 0, 0, 0, 0) + # make sure the first command doesn't get lost + time.sleep(1) + + self._srv_cmd_long(False, 400, False, + # arm + 1, 0, 0, 0, 0, 0, 0) + armed = True if (self.local_position.pose.position.x > 5 diff --git a/integrationtests/python_src/px4_it/mavros/mavros_offboard_posctl_test.py b/integrationtests/python_src/px4_it/mavros/mavros_offboard_posctl_test.py index bd106d672b..c39f400a67 100755 --- a/integrationtests/python_src/px4_it/mavros/mavros_offboard_posctl_test.py +++ b/integrationtests/python_src/px4_it/mavros/mavros_offboard_posctl_test.py @@ -41,6 +41,7 @@ import unittest import rospy import math import rosbag +import time from numpy import linalg import numpy as np @@ -131,7 +132,14 @@ class MavrosOffboardPosctlTest(unittest.TestCase): # (need to wait the first few rounds until PX4 has the offboard stream) if not self.armed and count > 5: self._srv_cmd_long(False, 176, False, - 128 | 1, 6, 0, 0, 0, 0, 0) + 1, 6, 0, 0, 0, 0, 0) + # make sure the first command doesn't get lost + time.sleep(1) + + self._srv_cmd_long(False, 400, False, + # arm + 1, 0, 0, 0, 0, 0, 0) + self.armed = True if self.is_at_position(pos.pose.position.x, pos.pose.position.y, pos.pose.position.z, 1): diff --git a/integrationtests/python_src/px4_it/mavros/mission_test.py b/integrationtests/python_src/px4_it/mavros/mission_test.py index 5b3fbd2e53..95b71b9411 100755 --- a/integrationtests/python_src/px4_it/mavros/mission_test.py +++ b/integrationtests/python_src/px4_it/mavros/mission_test.py @@ -43,6 +43,7 @@ import math import rosbag import sys import os +import time import mavros from pymavlink import mavutil @@ -174,10 +175,16 @@ class MavrosMissionTest(unittest.TestCase): (self.mission_name, lat, lon, alt, xy_radius, z_radius, timeout, index, self.last_pos_d, self.last_alt_d))) def run_mission(self): - """switch mode: armed | auto""" + """switch mode: auto and arm""" self._srv_cmd_long(False, 176, False, - # arm | custom, auto, mission - 128 | 1, 4, 4, 0, 0, 0, 0) + # custom, auto, mission + 1, 4, 4, 0, 0, 0, 0) + # make sure the first command doesn't get lost + time.sleep(1) + + self._srv_cmd_long(False, 400, False, + # arm + 1, 0, 0, 0, 0, 0, 0) def wait_until_ready(self): """FIXME: hack to wait for simulation to be ready""" -- GitLab