aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorAndreas Antener <antener_a@gmx.ch>2015-02-27 18:01:16 +0100
committerAndreas Antener <antener_a@gmx.ch>2015-02-28 20:03:49 +0100
commitc4b938fee625d1c9aabfd5c75d63635384f5d52f (patch)
tree063bfb8ca220686e586f823804ab121f86ef7fef
parent5d8516b356a58c865de2336c211e1974f2f453e2 (diff)
downloadpx4-firmware-c4b938fee625d1c9aabfd5c75d63635384f5d52f.tar.gz
px4-firmware-c4b938fee625d1c9aabfd5c75d63635384f5d52f.tar.bz2
px4-firmware-c4b938fee625d1c9aabfd5c75d63635384f5d52f.zip
moved mavros to root node
-rwxr-xr-xintegrationtests/demo_tests/mavros_offboard_posctl_test.py10
-rw-r--r--launch/mavros_sitl.launch28
2 files changed, 18 insertions, 20 deletions
diff --git a/integrationtests/demo_tests/mavros_offboard_posctl_test.py b/integrationtests/demo_tests/mavros_offboard_posctl_test.py
index 533d9ad3c..14c7d6c19 100755
--- a/integrationtests/demo_tests/mavros_offboard_posctl_test.py
+++ b/integrationtests/demo_tests/mavros_offboard_posctl_test.py
@@ -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
diff --git a/launch/mavros_sitl.launch b/launch/mavros_sitl.launch
index 582fdaa7d..40010a273 100644
--- a/launch/mavros_sitl.launch
+++ b/launch/mavros_sitl.launch
@@ -2,22 +2,20 @@
<!-- 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" />
- <arg name="tgt_component" default="50" />
+ <arg name="fcu_url" default="udp://localhost:14560@localhost:14565" />
+ <arg name="gcs_url" default="" />
+ <arg name="tgt_system" default="1" />
+ <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">
- <arg name="blacklist_yaml" value="$(find mavros)/launch/px4_blacklist.yaml" />
- <arg name="config_yaml" value="$(find mavros)/launch/px4_config.yaml" />
+ <include file="$(find mavros)/launch/node.launch">
+ <arg name="blacklist_yaml" value="$(find mavros)/launch/px4_blacklist.yaml" />
+ <arg name="config_yaml" value="$(find mavros)/launch/px4_config.yaml" />
- <arg name="fcu_url" value="$(arg fcu_url)" />
- <arg name="gcs_url" value="$(arg gcs_url)" />
- <arg name="tgt_system" value="$(arg tgt_system)" />
- <arg name="tgt_component" value="$(arg tgt_component)" />
- </include>
- </group>
+ <arg name="fcu_url" value="$(arg fcu_url)" />
+ <arg name="gcs_url" value="$(arg gcs_url)" />
+ <arg name="tgt_system" value="$(arg tgt_system)" />
+ <arg name="tgt_component" value="$(arg tgt_component)" />
+ </include>
</launch>