diff --git a/integrationtests/demo_tests/mavros_offboard_posctl_test.py b/integrationtests/demo_tests/mavros_offboard_posctl_test.py
index 533d9ad3c3..14c7d6c19d 100755
--- a/integrationtests/demo_tests/mavros_offboard_posctl_test.py
+++ b/integrationtests/demo_tests/mavros_offboard_posctl_test.py
@@ -55,11 +55,11 @@ class OffboardPosctlTest(unittest.TestCase):
def setUp(self):
rospy.init_node('test_node', anonymous=True)
- rospy.wait_for_service('px4_multicopter/mavros/cmd/arming', 30)
- rospy.Subscriber('px4_multicopter/vehicle_control_mode', vehicle_control_mode, self.vehicle_control_mode_callback)
- rospy.Subscriber("px4_multicopter/mavros/position/local", PoseStamped, self.position_callback)
- self.pubSpt = rospy.Publisher('px4_multicopter/mavros/setpoint/local_position', PoseStamped, queue_size=10)
- self.cmdArm = rospy.ServiceProxy("px4_multicopter/mavros/cmd/arming", CommandBool)
+ rospy.wait_for_service('mavros/cmd/arming', 30)
+ rospy.Subscriber('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)
self.rate = rospy.Rate(10) # 10hz
self.rateSec = rospy.Rate(1)
self.hasPos = False
diff --git a/launch/mavros_sitl.launch b/launch/mavros_sitl.launch
index 582fdaa7d2..40010a2735 100644
--- a/launch/mavros_sitl.launch
+++ b/launch/mavros_sitl.launch
@@ -2,22 +2,20 @@
-
-
-
-
-
+
+
+
+
-
+
-
-
-
+
+
+
-
-
-
-
-
-
+
+
+
+
+