From 120fca61ad2fde5a8967f7dc554d8bd05499593a Mon Sep 17 00:00:00 2001 From: Andreas Antener Date: Wed, 8 Apr 2015 09:48:27 +0200 Subject: use global namespace for tests --- integrationtests/demo_tests/direct_manual_input_test.py | 4 ++-- integrationtests/demo_tests/direct_offboard_posctl_test.py | 6 +++--- integrationtests/demo_tests/direct_tests.launch | 10 +++++++--- integrationtests/demo_tests/flight_path_assertion.py | 8 ++++---- integrationtests/demo_tests/manual_input.py | 4 ++-- integrationtests/demo_tests/mavros_offboard_attctl_test.py | 10 +++++----- integrationtests/demo_tests/mavros_offboard_posctl_test.py | 6 +++--- integrationtests/demo_tests/mavros_tests.launch | 10 ++++++---- 8 files changed, 32 insertions(+), 26 deletions(-) (limited to 'integrationtests') diff --git a/integrationtests/demo_tests/direct_manual_input_test.py b/integrationtests/demo_tests/direct_manual_input_test.py index 394500e94..e5d288767 100755 --- a/integrationtests/demo_tests/direct_manual_input_test.py +++ b/integrationtests/demo_tests/direct_manual_input_test.py @@ -67,8 +67,8 @@ class ManualInputTest(unittest.TestCase): # def test_manual_input(self): rospy.init_node('test_node', anonymous=True) - 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) + rospy.Subscriber('actuator_armed', actuator_armed, self.actuator_armed_callback) + rospy.Subscriber('vehicle_control_mode', vehicle_control_mode, self.vehicle_control_mode_callback) man_in = ManualInput() diff --git a/integrationtests/demo_tests/direct_offboard_posctl_test.py b/integrationtests/demo_tests/direct_offboard_posctl_test.py index 734bcf590..9a6c4af78 100755 --- a/integrationtests/demo_tests/direct_offboard_posctl_test.py +++ b/integrationtests/demo_tests/direct_offboard_posctl_test.py @@ -68,9 +68,9 @@ class DirectOffboardPosctlTest(unittest.TestCase): self.helper = PX4TestHelper("direct_offboard_posctl_test") self.helper.setUp() - rospy.Subscriber('iris/vehicle_control_mode', vehicle_control_mode, self.vehicle_control_mode_callback) - self.sub_vlp = rospy.Subscriber("iris/vehicle_local_position", vehicle_local_position, self.position_callback) - self.pub_spt = rospy.Publisher('iris/position_setpoint_triplet', position_setpoint_triplet, queue_size=10) + rospy.Subscriber('vehicle_control_mode', vehicle_control_mode, self.vehicle_control_mode_callback) + self.sub_vlp = rospy.Subscriber("vehicle_local_position", vehicle_local_position, self.position_callback) + self.pub_spt = rospy.Publisher('position_setpoint_triplet', position_setpoint_triplet, queue_size=10) self.rate = rospy.Rate(10) # 10hz self.has_pos = False self.local_position = vehicle_local_position() diff --git a/integrationtests/demo_tests/direct_tests.launch b/integrationtests/demo_tests/direct_tests.launch index f332332cf..04ba8a54d 100644 --- a/integrationtests/demo_tests/direct_tests.launch +++ b/integrationtests/demo_tests/direct_tests.launch @@ -3,7 +3,8 @@ - + + @@ -11,8 +12,11 @@ + - - + + + + diff --git a/integrationtests/demo_tests/flight_path_assertion.py b/integrationtests/demo_tests/flight_path_assertion.py index 244324cd0..7de82cc84 100644 --- a/integrationtests/demo_tests/flight_path_assertion.py +++ b/integrationtests/demo_tests/flight_path_assertion.py @@ -62,10 +62,10 @@ class FlightPathAssertion(threading.Thread): # def __init__(self, positions, tunnelRadius=1, yaw_offset=0.2): threading.Thread.__init__(self) - rospy.Subscriber("iris/vehicle_local_position", vehicle_local_position, self.position_callback) - self.spawn_model = rospy.ServiceProxy('gazebo/spawn_sdf_model', SpawnModel) - self.set_model_state = rospy.ServiceProxy('gazebo/set_model_state', SetModelState) - self.delete_model = rospy.ServiceProxy('gazebo/delete_model', DeleteModel) + rospy.Subscriber("vehicle_local_position", vehicle_local_position, self.position_callback) + self.spawn_model = rospy.ServiceProxy('/gazebo/spawn_sdf_model', SpawnModel) + self.set_model_state = rospy.ServiceProxy('/gazebo/set_model_state', SetModelState) + self.delete_model = rospy.ServiceProxy('/gazebo/delete_model', DeleteModel) self.positions = positions self.tunnel_radius = tunnelRadius diff --git a/integrationtests/demo_tests/manual_input.py b/integrationtests/demo_tests/manual_input.py index 167221285..b7adaa31c 100755 --- a/integrationtests/demo_tests/manual_input.py +++ b/integrationtests/demo_tests/manual_input.py @@ -49,8 +49,8 @@ class ManualInput(object): def __init__(self): rospy.init_node('test_node', anonymous=True) - self.pub_mcsp = rospy.Publisher('iris/manual_control_setpoint', manual_control_setpoint, queue_size=10) - self.pub_off = rospy.Publisher('iris/offboard_control_mode', offboard_control_mode, queue_size=10) + self.pub_mcsp = rospy.Publisher('manual_control_setpoint', manual_control_setpoint, queue_size=10) + self.pub_off = rospy.Publisher('offboard_control_mode', offboard_control_mode, queue_size=10) def arm(self): rate = rospy.Rate(10) # 10hz diff --git a/integrationtests/demo_tests/mavros_offboard_attctl_test.py b/integrationtests/demo_tests/mavros_offboard_attctl_test.py index a9cbc2de5..7329c1efc 100755 --- a/integrationtests/demo_tests/mavros_offboard_attctl_test.py +++ b/integrationtests/demo_tests/mavros_offboard_attctl_test.py @@ -61,14 +61,14 @@ class MavrosOffboardAttctlTest(unittest.TestCase): def setUp(self): rospy.init_node('test_node', anonymous=True) - rospy.wait_for_service('iris/mavros/cmd/arming', 30) + rospy.wait_for_service('mavros/cmd/arming', 30) self.helper = PX4TestHelper("mavros_offboard_attctl_test") self.helper.setUp() - rospy.Subscriber('iris/vehicle_control_mode', vehicle_control_mode, self.vehicle_control_mode_callback) - rospy.Subscriber("iris/mavros/local_position/local", PoseStamped, self.position_callback) - self.pub_att = rospy.Publisher('iris/mavros/setpoint_attitude/attitude', PoseStamped, queue_size=10) - self.pub_thr = rospy.Publisher('iris/mavros/setpoint_attitude/att_throttle', Float64, queue_size=10) + rospy.Subscriber('vehicle_control_mode', vehicle_control_mode, self.vehicle_control_mode_callback) + rospy.Subscriber("mavros/local_position/local", PoseStamped, self.position_callback) + self.pub_att = rospy.Publisher('mavros/setpoint_attitude/attitude', PoseStamped, queue_size=10) + self.pub_thr = rospy.Publisher('mavros/setpoint_attitude/att_throttle', Float64, queue_size=10) self.rate = rospy.Rate(10) # 10hz self.has_pos = False self.control_mode = vehicle_control_mode() diff --git a/integrationtests/demo_tests/mavros_offboard_posctl_test.py b/integrationtests/demo_tests/mavros_offboard_posctl_test.py index 1c6bade5c..58e7ae2ed 100755 --- a/integrationtests/demo_tests/mavros_offboard_posctl_test.py +++ b/integrationtests/demo_tests/mavros_offboard_posctl_test.py @@ -67,9 +67,9 @@ class MavrosOffboardPosctlTest(unittest.TestCase): self.helper = PX4TestHelper("mavros_offboard_posctl_test") self.helper.setUp() - rospy.Subscriber('iris/vehicle_control_mode', vehicle_control_mode, self.vehicle_control_mode_callback) - rospy.Subscriber("iris/mavros/local_position/local", PoseStamped, self.position_callback) - self.pub_spt = rospy.Publisher('iris/mavros/setpoint_position/local', PoseStamped, queue_size=10) + rospy.Subscriber('vehicle_control_mode', vehicle_control_mode, self.vehicle_control_mode_callback) + rospy.Subscriber("mavros/local_position/local", PoseStamped, self.position_callback) + self.pub_spt = rospy.Publisher('mavros/setpoint_position/local', PoseStamped, queue_size=10) self.rate = rospy.Rate(10) # 10hz self.has_pos = False self.local_position = PoseStamped() diff --git a/integrationtests/demo_tests/mavros_tests.launch b/integrationtests/demo_tests/mavros_tests.launch index cc4918307..cdafc967c 100644 --- a/integrationtests/demo_tests/mavros_tests.launch +++ b/integrationtests/demo_tests/mavros_tests.launch @@ -12,12 +12,14 @@ - + - + - - + + + + -- cgit v1.2.3