aboutsummaryrefslogtreecommitdiff
path: root/integrationtests
diff options
context:
space:
mode:
Diffstat (limited to 'integrationtests')
-rwxr-xr-xintegrationtests/demo_tests/mavros_offboard_attctl_test.py2
-rwxr-xr-xintegrationtests/demo_tests/mavros_offboard_posctl_test.py2
2 files changed, 2 insertions, 2 deletions
diff --git a/integrationtests/demo_tests/mavros_offboard_attctl_test.py b/integrationtests/demo_tests/mavros_offboard_attctl_test.py
index 63e2922d0..a9cbc2de5 100755
--- a/integrationtests/demo_tests/mavros_offboard_attctl_test.py
+++ b/integrationtests/demo_tests/mavros_offboard_attctl_test.py
@@ -66,7 +66,7 @@ class MavrosOffboardAttctlTest(unittest.TestCase):
self.helper.setUp()
rospy.Subscriber('iris/vehicle_control_mode', vehicle_control_mode, self.vehicle_control_mode_callback)
- rospy.Subscriber("iris/mavros/position/local", PoseStamped, self.position_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)
self.rate = rospy.Rate(10) # 10hz
diff --git a/integrationtests/demo_tests/mavros_offboard_posctl_test.py b/integrationtests/demo_tests/mavros_offboard_posctl_test.py
index 58796dc60..1c6bade5c 100755
--- a/integrationtests/demo_tests/mavros_offboard_posctl_test.py
+++ b/integrationtests/demo_tests/mavros_offboard_posctl_test.py
@@ -68,7 +68,7 @@ class MavrosOffboardPosctlTest(unittest.TestCase):
self.helper.setUp()
rospy.Subscriber('iris/vehicle_control_mode', vehicle_control_mode, self.vehicle_control_mode_callback)
- rospy.Subscriber("iris/mavros/position/local", PoseStamped, self.position_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)
self.rate = rospy.Rate(10) # 10hz
self.has_pos = False