diff --git a/integrationtests/demo_tests/mavros_offboard_attctl_test.py b/integrationtests/demo_tests/mavros_offboard_attctl_test.py
index ef875ce61ec84ebf5e6b2f783c516eca2997845b..63e2922d00371ff8d1b610dab89a5a80ee882922 100755
--- a/integrationtests/demo_tests/mavros_offboard_attctl_test.py
+++ b/integrationtests/demo_tests/mavros_offboard_attctl_test.py
@@ -67,8 +67,8 @@ class MavrosOffboardAttctlTest(unittest.TestCase):
 
         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.pub_att = rospy.Publisher('iris/mavros/setpoint/attitude', PoseStamped, queue_size=10)
-        self.pub_thr = rospy.Publisher('iris/mavros/setpoint/att_throttle', Float64, queue_size=10)
+        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
         self.has_pos = False
         self.control_mode = vehicle_control_mode()
@@ -110,9 +110,9 @@ class MavrosOffboardAttctlTest(unittest.TestCase):
             att.header.stamp = rospy.Time.now()
 
             self.pub_att.publish(att)
-            self.helper.bag_write('mavros/setpoint/attitude', att)
+            self.helper.bag_write('mavros/setpoint_attitude/attitude', att)
             self.pub_thr.publish(throttle)
-            self.helper.bag_write('mavros/setpoint/att_throttle', throttle)
+            self.helper.bag_write('mavros/setpoint_attitude/att_throttle', throttle)
             self.rate.sleep()
 
             if (self.local_position.pose.position.x > 5
diff --git a/integrationtests/demo_tests/mavros_offboard_posctl_test.py b/integrationtests/demo_tests/mavros_offboard_posctl_test.py
index 1383cd04cddf992f242410c2da1670f4ccdda335..58796dc607542fe5e84a84d2923981f8d3202b94 100755
--- a/integrationtests/demo_tests/mavros_offboard_posctl_test.py
+++ b/integrationtests/demo_tests/mavros_offboard_posctl_test.py
@@ -69,7 +69,7 @@ class MavrosOffboardPosctlTest(unittest.TestCase):
 
         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.pub_spt = rospy.Publisher('iris/mavros/setpoint/local_position', PoseStamped, queue_size=10)
+        self.pub_spt = rospy.Publisher('iris/mavros/setpoint_position/local', PoseStamped, queue_size=10)
         self.rate = rospy.Rate(10) # 10hz
         self.has_pos = False
         self.local_position = PoseStamped()
@@ -128,7 +128,7 @@ class MavrosOffboardPosctlTest(unittest.TestCase):
             # update timestamp for each published SP
             pos.header.stamp = rospy.Time.now()
             self.pub_spt.publish(pos)
-            self.helper.bag_write('mavros/setpoint/local_position', pos)
+            self.helper.bag_write('mavros/setpoint_position/local', pos)
 
             if self.is_at_position(pos.pose.position.x, pos.pose.position.y, pos.pose.position.z, 0.5):
                 break
diff --git a/launch/mavros_sitl.launch b/launch/mavros_sitl.launch
index 7362fa4644d348c7781758c1d46cebbb684298cc..60b85b6ff8aa6016ee31850a0489d668f73e596d 100644
--- a/launch/mavros_sitl.launch
+++ b/launch/mavros_sitl.launch
@@ -9,10 +9,11 @@
 	<arg name="tgt_system" default="1" />
 	<arg name="tgt_component" default="50" />
 
-	<param name="mavros/setpoint/attitude/listen_twist" type="bool" value="false" />
+	<!-- TODO: fix for mavros 0.11.1 because of this: https://github.com/mavlink/mavros/commit/22c09f27e86876f049552cef75b6ceff047358fb -->
+	<param name="mavros/setpoint_attitude/attitude/listen_twist" type="bool" value="false" />
 
 	<include file="$(find mavros)/launch/node.launch">
-		<arg name="blacklist_yaml" value="$(find mavros)/launch/px4_blacklist.yaml" />
+		<arg name="pluginlists_yaml" value="$(find mavros)/launch/px4_pluginlists.yaml" />
 		<arg name="config_yaml" value="$(find mavros)/launch/px4_config.yaml" />
 
 		<arg name="fcu_url" value="$(arg fcu_url)" />
diff --git a/src/platforms/ros/nodes/demo_offboard_attitude_setpoints/demo_offboard_attitude_setpoints.cpp b/src/platforms/ros/nodes/demo_offboard_attitude_setpoints/demo_offboard_attitude_setpoints.cpp
index fb0b09de1ed958cda7f793da99a422b8d99c7c6b..328f545c6b805f0c250aded7780e87f6223ac2c0 100644
--- a/src/platforms/ros/nodes/demo_offboard_attitude_setpoints/demo_offboard_attitude_setpoints.cpp
+++ b/src/platforms/ros/nodes/demo_offboard_attitude_setpoints/demo_offboard_attitude_setpoints.cpp
@@ -49,8 +49,8 @@
 
 DemoOffboardAttitudeSetpoints::DemoOffboardAttitudeSetpoints() :
 	_n(),
-	_attitude_sp_pub(_n.advertise<geometry_msgs::PoseStamped>("mavros/setpoint/attitude", 1)),
-	_thrust_sp_pub(_n.advertise<std_msgs::Float64>("mavros/setpoint/att_throttle", 1))
+	_attitude_sp_pub(_n.advertise<geometry_msgs::PoseStamped>("mavros/setpoint_attitude/attitude", 1)),
+	_thrust_sp_pub(_n.advertise<std_msgs::Float64>("mavros/setpoint_attitude/att_throttle", 1))
 {
 }
 
diff --git a/src/platforms/ros/nodes/demo_offboard_position_setpoints/demo_offboard_position_setpoints.cpp b/src/platforms/ros/nodes/demo_offboard_position_setpoints/demo_offboard_position_setpoints.cpp
index 125ceaddc75a2c6f7a444dd9beb8bc56296e2018..8a626f255e2476c0501ea7b8f7a509ce367c7e03 100644
--- a/src/platforms/ros/nodes/demo_offboard_position_setpoints/demo_offboard_position_setpoints.cpp
+++ b/src/platforms/ros/nodes/demo_offboard_position_setpoints/demo_offboard_position_setpoints.cpp
@@ -46,7 +46,7 @@
 
 DemoOffboardPositionSetpoints::DemoOffboardPositionSetpoints() :
 	_n(),
-	_local_position_sp_pub(_n.advertise<geometry_msgs::PoseStamped>("mavros/setpoint/local_position", 1))
+	_local_position_sp_pub(_n.advertise<geometry_msgs::PoseStamped>("mavros/setpoint_position/local", 1))
 {
 }