forked from Archive/PX4-Autopilot
Integration tests: use separate commands to set mode and arm
This commit is contained in:
parent
adc9ed61b8
commit
17f49ec8cb
|
@ -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
|
||||
|
|
|
@ -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):
|
||||
|
|
|
@ -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"""
|
||||
|
|
Loading…
Reference in New Issue