Skip to content

Commit

Permalink
update attitude and position setpoint topics
Browse files Browse the repository at this point in the history
  • Loading branch information
AndreasAntener committed Apr 8, 2015
1 parent f8c8876 commit 9924f55
Show file tree
Hide file tree
Showing 5 changed files with 12 additions and 11 deletions.
8 changes: 4 additions & 4 deletions integrationtests/demo_tests/mavros_offboard_attctl_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -67,8 +67,8 @@ def setUp(self):

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()
Expand Down Expand Up @@ -110,9 +110,9 @@ def test_attctl(self):
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
Expand Down
4 changes: 2 additions & 2 deletions integrationtests/demo_tests/mavros_offboard_posctl_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -69,7 +69,7 @@ def setUp(self):

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()
Expand Down Expand Up @@ -128,7 +128,7 @@ def reach_position(self, x, y, z, timeout):
# 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
Expand Down
5 changes: 3 additions & 2 deletions launch/mavros_sitl.launch
Original file line number Diff line number Diff line change
Expand Up @@ -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)" />
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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))
{
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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))
{
}

Expand Down

0 comments on commit 9924f55

Please sign in to comment.