diff options
Diffstat (limited to 'integrationtests')
-rwxr-xr-x | integrationtests/demo_tests/mavros_offboard_attctl_test.py | 8 | ||||
-rwxr-xr-x | integrationtests/demo_tests/mavros_offboard_posctl_test.py | 4 |
2 files changed, 6 insertions, 6 deletions
diff --git a/integrationtests/demo_tests/mavros_offboard_attctl_test.py b/integrationtests/demo_tests/mavros_offboard_attctl_test.py index ef875ce61..63e2922d0 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 1383cd04c..58796dc60 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 |