aboutsummaryrefslogtreecommitdiff
path: root/integrationtests
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2015-03-07 19:27:36 +0100
committerThomas Gubler <thomasgubler@gmail.com>2015-03-10 20:56:53 +0100
commit9a9ca184e80622f2e217b4397be78a74cb1dad7f (patch)
treea1ea9f707a2c6b2e9fa0db64884aea45d75f4bbb /integrationtests
parentdf4f8259026bb7882659303558f5fb5b0d99e5f6 (diff)
downloadpx4-firmware-9a9ca184e80622f2e217b4397be78a74cb1dad7f.tar.gz
px4-firmware-9a9ca184e80622f2e217b4397be78a74cb1dad7f.tar.bz2
px4-firmware-9a9ca184e80622f2e217b4397be78a74cb1dad7f.zip
update namespace in mavros tests
Diffstat (limited to 'integrationtests')
-rwxr-xr-xintegrationtests/demo_tests/direct_manual_input_test.py4
-rwxr-xr-xintegrationtests/demo_tests/direct_offboard_posctl_test.py6
-rwxr-xr-xintegrationtests/demo_tests/manual_input.py6
-rwxr-xr-xintegrationtests/demo_tests/mavros_offboard_attctl_test.py18
-rwxr-xr-xintegrationtests/demo_tests/mavros_offboard_posctl_test.py18
-rw-r--r--integrationtests/demo_tests/mavros_tests.launch8
6 files changed, 32 insertions, 28 deletions
diff --git a/integrationtests/demo_tests/direct_manual_input_test.py b/integrationtests/demo_tests/direct_manual_input_test.py
index 6d115316b..b037d842f 100755
--- a/integrationtests/demo_tests/direct_manual_input_test.py
+++ b/integrationtests/demo_tests/direct_manual_input_test.py
@@ -64,8 +64,8 @@ class ManualInputTest(unittest.TestCase):
#
def test_manual_input(self):
rospy.init_node('test_node', anonymous=True)
- rospy.Subscriber('px4_multicopter/actuator_armed', actuator_armed, self.actuator_armed_callback)
- rospy.Subscriber('px4_multicopter/vehicle_control_mode', vehicle_control_mode, self.vehicle_control_mode_callback)
+ rospy.Subscriber('iris/actuator_armed', actuator_armed, self.actuator_armed_callback)
+ rospy.Subscriber('iris/vehicle_control_mode', vehicle_control_mode, self.vehicle_control_mode_callback)
man = ManualInput()
diff --git a/integrationtests/demo_tests/direct_offboard_posctl_test.py b/integrationtests/demo_tests/direct_offboard_posctl_test.py
index e09550bbc..18239e926 100755
--- a/integrationtests/demo_tests/direct_offboard_posctl_test.py
+++ b/integrationtests/demo_tests/direct_offboard_posctl_test.py
@@ -66,9 +66,9 @@ class DirectOffboardPosctlTest(unittest.TestCase):
def setUp(self):
rospy.init_node('test_node', anonymous=True)
- rospy.Subscriber('px4_multicopter/vehicle_control_mode', vehicle_control_mode, self.vehicle_control_mode_callback)
- rospy.Subscriber("px4_multicopter/vehicle_local_position", vehicle_local_position, self.position_callback)
- self.pubSpt = rospy.Publisher('px4_multicopter/position_setpoint_triplet', position_setpoint_triplet, queue_size=10)
+ rospy.Subscriber('iris/vehicle_control_mode', vehicle_control_mode, self.vehicle_control_mode_callback)
+ rospy.Subscriber("iris/vehicle_local_position", vehicle_local_position, self.position_callback)
+ self.pubSpt = rospy.Publisher('iris/position_setpoint_triplet', position_setpoint_triplet, queue_size=10)
self.rate = rospy.Rate(10) # 10hz
def tearDown(self):
diff --git a/integrationtests/demo_tests/manual_input.py b/integrationtests/demo_tests/manual_input.py
index 9b2471a00..7072464de 100755
--- a/integrationtests/demo_tests/manual_input.py
+++ b/integrationtests/demo_tests/manual_input.py
@@ -54,8 +54,8 @@ class ManualInput:
def __init__(self):
rospy.init_node('test_node', anonymous=True)
- self.pubMcsp = rospy.Publisher('px4_multicopter/manual_control_setpoint', manual_control_setpoint, queue_size=10)
- self.pubOff = rospy.Publisher('px4_multicopter/offboard_control_mode', offboard_control_mode, queue_size=10)
+ self.pubMcsp = rospy.Publisher('iris/manual_control_setpoint', manual_control_setpoint, queue_size=10)
+ self.pubOff = rospy.Publisher('iris/offboard_control_mode', offboard_control_mode, queue_size=10)
self.pubAtt = rospy.Publisher('iris/command/attitude', CommandAttitudeThrust, queue_size=10)
def arm(self):
@@ -85,7 +85,7 @@ class ManualInput:
# Fake input to iris commander
self.pubAtt.publish(att)
rate.sleep()
- count = count + 1
+ count = count + 1
pos.r = 1
count = 0
diff --git a/integrationtests/demo_tests/mavros_offboard_attctl_test.py b/integrationtests/demo_tests/mavros_offboard_attctl_test.py
index a52f7ffc1..92cdf1e0a 100755
--- a/integrationtests/demo_tests/mavros_offboard_attctl_test.py
+++ b/integrationtests/demo_tests/mavros_offboard_attctl_test.py
@@ -65,12 +65,12 @@ class MavrosOffboardAttctlTest(unittest.TestCase):
def setUp(self):
rospy.init_node('test_node', anonymous=True)
- rospy.wait_for_service('mavros/cmd/arming', 30)
- rospy.Subscriber('px4_multicopter/vehicle_control_mode', vehicle_control_mode, self.vehicle_control_mode_callback)
- rospy.Subscriber("mavros/position/local", PoseStamped, self.position_callback)
- self.pubAtt = rospy.Publisher('mavros/setpoint/attitude', PoseStamped, queue_size=10)
- self.pubThr = rospy.Publisher('mavros/setpoint/att_throttle', Float64, queue_size=10)
- self.cmdArm = rospy.ServiceProxy("mavros/cmd/arming", CommandBool)
+ rospy.wait_for_service('iris/mavros/cmd/arming', 30)
+ rospy.Subscriber('iris/vehicle_control_mode', vehicle_control_mode, self.vehicle_control_mode_callback)
+ rospy.Subscriber("iris/mavros/position/local", PoseStamped, self.position_callback)
+ self.pubAtt = rospy.Publisher('iris/mavros/setpoint/attitude', PoseStamped, queue_size=10)
+ self.pubThr = rospy.Publisher('iris/mavros/setpoint/att_throttle', Float64, queue_size=10)
+ self.cmdArm = rospy.ServiceProxy("iris/mavros/cmd/arming", CommandBool)
self.rate = rospy.Rate(10) # 10hz
self.rateSec = rospy.Rate(1)
self.hasPos = False
@@ -109,7 +109,7 @@ class MavrosOffboardAttctlTest(unittest.TestCase):
# set some attitude and thrust
att = PoseStamped()
- att.header = Header()
+ att.header = Header()
att.header.frame_id = "base_footprint"
att.header.stamp = rospy.Time.now()
quaternion = quaternion_from_euler(0.15, 0.15, 0)
@@ -126,7 +126,7 @@ class MavrosOffboardAttctlTest(unittest.TestCase):
att.header.stamp = rospy.Time.now()
self.pubAtt.publish(att)
self.pubThr.publish(throttle)
-
+
if (self.localPosition.pose.position.x > 5
and self.localPosition.pose.position.z > 5
and self.localPosition.pose.position.y < -5):
@@ -135,7 +135,7 @@ class MavrosOffboardAttctlTest(unittest.TestCase):
self.rate.sleep()
self.assertTrue(count < timeout, "took too long to cross boundaries")
-
+
if __name__ == '__main__':
import rostest
diff --git a/integrationtests/demo_tests/mavros_offboard_posctl_test.py b/integrationtests/demo_tests/mavros_offboard_posctl_test.py
index a3739ae5c..6d26015e7 100755
--- a/integrationtests/demo_tests/mavros_offboard_posctl_test.py
+++ b/integrationtests/demo_tests/mavros_offboard_posctl_test.py
@@ -64,11 +64,11 @@ class MavrosOffboardPosctlTest(unittest.TestCase):
def setUp(self):
rospy.init_node('test_node', anonymous=True)
- rospy.wait_for_service('mavros/cmd/arming', 30)
- rospy.Subscriber('px4_multicopter/vehicle_control_mode', vehicle_control_mode, self.vehicle_control_mode_callback)
- rospy.Subscriber("mavros/position/local", PoseStamped, self.position_callback)
- self.pubSpt = rospy.Publisher('mavros/setpoint/local_position', PoseStamped, queue_size=10)
- self.cmdArm = rospy.ServiceProxy("mavros/cmd/arming", CommandBool)
+ rospy.wait_for_service('iris/mavros/cmd/arming', 30)
+ rospy.Subscriber('iris/vehicle_control_mode', vehicle_control_mode, self.vehicle_control_mode_callback)
+ rospy.Subscriber("iris/mavros/position/local", PoseStamped, self.position_callback)
+ self.pubSpt = rospy.Publisher('iris/mavros/setpoint/local_position', PoseStamped, queue_size=10)
+ self.cmdArm = rospy.ServiceProxy("iris/mavros/cmd/arming", CommandBool)
self.rate = rospy.Rate(10) # 10hz
self.rateSec = rospy.Rate(1)
self.hasPos = False
@@ -100,7 +100,7 @@ class MavrosOffboardPosctlTest(unittest.TestCase):
def reach_position(self, x, y, z, timeout):
# set a position setpoint
pos = PoseStamped()
- pos.header = Header()
+ pos.header = Header()
pos.header.frame_id = "base_footprint"
pos.pose.position.x = x
pos.pose.position.y = y
@@ -118,7 +118,7 @@ class MavrosOffboardPosctlTest(unittest.TestCase):
# update timestamp for each published SP
pos.header.stamp = rospy.Time.now()
self.pubSpt.publish(pos)
-
+
if(self.is_at_position(pos.pose.position.x, pos.pose.position.y, pos.pose.position.z, 0.5)):
break
count = count + 1
@@ -153,7 +153,7 @@ class MavrosOffboardPosctlTest(unittest.TestCase):
for i in range(0, len(positions)):
self.reach_position(positions[i][0], positions[i][1], positions[i][2], 120)
-
+
# does it hold the position for Y seconds?
positionHeld = True
count = 0
@@ -166,7 +166,7 @@ class MavrosOffboardPosctlTest(unittest.TestCase):
self.rate.sleep()
self.assertTrue(count == timeout, "position could not be held")
-
+
if __name__ == '__main__':
import rostest
diff --git a/integrationtests/demo_tests/mavros_tests.launch b/integrationtests/demo_tests/mavros_tests.launch
index 4651f0dc9..e42db6043 100644
--- a/integrationtests/demo_tests/mavros_tests.launch
+++ b/integrationtests/demo_tests/mavros_tests.launch
@@ -3,7 +3,8 @@
<arg name="gui" default="false"/>
<arg name="enable_logging" default="false"/>
<arg name="enable_ground_truth" default="false"/>
- <arg name="log_file" default="iris"/>
+ <arg name="ns" default="iris"/>
+ <arg name="log_file" default="$(arg ns)"/>
<include file="$(find px4)/launch/gazebo_iris_empty_world.launch">
<arg name="headless" value="$(arg headless)"/>
@@ -11,8 +12,11 @@
<arg name="enable_logging" value="$(arg enable_logging)" />
<arg name="enable_ground_truth" value="$(arg enable_ground_truth)" />
<arg name="log_file" value="$(arg log_file)"/>
+ <arg name="ns" value="$(arg ns)"/>
+ </include>
+ <include file="$(find px4)/launch/mavros_sitl.launch">
+ <arg name="ns" value="$(arg ns)"/>
</include>
- <include file="$(find px4)/launch/mavros_sitl.launch" />
<test test-name="mavros_offboard_posctl_test" pkg="px4" type="mavros_offboard_posctl_test.py" />
<test test-name="mavros_offboard_attctl_test" pkg="px4" type="mavros_offboard_attctl_test.py" />