Browse Source

moved mavros to root node

sbg
Andreas Antener 10 years ago
parent
commit
c4b938fee6
  1. 10
      integrationtests/demo_tests/mavros_offboard_posctl_test.py
  2. 2
      launch/mavros_sitl.launch

10
integrationtests/demo_tests/mavros_offboard_posctl_test.py

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

2
launch/mavros_sitl.launch

@ -2,7 +2,6 @@ @@ -2,7 +2,6 @@
<!-- vim: set ft=xml noet : -->
<!-- example launch script for PX4 based FCU's -->
<group ns="px4_multicopter">
<arg name="fcu_url" default="udp://localhost:14560@localhost:14565" />
<arg name="gcs_url" default="" />
<arg name="tgt_system" default="1" />
@ -19,5 +18,4 @@ @@ -19,5 +18,4 @@
<arg name="tgt_system" value="$(arg tgt_system)" />
<arg name="tgt_component" value="$(arg tgt_component)" />
</include>
</group>
</launch>

Loading…
Cancel
Save