moved mavros to root node

This commit is contained in:
Andreas Antener
2015-02-27 18:01:16 +01:00
parent 5d8516b356
commit c4b938fee6
2 changed files with 18 additions and 20 deletions

View File

@@ -55,11 +55,11 @@ class OffboardPosctlTest(unittest.TestCase):
def setUp(self): def setUp(self):
rospy.init_node('test_node', anonymous=True) rospy.init_node('test_node', anonymous=True)
rospy.wait_for_service('px4_multicopter/mavros/cmd/arming', 30) rospy.wait_for_service('mavros/cmd/arming', 30)
rospy.Subscriber('px4_multicopter/vehicle_control_mode', vehicle_control_mode, self.vehicle_control_mode_callback) rospy.Subscriber('vehicle_control_mode', vehicle_control_mode, self.vehicle_control_mode_callback)
rospy.Subscriber("px4_multicopter/mavros/position/local", PoseStamped, self.position_callback) rospy.Subscriber("mavros/position/local", PoseStamped, self.position_callback)
self.pubSpt = rospy.Publisher('px4_multicopter/mavros/setpoint/local_position', PoseStamped, queue_size=10) self.pubSpt = rospy.Publisher('mavros/setpoint/local_position', PoseStamped, queue_size=10)
self.cmdArm = rospy.ServiceProxy("px4_multicopter/mavros/cmd/arming", CommandBool) self.cmdArm = rospy.ServiceProxy("mavros/cmd/arming", CommandBool)
self.rate = rospy.Rate(10) # 10hz self.rate = rospy.Rate(10) # 10hz
self.rateSec = rospy.Rate(1) self.rateSec = rospy.Rate(1)
self.hasPos = False self.hasPos = False

View File

@@ -2,22 +2,20 @@
<!-- vim: set ft=xml noet : --> <!-- vim: set ft=xml noet : -->
<!-- example launch script for PX4 based FCU's --> <!-- example launch script for PX4 based FCU's -->
<group ns="px4_multicopter"> <arg name="fcu_url" default="udp://localhost:14560@localhost:14565" />
<arg name="fcu_url" default="udp://localhost:14560@localhost:14565" /> <arg name="gcs_url" default="" />
<arg name="gcs_url" default="" /> <arg name="tgt_system" default="1" />
<arg name="tgt_system" default="1" /> <arg name="tgt_component" default="50" />
<arg name="tgt_component" default="50" />
<param name="mavros/setpoint/attitude/listen_twist" type="bool" value="false" /> <param name="mavros/setpoint/attitude/listen_twist" type="bool" value="false" />
<include file="$(find mavros)/launch/node.launch"> <include file="$(find mavros)/launch/node.launch">
<arg name="blacklist_yaml" value="$(find mavros)/launch/px4_blacklist.yaml" /> <arg name="blacklist_yaml" value="$(find mavros)/launch/px4_blacklist.yaml" />
<arg name="config_yaml" value="$(find mavros)/launch/px4_config.yaml" /> <arg name="config_yaml" value="$(find mavros)/launch/px4_config.yaml" />
<arg name="fcu_url" value="$(arg fcu_url)" /> <arg name="fcu_url" value="$(arg fcu_url)" />
<arg name="gcs_url" value="$(arg gcs_url)" /> <arg name="gcs_url" value="$(arg gcs_url)" />
<arg name="tgt_system" value="$(arg tgt_system)" /> <arg name="tgt_system" value="$(arg tgt_system)" />
<arg name="tgt_component" value="$(arg tgt_component)" /> <arg name="tgt_component" value="$(arg tgt_component)" />
</include> </include>
</group>
</launch> </launch>