forked from Archive/PX4-Autopilot
moved mavros to root node
This commit is contained in:
parent
5d8516b356
commit
c4b938fee6
|
@ -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,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>
|
||||
|
|
Loading…
Reference in New Issue