Integration tests: use separate commands to set mode and arm

This commit is contained in:
Andreas Antener 2016-12-11 16:16:07 +01:00 committed by Lorenz Meier
parent adc9ed61b8
commit 17f49ec8cb
3 changed files with 28 additions and 5 deletions

View File

@ -40,6 +40,7 @@ PKG = 'px4'
import unittest import unittest
import rospy import rospy
import rosbag import rosbag
import time
from std_msgs.msg import Header from std_msgs.msg import Header
from std_msgs.msg import Float64 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) # (need to wait the first few rounds until PX4 has the offboard stream)
if not armed and count > 5: if not armed and count > 5:
self._srv_cmd_long(False, 176, False, 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 armed = True
if (self.local_position.pose.position.x > 5 if (self.local_position.pose.position.x > 5

View File

@ -41,6 +41,7 @@ import unittest
import rospy import rospy
import math import math
import rosbag import rosbag
import time
from numpy import linalg from numpy import linalg
import numpy as np 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) # (need to wait the first few rounds until PX4 has the offboard stream)
if not self.armed and count > 5: if not self.armed and count > 5:
self._srv_cmd_long(False, 176, False, 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 self.armed = True
if self.is_at_position(pos.pose.position.x, pos.pose.position.y, pos.pose.position.z, 1): if self.is_at_position(pos.pose.position.x, pos.pose.position.y, pos.pose.position.z, 1):

View File

@ -43,6 +43,7 @@ import math
import rosbag import rosbag
import sys import sys
import os import os
import time
import mavros import mavros
from pymavlink import mavutil 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))) (self.mission_name, lat, lon, alt, xy_radius, z_radius, timeout, index, self.last_pos_d, self.last_alt_d)))
def run_mission(self): def run_mission(self):
"""switch mode: armed | auto""" """switch mode: auto and arm"""
self._srv_cmd_long(False, 176, False, self._srv_cmd_long(False, 176, False,
# arm | custom, auto, mission # custom, auto, mission
128 | 1, 4, 4, 0, 0, 0, 0) 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): def wait_until_ready(self):
"""FIXME: hack to wait for simulation to be ready""" """FIXME: hack to wait for simulation to be ready"""