Browse Source

improve launch files

sbg
Thomas Gubler 10 years ago
parent
commit
1b0446ed41
  1. 11
      launch/gazebo_multicopter.launch
  2. 5
      launch/multicopter.launch

11
launch/gazebo_multicopter.launch

@ -1,13 +1,6 @@ @@ -1,13 +1,6 @@
<launch>
<include file="$(find mav_gazebo)/launch/vtol_empty_world_with_joy.launch" />
<group ns="px4_multicopter">
<node pkg="joy" name="joy_node" type="joy_node"/>
<node pkg="px4" name="manual_input" type="manual_input"/>
<node pkg="px4" name="commander" type="commander"/>
<node pkg="px4" name="mc_mixer" type="mc_mixer"/>
<node pkg="px4" name="attitude_estimator" type="attitude_estimator"/>
<node pkg="px4" name="mc_att_control" type="mc_att_control"/>
</group>
<include file="$(find mav_gazebo)/launch/vtol_empty_world_with_joy.launch" />
<include file="$(find px4)/launch/multicopter.launch" />
</launch>

5
launch/multicopter.launch

@ -7,6 +7,11 @@ @@ -7,6 +7,11 @@
<node pkg="px4" name="mc_mixer" type="mc_mixer"/>
<node pkg="px4" name="attitude_estimator" type="attitude_estimator"/>
<node pkg="px4" name="mc_att_control" type="mc_att_control"/>
<param name="MC_ROLL_P" type="double" value="6.0" />
<param name="MC_PITCH_P" type="double" value="6.0" />
<param name="MC_ROLLRATE_P" type="double" value="0.05" />
<param name="MC_PITCHRATE_P" type="double" value="0.05" />
</group>
</launch>

Loading…
Cancel
Save