Skip to content
Snippets Groups Projects
Commit 9924f551 authored by Andreas Antener's avatar Andreas Antener
Browse files

update attitude and position setpoint topics

parent f8c88766
No related branches found
No related tags found
No related merge requests found
......@@ -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
......
......@@ -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
......
......@@ -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)" />
......
......@@ -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))
{
}
......
......@@ -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))
{
}
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment